Skip to content

Commit

Permalink
Use new spawner option for ros args (#577)
Browse files Browse the repository at this point in the history
Co-authored-by: Sai Kishor Kothakota <[email protected]>
  • Loading branch information
christophfroehlich and saikishor authored Dec 21, 2024
1 parent 1b1c2e5 commit e23a12a
Show file tree
Hide file tree
Showing 4 changed files with 32 additions and 16 deletions.
11 changes: 7 additions & 4 deletions example_11/bringup/launch/carlikebot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down Expand Up @@ -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`
Expand Down
10 changes: 10 additions & 0 deletions example_11/test/test_carlikebot_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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()
Expand Down
16 changes: 8 additions & 8 deletions example_15/bringup/launch/rrbot_namespace.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand Down Expand Up @@ -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(
Expand Down
11 changes: 7 additions & 4 deletions example_2/bringup/launch/diffbot.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand All @@ -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`
Expand Down

0 comments on commit e23a12a

Please sign in to comment.