diff --git a/ur_robot_driver/launch/ur_control.launch.py b/ur_robot_driver/launch/ur_control.launch.py index 7b108f20b..461f15034 100644 --- a/ur_robot_driver/launch/ur_control.launch.py +++ b/ur_robot_driver/launch/ur_control.launch.py @@ -68,6 +68,8 @@ def launch_setup(): parameters=[ LaunchConfiguration("update_rate_config_file"), ParameterFile(controllers_file, allow_substs=True), + # We use the tf_prefix as substitution in there, so that's why we keep it as an + # argument for this launchfile ], output="screen", ) @@ -280,6 +282,15 @@ def generate_launch_description(): "publishes the description topic.", ) ) + declared_arguments.append( + DeclareLaunchArgument( + "tf_prefix", + default_value="", + description="tf_prefix of the joint names, useful for " + "multi-robot setup. If changed, also joint names in the controllers' configuration " + "have to be updated.", + ) + ) declared_arguments.append( DeclareLaunchArgument( "use_mock_hardware", diff --git a/ur_robot_driver/test/test_common.py b/ur_robot_driver/test/test_common.py index 435a20c37..4a0b2ad1b 100644 --- a/ur_robot_driver/test/test_common.py +++ b/ur_robot_driver/test/test_common.py @@ -307,23 +307,26 @@ def generate_driver_test_description( ): ur_type = LaunchConfiguration("ur_type") + launch_arguments = { + "robot_ip": "192.168.56.101", + "ur_type": ur_type, + "launch_rviz": "false", + "controller_spawner_timeout": str(controller_spawner_timeout), + "initial_joint_controller": "scaled_joint_trajectory_controller", + "headless_mode": "true", + "launch_dashboard_client": "false", + "start_joint_controller": "false", + } + if tf_prefix: + launch_arguments["tf_prefix"] = tf_prefix + robot_driver = IncludeLaunchDescription( PythonLaunchDescriptionSource( PathJoinSubstitution( [FindPackageShare("ur_robot_driver"), "launch", "ur_control.launch.py"] ) ), - launch_arguments={ - "robot_ip": "192.168.56.101", - "ur_type": ur_type, - "launch_rviz": "false", - "controller_spawner_timeout": str(controller_spawner_timeout), - "initial_joint_controller": "scaled_joint_trajectory_controller", - "headless_mode": "true", - "launch_dashboard_client": "false", - "start_joint_controller": "false", - "tf_prefix": tf_prefix, - }.items(), + launch_arguments=launch_arguments.items(), ) wait_dashboard_server = ExecuteProcess( cmd=[