diff --git a/ur_moveit_config/config/controllers.yaml b/ur_moveit_config/config/controllers.yaml index 784ebd315..afafbb68a 100644 --- a/ur_moveit_config/config/controllers.yaml +++ b/ur_moveit_config/config/controllers.yaml @@ -2,11 +2,10 @@ controller_names: - scaled_joint_trajectory_controller - joint_trajectory_controller - scaled_joint_trajectory_controller: action_ns: follow_joint_trajectory type: FollowJointTrajectory - default: true + default: false joints: - shoulder_pan_joint - shoulder_lift_joint diff --git a/ur_moveit_config/launch/ur_moveit.launch.py b/ur_moveit_config/launch/ur_moveit.launch.py index 256dc1aed..b401a6f0d 100644 --- a/ur_moveit_config/launch/ur_moveit.launch.py +++ b/ur_moveit_config/launch/ur_moveit.launch.py @@ -44,13 +44,8 @@ def launch_setup(context, *args, **kwargs): # Initialize Arguments ur_type = LaunchConfiguration("ur_type") - use_mock_hardware = LaunchConfiguration("use_mock_hardware") - safety_limits = LaunchConfiguration("safety_limits") - safety_pos_margin = LaunchConfiguration("safety_pos_margin") - safety_k_position = LaunchConfiguration("safety_k_position") + initial_joint_controller = LaunchConfiguration("initial_joint_controller") # General arguments - description_package = LaunchConfiguration("description_package") - description_file = LaunchConfiguration("description_file") moveit_config_package = LaunchConfiguration("moveit_config_package") moveit_joint_limits_file = LaunchConfiguration("moveit_joint_limits_file") moveit_config_file = LaunchConfiguration("moveit_config_file") @@ -59,68 +54,6 @@ def launch_setup(context, *args, **kwargs): use_sim_time = LaunchConfiguration("use_sim_time") launch_rviz = LaunchConfiguration("launch_rviz") launch_servo = LaunchConfiguration("launch_servo") - - joint_limit_params = PathJoinSubstitution( - [FindPackageShare(description_package), "config", ur_type, "joint_limits.yaml"] - ) - kinematics_params = PathJoinSubstitution( - [FindPackageShare(description_package), "config", ur_type, "default_kinematics.yaml"] - ) - physical_params = PathJoinSubstitution( - [FindPackageShare(description_package), "config", ur_type, "physical_parameters.yaml"] - ) - visual_params = PathJoinSubstitution( - [FindPackageShare(description_package), "config", ur_type, "visual_parameters.yaml"] - ) - - robot_description_content = Command( - [ - PathJoinSubstitution([FindExecutable(name="xacro")]), - " ", - PathJoinSubstitution([FindPackageShare(description_package), "urdf", description_file]), - " ", - "robot_ip:=xxx.yyy.zzz.www", - " ", - "joint_limit_params:=", - joint_limit_params, - " ", - "kinematics_params:=", - kinematics_params, - " ", - "physical_params:=", - physical_params, - " ", - "visual_params:=", - visual_params, - " ", - "safety_limits:=", - safety_limits, - " ", - "safety_pos_margin:=", - safety_pos_margin, - " ", - "safety_k_position:=", - safety_k_position, - " ", - "name:=", - "ur", - " ", - "ur_type:=", - ur_type, - " ", - "script_filename:=ros_control.urscript", - " ", - "input_recipe_filename:=rtde_input_recipe.txt", - " ", - "output_recipe_filename:=rtde_output_recipe.txt", - " ", - "prefix:=", - prefix, - " ", - ] - ) - robot_description = {"robot_description": robot_description_content} - # MoveIt Configuration robot_description_semantic_content = Command( [ @@ -131,9 +64,7 @@ def launch_setup(context, *args, **kwargs): ), " ", "name:=", - # Also ur_type parameter could be used but then the planning group names in yaml - # configs has to be updated! - "ur", + ur_type, " ", "prefix:=", prefix, @@ -166,11 +97,8 @@ 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 mock hardware - change_controllers = context.perform_substitution(use_mock_hardware) - if change_controllers == "true": - controllers_yaml["scaled_joint_trajectory_controller"]["default"] = False - controllers_yaml["joint_trajectory_controller"]["default"] = True + initial_controller = context.perform_substitution(initial_joint_controller) + controllers_yaml[initial_controller]["default"] = True moveit_controllers = { "moveit_simple_controller_manager": controllers_yaml, @@ -183,7 +111,6 @@ def launch_setup(context, *args, **kwargs): "trajectory_execution.allowed_goal_duration_margin": 0.5, "trajectory_execution.allowed_start_tolerance": 0.01, } - planning_scene_monitor_parameters = { "publish_planning_scene": True, "publish_geometry_updates": True, @@ -202,7 +129,6 @@ def launch_setup(context, *args, **kwargs): executable="move_group", output="screen", parameters=[ - robot_description, robot_description_semantic, robot_description_kinematics, robot_description_planning, @@ -227,7 +153,6 @@ def launch_setup(context, *args, **kwargs): output="log", arguments=["-d", rviz_config_file], parameters=[ - robot_description, robot_description_semantic, ompl_planning_pipeline_config, robot_description_kinematics, @@ -245,7 +170,6 @@ def launch_setup(context, *args, **kwargs): executable="servo_node_main", parameters=[ servo_params, - robot_description, robot_description_semantic, ], output="screen", @@ -258,7 +182,7 @@ def launch_setup(context, *args, **kwargs): def generate_launch_description(): declared_arguments = [] - # UR specific arguments + # UR specific arguments. declared_arguments.append( DeclareLaunchArgument( "ur_type", @@ -268,9 +192,10 @@ def generate_launch_description(): ) declared_arguments.append( DeclareLaunchArgument( - "use_mock_hardware", - default_value="false", - description="Indicate whether robot is running with mock hardware mirroring command to its states.", + "initial_joint_controller", + default_value="scaled_joint_trajectory_controller", + description="Initial controller used by MoveIt!.", + choices=["scaled_joint_trajectory_controller", "joint_trajectory_controller"], ) ) declared_arguments.append( diff --git a/ur_moveit_config/srdf/ur.srdf.xacro b/ur_moveit_config/srdf/ur.srdf.xacro index 0ae2cca27..80bcedddf 100644 --- a/ur_moveit_config/srdf/ur.srdf.xacro +++ b/ur_moveit_config/srdf/ur.srdf.xacro @@ -1,13 +1,11 @@ - - - + diff --git a/ur_moveit_config/srdf/ur_macro.srdf.xacro b/ur_moveit_config/srdf/ur_macro.srdf.xacro index 04554f33c..8c2f319b9 100644 --- a/ur_moveit_config/srdf/ur_macro.srdf.xacro +++ b/ur_moveit_config/srdf/ur_macro.srdf.xacro @@ -4,17 +4,17 @@ This is a format for representing semantic information about the robot structure. A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined --> - + - + - + @@ -22,7 +22,7 @@ - + @@ -30,7 +30,7 @@ - + diff --git a/ur_robot_driver/doc/usage.rst b/ur_robot_driver/doc/usage.rst index 48c59c745..fa02d8c68 100644 --- a/ur_robot_driver/doc/usage.rst +++ b/ur_robot_driver/doc/usage.rst @@ -73,7 +73,7 @@ outside of this driver's scope. * - mode - available controllers * - mock_hardware - - :raw-html-m2r:`
  • joint_trajectory_controller
  • forward_velocity_controller
  • forward_position_controller
