moveit2: MoveItConfigsBuilder with UR robot is not working

Description

I am trying to adapt MoveItConfigsBuilder to UR3e robot while using Pilz Industrial Motion Planner. The MoveItConfigsBuilder expects certain files inside the config folder of robot_moveit_config package. Unfortunately, the package structure is different in the case of UR robot. Below are the two important packages inside /opt/ros/humble/share folder:

├── ur_description
│   ├── cmake
│   ├── config
│   │   ├── initial_positions.yaml
│   │   └── ur3e
│   │       ├── default_kinematics.yaml
│   │       ├── joint_limits.yaml
│   │       ├── physical_parameters.yaml
│   │       └── visual_parameters.yaml
│   ├── environment
│   ├── launch
│   ├── meshes
│   ├── rviz
│   └── urdf
│       ├── inc
│       │   ├── ur_common.xacro
│       │   └── ur_transmissions.xacro
│       ├── ur_macro.xacro
│       ├── ur.ros2_control.xacro
│       └── ur.urdf.xacro
├── ur_moveit_config
│   ├── cmake
│   ├── config
│   │   ├── controllers.yaml
│   │   ├── kinematics.yaml
│   │   ├── ompl_planning.yaml
│   │   └── ur_servo.yaml
│   ├── environment
│   ├── launch
│   │   └── ur_moveit.launch.py
│   ├── local_setup.bash
│   ├── package.xml
│   ├── rviz
│   │   └── view_robot.rviz
│   └── srdf
│       ├── ur_macro.srdf.xacro
│       └── ur.srdf.xacro

Below is a snippet from my launch file (ur_moveit.launch.py):

    robot_name = "ur3e"
    moveit_config = (
        MoveItConfigsBuilder(robot_name="ur3e")
        .robot_description(file_path=get_package_share_directory("ur_description") + "/urdf/ur.urdf.xacro", mappings={"name": robot_name, "ur_type": robot_name})
        .robot_description_semantic(file_path=get_package_share_directory("ur_moveit_config") + "/srdf/ur.srdf.xacro", mappings={"name": robot_name})
        .trajectory_execution(file_path=get_package_share_directory("ur_moveit_config") + "/config/controllers.yaml")
        .planning_pipelines(pipelines=["pilz_industrial_motion_planner"])
        .to_moveit_configs()
    )

Your environment

  • ROS Distro: Humble
  • OS Version: Ubuntu 22.04
  • Source or Binary build: Source (humble branch)

Steps to reproduce

$ ros2 launch ur_robot_driver ur3e.launch.py robot_ip:=yyy.yyy.yyy.yyy use_fake_hardware:=true launch_rviz:=false initial_joint_controller:=scaled_joint_trajectory_controller
$ ros2 launch hello_moveit ur_moveit.launch.py ur_type:=ur3e launch_rviz:=true

Actual behaviour

Upon running my ur_moveit.launch.py, it can not find the package as shown below:

$ ros2 launch hello_moveit ur_moveit.launch.py ur_type:=ur3e launch_rviz:=true
[INFO] [launch]: All log files can be found below /home/user/.ros/log/2023-10-25-12-29-06-950816-dell-127409
[INFO] [launch]: Default logging verbosity is set to INFO
[ERROR] [launch]: Caught exception in launch (see debug for traceback): Caught exception when trying to load file of format [py]: "package 'ur3e_moveit_config' not found, searching: ['/home/user/ws_moveit2_humble/install/pilz_industrial_motion_planner_testutils', '/home/user/ws_moveit2_humble/install/moveit_runtime', '/home/user/ws_moveit2_humble/install/moveit2_tutorials', '/home/user/ws_moveit2_humble/install/moveit', '/home/user/ws_moveit2_humble/install/moveit_planners', '/home/user/ws_moveit2_humble/install/pilz_industrial_motion_planner', '/home/user/ws_moveit2_humble/install/hello_moveit', '/home/user/ws_moveit2_humble/install/moveit_visual_tools', ... ... ...
'/home/user/ws_moveit2_humble/install/moveit_resources_prbt_support', '/home/user/ws_moveit2_humble/install/moveit_resources', '/home/user/ws_moveit2_humble/install/moveit_resources_pr2_description', '/home/user/ws_moveit2_humble/install/moveit_resources_panda_moveit_config', '/home/user/ws_moveit2_humble/install/moveit_resources_panda_description', '/home/user/ws_moveit2_humble/install/moveit_resources_fanuc_moveit_config', '/home/user/ws_moveit2_humble/install/moveit_resources_fanuc_description', '/home/user/ws_moveit2_humble/install/moveit_common', '/home/user/ws_moveit2_humble/install/launch_param_builder', '/opt/ros/humble']"

