Skip to content

Commit e23a12a

Browse files
Use new spawner option for ros args (#577)
Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com>
1 parent 1b1c2e5 commit e23a12a

File tree

4 files changed

+32
-16
lines changed

4 files changed

+32
-16
lines changed

example_11/bringup/launch/carlikebot.launch.py

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -77,9 +77,6 @@ def generate_launch_description():
7777
executable="ros2_control_node",
7878
parameters=[robot_controllers],
7979
output="both",
80-
remappings=[
81-
("/bicycle_steering_controller/tf_odometry", "/tf"),
82-
],
8380
condition=IfCondition(remap_odometry_tf),
8481
)
8582
control_node = Node(
@@ -114,7 +111,13 @@ def generate_launch_description():
114111
robot_bicycle_controller_spawner = Node(
115112
package="controller_manager",
116113
executable="spawner",
117-
arguments=["bicycle_steering_controller", "--param-file", robot_controllers],
114+
arguments=[
115+
"bicycle_steering_controller",
116+
"--param-file",
117+
robot_controllers,
118+
"--controller-ros-args",
119+
"-r /bicycle_steering_controller/tf_odometry:=/tf",
120+
],
118121
)
119122

120123
# Delay rviz start after `joint_state_broadcaster`

example_11/test/test_carlikebot_launch.py

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737
from launch.actions import IncludeLaunchDescription
3838
from launch.launch_description_sources import PythonLaunchDescriptionSource
3939
from launch_testing.actions import ReadyToTest
40+
from launch_testing_ros import WaitForTopics
4041

4142
# import launch_testing.markers
4243
import rclpy
@@ -46,6 +47,8 @@
4647
check_node_running,
4748
)
4849

50+
from tf2_msgs.msg import TFMessage
51+
4952

5053
# Executes the given launch file and checks if all nodes can be started
5154
@pytest.mark.rostest
@@ -98,6 +101,13 @@ def test_check_if_msgs_published(self):
98101
],
99102
)
100103

104+
def test_remapped_topic(self):
105+
# we don't want to implement a tf lookup here
106+
# so just check if the unmapped topic is not published
107+
old_topic = "/bicycle_steering_controller/tf_odometry"
108+
wait_for_topics = WaitForTopics([(old_topic, TFMessage)])
109+
assert not wait_for_topics.wait(), f"Topic '{old_topic}' found, but should be remapped!"
110+
101111

102112
# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
103113
# @launch_testing.post_shutdown_test()

example_15/bringup/launch/rrbot_namespace.launch.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -69,13 +69,6 @@ def generate_launch_description():
6969
executable="ros2_control_node",
7070
namespace="/rrbot",
7171
parameters=[robot_description, robot_controllers],
72-
remappings=[
73-
(
74-
# we use the remapping from a relative name to FQN /position_commands
75-
"forward_position_controller/commands",
76-
"/position_commands",
77-
),
78-
],
7972
output={
8073
"stdout": "screen",
8174
"stderr": "screen",
@@ -108,7 +101,14 @@ def generate_launch_description():
108101
package="controller_manager",
109102
executable="spawner",
110103
namespace="rrbot",
111-
arguments=["forward_position_controller", "--param-file", robot_controllers],
104+
arguments=[
105+
"forward_position_controller",
106+
"--param-file",
107+
robot_controllers,
108+
# we use the remapping from a relative name to FQN /position_commands
109+
"--controller-ros-args",
110+
"-r forward_position_controller/commands:=/position_commands",
111+
],
112112
)
113113

114114
robot_position_trajectory_controller_spawner = Node(

example_2/bringup/launch/diffbot.launch.py

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -75,9 +75,6 @@ def generate_launch_description():
7575
executable="ros2_control_node",
7676
parameters=[robot_controllers],
7777
output="both",
78-
remappings=[
79-
("/diffbot_base_controller/cmd_vel", "/cmd_vel"),
80-
],
8178
)
8279
robot_state_pub_node = Node(
8380
package="robot_state_publisher",
@@ -103,7 +100,13 @@ def generate_launch_description():
103100
robot_controller_spawner = Node(
104101
package="controller_manager",
105102
executable="spawner",
106-
arguments=["diffbot_base_controller", "--param-file", robot_controllers],
103+
arguments=[
104+
"diffbot_base_controller",
105+
"--param-file",
106+
robot_controllers,
107+
"--controller-ros-args",
108+
"-r /diffbot_base_controller/cmd_vel:=/cmd_vel",
109+
],
107110
)
108111

109112
# Delay rviz start after `joint_state_broadcaster`

0 commit comments

Comments
 (0)