` + - :raw-html-m2r:`
  • joint_trajectory_controller
  • scaled_joint_trajectory_controller
  • forward_velocity_controller
  • forward_position_controller
` * - real hardware / URSim - :raw-html-m2r:`
  • joint_trajectory_controller
  • scaled_joint_trajectory_controller
  • forward_velocity_controller
  • forward_position_controller
` @@ -194,14 +194,18 @@ robot as explained `here `_ pending to fix that. Until this is merged and released, you'll have to fallback to the ``joint_trajectory_controller`` by passing ``initial_controller:=joint_trajectory_controller`` to the driver's startup. Also, you'll have to tell MoveIt! that you're using mock_hardware as it then has to map to the other controller: +To test the driver on mock hardware with the example MoveIt-setup, first start the driver as described +`above <#start-hardware-simulator-or-mockup>`_. .. code-block:: - ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=yyy.yyy.yyy.yyy use_mock_hardware:=true launch_rviz:=false initial_joint_controller:=joint_trajectory_controller + ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=yyy.yyy.yyy.yyy use_mock_hardware:=true launch_rviz:=false # and in another shell - ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur5e launch_rviz:=true use_mock_hardware:=true + ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur5e launch_rviz:=true + +Now you should be able to use the MoveIt Plugin in rviz2 to plan and execute trajectories with the +robot as explained `in the MoveIt! documentation `_. + Robot frames ------------