@@ -366,6 +366,42 @@ def generate_dashboard_test_description():
366366 )
367367
368368
369+ def generate_mock_hardware_test_description (
370+ tf_prefix = "" ,
371+ initial_joint_controller = "scaled_joint_trajectory_controller" ,
372+ controller_spawner_timeout = TIMEOUT_WAIT_SERVICE_INITIAL ,
373+ use_mock_hardware = "false" ,
374+ ):
375+
376+ ur_type = LaunchConfiguration ("ur_type" )
377+
378+ launch_arguments = {
379+ "robot_ip" : "0.0.0.0" ,
380+ "ur_type" : ur_type ,
381+ "launch_rviz" : "false" ,
382+ "controller_spawner_timeout" : str (controller_spawner_timeout ),
383+ "initial_joint_controller" : initial_joint_controller ,
384+ "headless_mode" : "true" ,
385+ "launch_dashboard_client" : "true" ,
386+ "start_joint_controller" : "false" ,
387+ "use_mock_hardware" : use_mock_hardware ,
388+ "mock_sensor_commands" : use_mock_hardware ,
389+ }
390+ if tf_prefix :
391+ launch_arguments ["tf_prefix" ] = tf_prefix
392+
393+ robot_driver = IncludeLaunchDescription (
394+ PythonLaunchDescriptionSource (
395+ PathJoinSubstitution (
396+ [FindPackageShare ("ur_robot_driver" ), "launch" , "ur_control.launch.py" ]
397+ )
398+ ),
399+ launch_arguments = launch_arguments .items (),
400+ )
401+
402+ return LaunchDescription (_declare_launch_arguments () + [ReadyToTest (), robot_driver ])
403+
404+
369405def generate_driver_test_description (
370406 tf_prefix = "" ,
371407 initial_joint_controller = "scaled_joint_trajectory_controller" ,
0 commit comments