diff --git a/ur_moveit_config/launch/ur_moveit.launch.py b/ur_moveit_config/launch/ur_moveit.launch.py index b1858d519..3ceb5558b 100644 --- a/ur_moveit_config/launch/ur_moveit.launch.py +++ b/ur_moveit_config/launch/ur_moveit.launch.py @@ -43,7 +43,6 @@ FindExecutable, LaunchConfiguration, PathJoinSubstitution, - OrSubstitution, ) @@ -51,7 +50,6 @@ def launch_setup(context, *args, **kwargs): # Initialize Arguments ur_type = LaunchConfiguration("ur_type") - use_fake_hardware = LaunchConfiguration("use_fake_hardware") safety_limits = LaunchConfiguration("safety_limits") safety_pos_margin = LaunchConfiguration("safety_pos_margin") safety_k_position = LaunchConfiguration("safety_k_position") @@ -179,9 +177,7 @@ def launch_setup(context, *args, **kwargs): # Trajectory Execution Configuration controllers_yaml = load_yaml("ur_moveit_config", "config/controllers.yaml") # the scaled_joint_trajectory_controller does not work on fake hardware - change_controllers = context.perform_substitution( - OrSubstitution(use_fake_hardware, use_sim_time) - ) + change_controllers = context.perform_substitution(use_sim_time) if change_controllers == "true": controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False controllers_yaml["joint_trajectory_controller"]["default"] = True @@ -287,13 +283,6 @@ def generate_launch_description(): choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20", "ur30"], ) ) - declared_arguments.append( - DeclareLaunchArgument( - "use_fake_hardware", - default_value="false", - description="Indicate whether robot is running with fake hardware mirroring command to its states.", - ) - ) declared_arguments.append( DeclareLaunchArgument( "safety_limits",