From e23a12a68914604dc98ec029304e90d98d229983 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sat, 21 Dec 2024 21:03:00 +0100 Subject: [PATCH] Use new spawner option for ros args (#577) Co-authored-by: Sai Kishor Kothakota --- example_11/bringup/launch/carlikebot.launch.py | 11 +++++++---- example_11/test/test_carlikebot_launch.py | 10 ++++++++++ .../bringup/launch/rrbot_namespace.launch.py | 16 ++++++++-------- example_2/bringup/launch/diffbot.launch.py | 11 +++++++---- 4 files changed, 32 insertions(+), 16 deletions(-) diff --git a/example_11/bringup/launch/carlikebot.launch.py b/example_11/bringup/launch/carlikebot.launch.py index 47c3c3327..13054a298 100644 --- a/example_11/bringup/launch/carlikebot.launch.py +++ b/example_11/bringup/launch/carlikebot.launch.py @@ -77,9 +77,6 @@ def generate_launch_description(): executable="ros2_control_node", parameters=[robot_controllers], output="both", - remappings=[ - ("/bicycle_steering_controller/tf_odometry", "/tf"), - ], condition=IfCondition(remap_odometry_tf), ) control_node = Node( @@ -114,7 +111,13 @@ def generate_launch_description(): robot_bicycle_controller_spawner = Node( package="controller_manager", executable="spawner", - arguments=["bicycle_steering_controller", "--param-file", robot_controllers], + arguments=[ + "bicycle_steering_controller", + "--param-file", + robot_controllers, + "--controller-ros-args", + "-r /bicycle_steering_controller/tf_odometry:=/tf", + ], ) # Delay rviz start after `joint_state_broadcaster` diff --git a/example_11/test/test_carlikebot_launch.py b/example_11/test/test_carlikebot_launch.py index 1afb4ff33..1b45ec0d8 100644 --- a/example_11/test/test_carlikebot_launch.py +++ b/example_11/test/test_carlikebot_launch.py @@ -37,6 +37,7 @@ from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource from launch_testing.actions import ReadyToTest +from launch_testing_ros import WaitForTopics # import launch_testing.markers import rclpy @@ -46,6 +47,8 @@ check_node_running, ) +from tf2_msgs.msg import TFMessage + # Executes the given launch file and checks if all nodes can be started @pytest.mark.rostest @@ -98,6 +101,13 @@ def test_check_if_msgs_published(self): ], ) + def test_remapped_topic(self): + # we don't want to implement a tf lookup here + # so just check if the unmapped topic is not published + old_topic = "/bicycle_steering_controller/tf_odometry" + wait_for_topics = WaitForTopics([(old_topic, TFMessage)]) + assert not wait_for_topics.wait(), f"Topic '{old_topic}' found, but should be remapped!" + # TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore # @launch_testing.post_shutdown_test() diff --git a/example_15/bringup/launch/rrbot_namespace.launch.py b/example_15/bringup/launch/rrbot_namespace.launch.py index 537bdb208..1544f3657 100644 --- a/example_15/bringup/launch/rrbot_namespace.launch.py +++ b/example_15/bringup/launch/rrbot_namespace.launch.py @@ -69,13 +69,6 @@ def generate_launch_description(): executable="ros2_control_node", namespace="/rrbot", parameters=[robot_description, robot_controllers], - remappings=[ - ( - # we use the remapping from a relative name to FQN /position_commands - "forward_position_controller/commands", - "/position_commands", - ), - ], output={ "stdout": "screen", "stderr": "screen", @@ -108,7 +101,14 @@ def generate_launch_description(): package="controller_manager", executable="spawner", namespace="rrbot", - arguments=["forward_position_controller", "--param-file", robot_controllers], + arguments=[ + "forward_position_controller", + "--param-file", + robot_controllers, + # we use the remapping from a relative name to FQN /position_commands + "--controller-ros-args", + "-r forward_position_controller/commands:=/position_commands", + ], ) robot_position_trajectory_controller_spawner = Node( diff --git a/example_2/bringup/launch/diffbot.launch.py b/example_2/bringup/launch/diffbot.launch.py index 1c345464f..797ea5fd8 100644 --- a/example_2/bringup/launch/diffbot.launch.py +++ b/example_2/bringup/launch/diffbot.launch.py @@ -75,9 +75,6 @@ def generate_launch_description(): executable="ros2_control_node", parameters=[robot_controllers], output="both", - remappings=[ - ("/diffbot_base_controller/cmd_vel", "/cmd_vel"), - ], ) robot_state_pub_node = Node( package="robot_state_publisher", @@ -103,7 +100,13 @@ def generate_launch_description(): robot_controller_spawner = Node( package="controller_manager", executable="spawner", - arguments=["diffbot_base_controller", "--param-file", robot_controllers], + arguments=[ + "diffbot_base_controller", + "--param-file", + robot_controllers, + "--controller-ros-args", + "-r /diffbot_base_controller/cmd_vel:=/cmd_vel", + ], ) # Delay rviz start after `joint_state_broadcaster`