Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update all demos using the description from topic rather than the parameter #456

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion example_1/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
2 changes: 1 addition & 1 deletion example_10/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
8 changes: 1 addition & 7 deletions example_11/bringup/launch/carlikebot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,6 @@ def generate_launch_description():
parameters=[robot_controllers],
output="both",
remappings=[
("~/robot_description", "/robot_description"),
("/bicycle_steering_controller/tf_odometry", "/tf"),
],
condition=IfCondition(remap_odometry_tf),
Expand All @@ -88,19 +87,14 @@ def generate_launch_description():
executable="ros2_control_node",
parameters=[robot_controllers],
output="both",
remappings=[
("~/robot_description", "/robot_description"),
],
remappings=[],
condition=UnlessCondition(remap_odometry_tf),
)
robot_state_pub_bicycle_node = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
output="both",
parameters=[robot_description],
remappings=[
("~/robot_description", "/robot_description"),
],
)
rviz_node = Node(
package="rviz2",
Expand Down
2 changes: 1 addition & 1 deletion example_12/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
28 changes: 15 additions & 13 deletions example_14/hardware/rrbot_actuator_without_feedback.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,21 +183,23 @@ hardware_interface::return_type RRBotActuatorWithoutFeedback::read(
hardware_interface::return_type ros2_control_demo_example_14::RRBotActuatorWithoutFeedback::write(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
// START: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(
rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Writing command: %f", hw_joint_command_);

// Simulate sending commands to the hardware
std::ostringstream data;
data << hw_joint_command_;
RCLCPP_INFO(
rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Sending data command: %s",
data.str().c_str());
send(sock_, data.str().c_str(), strlen(data.str().c_str()), 0);
if (std::isfinite(hw_joint_command_))
{
// START: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(
rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Writing command: %f", hw_joint_command_);

RCLCPP_INFO(rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Joints successfully written!");
// END: This part here is for exemplary purposes - Please do not copy to your production code
// Simulate sending commands to the hardware
std::ostringstream data;
data << hw_joint_command_;
RCLCPP_INFO(
rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Sending data command: %s",
data.str().c_str());
send(sock_, data.str().c_str(), strlen(data.str().c_str()), 0);

RCLCPP_INFO(rclcpp::get_logger("RRBotActuatorWithoutFeedback"), "Joints successfully written!");
// END: This part here is for exemplary purposes - Please do not copy to your production code
}
return hardware_interface::return_type::OK;
}

Expand Down
2 changes: 1 addition & 1 deletion example_2/bringup/launch/diffbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
2 changes: 1 addition & 1 deletion example_6/bringup/launch/rrbot_modular_actuators.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
2 changes: 1 addition & 1 deletion example_7/bringup/launch/r6bot_controller.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
remappings=[
(
"/forward_position_controller/commands",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
2 changes: 1 addition & 1 deletion example_9/bringup/launch/rrbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ def generate_launch_description():
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_description, robot_controllers],
parameters=[robot_controllers],
output="both",
)
robot_state_pub_node = Node(
Expand Down
Loading