Workaround

I copied pilz_industrial_motion_planner_planning.yaml and placed inside ur_moveit_config. Later, I modified my launch file with the following content:

    pilz_planning_pipeline_config = {
        "move_group": {
            "planning_plugin": "pilz_industrial_motion_planner/CommandPlanner",
            "request_adapters": """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints default_planner_request_adapters/SetMaxCartesianEndEffectorSpeed""",
            "capabilities" : "pilz_industrial_motion_planner/MoveGroupSequenceAction pilz_industrial_motion_planner/MoveGroupSequenceService",
        }
    }
    pilz_planning_yaml = load_yaml("ur_moveit_config", "config/pilz_industrial_motion_planner_planning.yaml")
    pilz_planning_pipeline_config["move_group"].update(pilz_planning_yaml)

Unfortunately, this didn’t work either and showed the following error:

[rviz2-2] [INFO] [1698204681.211248409] [move_group_interface]: Planning request accepted
[move_group-1] [INFO] [1698204681.211253101] [moveit_move_group_default_capabilities.move_action_capability]: executing..
[move_group-1] [INFO] [1698204681.218459214] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[move_group-1] [INFO] [1698204681.218480233] [moveit_move_group_capabilities_base.move_group_capability]: Using planning pipeline 'move_group'
[move_group-1] [ERROR] [1698204681.218741296] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Path Constraints': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[rviz2-2] [INFO] [1698204681.219526289] [move_group_interface]: Planning request aborted
Complete logs can be seen here
$ ros2 launch hello_moveit ur_moveit.launch.py ur_type:=ur3e launch_rviz:=true
[INFO] [launch]: All log files can be found below /home/user/.ros/log/2023-10-25-12-31-03-079419-dell-136352
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [move_group-1]: process started with pid [136359]
[INFO] [rviz2-2]: process started with pid [136361]
[INFO] [servo_node_main-3]: process started with pid [136363]
[rviz2-2] Warning: Ignoring XDG_SESSION_TYPE=wayland on Gnome. Use QT_QPA_PLATFORM=wayland to run on Wayland anyway.
[move_group-1] [WARN] [1698204663.740232331] [move_group.move_group]: Falling back to using the the move_group node namespace (deprecated behavior).
[move_group-1] [INFO] [1698204663.743813478] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.00346763 seconds
[move_group-1] [INFO] [1698204663.743837428] [moveit_robot_model.robot_model]: Loading robot model 'ur'...
[move_group-1] [INFO] [1698204663.743846343] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[servo_node_main-3] [WARN] [1698204663.753605354] [moveit_servo.servo_node]: Intra-process communication is disabled, consider enabling it by adding: 
[servo_node_main-3] extra_arguments=[{'use_intra_process_comms' : True}]
[servo_node_main-3] to the Servo composable node in the launch file
[servo_node_main-3] [INFO] [1698204663.776117685] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.00596751 seconds
[servo_node_main-3] [INFO] [1698204663.776157167] [moveit_robot_model.robot_model]: Loading robot model 'ur'...
[servo_node_main-3] [INFO] [1698204663.776168789] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[servo_node_main-3] [WARN] [1698204663.787195558] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!
[move_group-1] [INFO] [1698204663.807739843] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Publishing maintained planning scene on 'monitored_planning_scene'
[move_group-1] [INFO] [1698204663.807909254] [moveit.ros_planning_interface.moveit_cpp]: Listening to 'joint_states' for joint states
[move_group-1] [INFO] [1698204663.808425356] [moveit_ros.current_state_monitor]: Listening to joint states on topic 'joint_states'
[move_group-1] [INFO] [1698204663.808649697] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/attached_collision_object' for attached collision objects
[move_group-1] [INFO] [1698204663.808660021] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting planning scene monitor
[move_group-1] [INFO] [1698204663.808798033] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/planning_scene'
[move_group-1] [INFO] [1698204663.808804789] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting world geometry update monitor for collision objects, attached objects, octomap updates.
[move_group-1] [INFO] [1698204663.808959016] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to 'collision_object'
[move_group-1] [INFO] [1698204663.809110476] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to 'planning_scene_world' for planning scene world geometry
[move_group-1] [WARN] [1698204663.809811016] [moveit.ros.occupancy_map_monitor.middleware_handle]: Resolution not specified for Octomap. Assuming resolution = 0.1 instead
[move_group-1] [ERROR] [1698204663.809823301] [moveit.ros.occupancy_map_monitor.middleware_handle]: No 3D sensor plugin(s) defined for octomap updates
[move_group-1] [INFO] [1698204663.811767781] [moveit.ros_planning_interface.moveit_cpp]: Loading planning pipeline 'move_group'
[move_group-1] [INFO] [1698204663.814858862] [moveit.pilz_industrial_motion_planner.joint_limits_aggregator]: Reading limits from namespace robot_description_planning
[move_group-1] [ERROR] [1698204663.816548953] [move_group]: Parameter 'robot_description_planning.cartesian_limits.max_trans_vel', is not set in the config file.
[move_group-1] [ERROR] [1698204663.816618548] [move_group]: Parameter 'robot_description_planning.cartesian_limits.max_trans_acc', is not set in the config file.
[move_group-1] [ERROR] [1698204663.816654111] [move_group]: Parameter 'robot_description_planning.cartesian_limits.max_trans_dec', is not set in the config file.
[move_group-1] [ERROR] [1698204663.816683910] [move_group]: Parameter 'robot_description_planning.cartesian_limits.max_rot_vel', is not set in the config file.
[move_group-1] [INFO] [1698204663.817202099] [moveit.pilz_industrial_motion_planner]: Available plugins: pilz_industrial_motion_planner/PlanningContextLoaderCIRC pilz_industrial_motion_planner/PlanningContextLoaderLIN pilz_industrial_motion_planner/PlanningContextLoaderPTP 
[move_group-1] [INFO] [1698204663.817209456] [moveit.pilz_industrial_motion_planner]: About to load: pilz_industrial_motion_planner/PlanningContextLoaderCIRC
[move_group-1] [INFO] [1698204663.818030357] [moveit.pilz_industrial_motion_planner]: Registered Algorithm [CIRC]
[move_group-1] [INFO] [1698204663.818041642] [moveit.pilz_industrial_motion_planner]: About to load: pilz_industrial_motion_planner/PlanningContextLoaderLIN
[move_group-1] [INFO] [1698204663.818573317] [moveit.pilz_industrial_motion_planner]: Registered Algorithm [LIN]
[move_group-1] [INFO] [1698204663.818580970] [moveit.pilz_industrial_motion_planner]: About to load: pilz_industrial_motion_planner/PlanningContextLoaderPTP
[move_group-1] [INFO] [1698204663.819023261] [moveit.pilz_industrial_motion_planner]: Registered Algorithm [PTP]
[move_group-1] [INFO] [1698204663.819038478] [moveit.ros_planning.planning_pipeline]: Using planning interface 'Pilz Industrial Motion Planner'
[move_group-1] [INFO] [1698204663.821985780] [moveit_ros.fix_workspace_bounds]: Param 'move_group.default_workspace_bounds' was not set. Using default value: 10.000000
[move_group-1] [INFO] [1698204663.822014309] [moveit_ros.fix_start_state_bounds]: Param 'move_group.start_state_max_bounds_error' was not set. Using default value: 0.050000
[move_group-1] [INFO] [1698204663.822018407] [moveit_ros.fix_start_state_bounds]: Param 'move_group.start_state_max_dt' was not set. Using default value: 0.500000
[move_group-1] [INFO] [1698204663.822026150] [moveit_ros.fix_start_state_collision]: Param 'move_group.start_state_max_dt' was not set. Using default value: 0.500000
[move_group-1] [INFO] [1698204663.822029953] [moveit_ros.fix_start_state_collision]: Param 'move_group.jiggle_fraction' was not set. Using default value: 0.020000
[move_group-1] [INFO] [1698204663.822038398] [moveit_ros.fix_start_state_collision]: Param 'move_group.max_sampling_attempts' was not set. Using default value: 100
[move_group-1] [INFO] [1698204663.822049617] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Workspace Bounds'
[move_group-1] [INFO] [1698204663.822054397] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Start State Bounds'
[move_group-1] [INFO] [1698204663.822057401] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Start State In Collision'
[move_group-1] [INFO] [1698204663.822070078] [moveit.ros_planning.planning_pipeline]: Using planning request adapter 'Fix Start State Path Constraints'
[servo_node_main-3] [INFO] [1698204663.818700110] [moveit_ros.current_state_monitor]: Listening to joint states on topic '/joint_states'
[servo_node_main-3] [INFO] [1698204663.821595328] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/attached_collision_object' for attached collision objects
[servo_node_main-3] [INFO] [1698204663.821606916] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting planning scene monitor
[servo_node_main-3] [INFO] [1698204663.822387639] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/planning_scene'
[servo_node_main-3] [INFO] [1698204663.822762995] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Publishing maintained planning scene on '/servo_node/publish_planning_scene'
[servo_node_main-3] [WARN] [1698204663.835622844] [moveit_servo.servo_calcs]: No kinematics solver instantiated for group 'ur_manipulator'. Will use inverse Jacobian for servo calculations instead.
[servo_node_main-3] [WARN] [1698204663.835653766] [moveit_servo.collision_check]: Collision check rate is low, increase it in yaml file if CPU allows
[move_group-1] [INFO] [1698204663.836766528] [moveit.plugins.moveit_simple_controller_manager]: Added FollowJointTrajectory controller for scaled_joint_trajectory_controller
[move_group-1] [INFO] [1698204663.837786098] [moveit.plugins.moveit_simple_controller_manager]: Added FollowJointTrajectory controller for joint_trajectory_controller
[move_group-1] [INFO] [1698204663.837897433] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-1] [INFO] [1698204663.837925654] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-1] [INFO] [1698204663.838160261] [moveit_ros.trajectory_execution_manager]: Trajectory execution is not managing controllers
[move_group-1] [INFO] [1698204663.838172099] [move_group.move_group]: MoveGroup debug mode is ON
[move_group-1] [INFO] [1698204663.850412074] [move_group.move_group]: 
[move_group-1] 
[move_group-1] ********************************************************
[move_group-1] * MoveGroup using: 
[move_group-1] *     - ApplyPlanningSceneService
[move_group-1] *     - ClearOctomapService
[move_group-1] *     - CartesianPathService
[move_group-1] *     - ExecuteTrajectoryAction
[move_group-1] *     - GetPlanningSceneService
[move_group-1] *     - KinematicsService
[move_group-1] *     - MoveAction
[move_group-1] *     - MotionPlanService
[move_group-1] *     - QueryPlannersService
[move_group-1] *     - StateValidationService
[move_group-1] ********************************************************
[move_group-1] 
[move_group-1] [INFO] [1698204663.850452176] [moveit_move_group_capabilities_base.move_group_context]: MoveGroup context using planning plugin pilz_industrial_motion_planner/CommandPlanner
[move_group-1] [INFO] [1698204663.850458386] [moveit_move_group_capabilities_base.move_group_context]: MoveGroup context initialization complete
[move_group-1] Loading 'move_group/ApplyPlanningSceneService'...
[move_group-1] Loading 'move_group/ClearOctomapService'...
[move_group-1] Loading 'move_group/MoveGroupCartesianPathService'...
[move_group-1] Loading 'move_group/MoveGroupExecuteTrajectoryAction'...
[move_group-1] Loading 'move_group/MoveGroupGetPlanningSceneService'...
[move_group-1] Loading 'move_group/MoveGroupKinematicsService'...
[move_group-1] Loading 'move_group/MoveGroupMoveAction'...
[move_group-1] Loading 'move_group/MoveGroupPlanService'...
[move_group-1] Loading 'move_group/MoveGroupQueryPlannersService'...
[move_group-1] Loading 'move_group/MoveGroupStateValidationService'...
[move_group-1] 
[move_group-1] You can start planning now!
[move_group-1] 
[rviz2-2] [INFO] [1698204663.875346959] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-2] [INFO] [1698204663.875428556] [rviz2]: OpenGl version: 4.5 (GLSL 4.5)
[rviz2-2] [INFO] [1698204663.917206181] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-2] Warning: class_loader.impl: SEVERE WARNING!!! A namespace collision has occurred with plugin factory for class rviz_default_plugins::displays::InteractiveMarkerDisplay. New factory will OVERWRITE existing one. This situation occurs when libraries containing plugins are directly linked against an executable (the one running right now generating this message). Please separate plugins out into their own library or just don't link against the library and use either class_loader::ClassLoader/MultiLibraryClassLoader to open.
[rviz2-2]          at line 253 in /opt/ros/humble/include/class_loader/class_loader/class_loader_core.hpp
[rviz2-2] [ERROR] [1698204666.998360006] [moveit_ros_visualization.motion_planning_frame]: Action server: /recognize_objects not available
[rviz2-2] [INFO] [1698204667.026269812] [moveit_ros_visualization.motion_planning_frame]: MoveGroup namespace changed: / -> . Reloading params.
[rviz2-2] [INFO] [1698204667.189951918] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.00340269 seconds
[rviz2-2] [INFO] [1698204667.189995775] [moveit_robot_model.robot_model]: Loading robot model 'ur'...
[rviz2-2] [INFO] [1698204667.190007204] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[rviz2-2] [INFO] [1698204667.273724023] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Starting planning scene monitor
[rviz2-2] [INFO] [1698204667.274830555] [moveit_ros.planning_scene_monitor.planning_scene_monitor]: Listening to '/monitored_planning_scene'
[rviz2-2] [INFO] [1698204667.427771240] [interactive_marker_display_94235211110048]: Connected on namespace: /rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic
[rviz2-2] [INFO] [1698204667.431146817] [moveit_ros_visualization.motion_planning_frame]: group ur_manipulator
[rviz2-2] [INFO] [1698204667.431161566] [moveit_ros_visualization.motion_planning_frame]: Constructing new MoveGroup connection for group 'ur_manipulator' in namespace ''
[rviz2-2] [INFO] [1698204667.438411466] [move_group_interface]: Ready to take commands for planning group ur_manipulator.
[rviz2-2] [INFO] [1698204667.531768184] [interactive_marker_display_94235211110048]: Sending request for interactive markers
[rviz2-2] [INFO] [1698204667.587595934] [interactive_marker_display_94235211110048]: Service response received for initialization
[rviz2-2] [INFO] [1698204681.210314494] [move_group_interface]: MoveGroup action client/server ready
[move_group-1] [INFO] [1698204681.211076149] [moveit_move_group_default_capabilities.move_action_capability]: Received request
[rviz2-2] [INFO] [1698204681.211248409] [move_group_interface]: Planning request accepted
[move_group-1] [INFO] [1698204681.211253101] [moveit_move_group_default_capabilities.move_action_capability]: executing..
[move_group-1] [INFO] [1698204681.218459214] [moveit_move_group_default_capabilities.move_action_capability]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[move_group-1] [INFO] [1698204681.218480233] [moveit_move_group_capabilities_base.move_group_capability]: Using planning pipeline 'move_group'
[move_group-1] [ERROR] [1698204681.218741296] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Path Constraints': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.218777529] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State In Collision': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.218800666] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Path Constraints': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.218813987] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Bounds': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.218965970] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Path Constraints': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.218979932] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State In Collision': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.218996604] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Path Constraints': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.219007457] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Workspace Bounds': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.219032644] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Path Constraints': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.219043489] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State In Collision': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.219060317] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Path Constraints': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.219071948] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Bounds': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.219091423] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Path Constraints': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.219101670] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State In Collision': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.219117791] [moveit.planning_request_adapter]: Exception caught executing adapter 'Fix Start State Path Constraints': acceleration limit not set for group ur_manipulator
[move_group-1] Skipping adapter instead.
[move_group-1] [ERROR] [1698204681.219136202] [moveit.ros_planning.planning_pipeline]: Exception caught: 'acceleration limit not set for group ur_manipulator'
[move_group-1] [INFO] [1698204681.219164403] [moveit_move_group_default_capabilities.move_action_capability]: Unknown event
[rviz2-2] [INFO] [1698204681.219526289] [move_group_interface]: Planning request aborted
[rviz2-2] [ERROR] [1698204681.220494998] [move_group_interface]: MoveGroupInterface::plan() failed or timeout reached

Question

I want to know how to incorporate MoveItConfigsBuilder to UR3e robot while using Pilz Industrial Motion Planner.

About this issue

  • Original URL
  • State: closed
  • Created 8 months ago
  • Comments: 17 (11 by maintainers)

Most upvoted comments

@Mennosytsma

I understand your requirement. In the past, I remember creating a separate package to add my table link and CAD models. Internally, my URDF was pointing to the one given by Universal Robots. On the other hand, I looked up the source code of MoveItConfigsBuilder to understand how it works.

BTW, it seems that you are mixing moveit_py with this issue. I suggest first making sure you can control your robot from RViz using the MoveIt Motion Planning window. Because it confirms that MoveIt configurations are done right. After that, you can start coding in moveit_py.

@Mennosytsma

… I cannot directly apply for my issue …

Would you mind elaborating on it a bit more? I plan to improve the package to cover as many cases as possible.

Thanks

@ravijo Thank you for providing your working example. I realized that you managed to find a workaround for your issue that I cannot directly apply for my issue now as far as I can see, but it will definitely help in the later steps to customize my setup with the UR.

@Mennosytsma

create a different package my_ur_moveit_config that has the specific format that MoveItConfigsBuilder requires

Thank you very much. I appreciate your suggestion but it seems a lot of work just to start the MoveIt!

@gavanderhoorn

Package sources can be found here: xml_launch/easy_launch_demo.

Thank you for supporting us from a decade! Thanks for sharing this package. After looking carefully into it, I realized that the joint limits must be available inside robot_description_planning namespace. I added it to my launch file and it worked like a charm. Below is a summery of my work:

  1. In joint_limits.yaml file, enabled has_acceleration_limits and set max_acceleration. This file is copied from here and kept inside the config subdirectory of my package.
  2. Kept pilz_industrial_motion_planner_planning.yaml and pilz_cartesian_limits.yaml inside the config subdirectory of my package.
  3. Modified ur_moveit.launch.py to read the edited joint_limits.yaml file, as show here
  4. Read the edited joint_limits.yaml file, as shown here
  5. Read pilz planning configuration files from the the config subdirectory of my package, as shown here

Finally, I uploaded this package to GitHub. Maybe @Mennosytsma can give it a try!

It might not necessarily be any easier if this is your first attempt at using MoveIt, but perhaps the approach described by @tylerjw in ROSCON 2023 - Retro ROS 2 Launch would be worth checking out.

Package sources can be found here: xml_launch/easy_launch_demo.

We’ve discussed it a bit in https://github.com/ros2/launch/issues/729 as well.