moveit/moveit2_tutorials

Couldn't find requested planning pipeline 'pilz_industrial_motion_planner'

ravijo opened this issue · 1 comments

Description

I am trying to incorporate UR robot with Pilz Industrial Motion Planner by following the official tutorial. The demo with Panda Arm works but in the case of UR, terminal is showing the following messages:

[move_group-1] [INFO] [1698838164.950089833] [move_group]: MoveGroupMoveAction: Received request
[move_group-1] [INFO] [1698838164.950510153] [move_group]: executing..
[move_group-1] [INFO] [1698838164.953140900] [move_group]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[move_group-1] [WARN] [1698838164.953235151] [move_group]: Couldn't find requested planning pipeline 'pilz_industrial_motion_planner'
[move_group-1] [INFO] [1698838164.953280927] [move_group]: FAILURE

Your environment

  • ROS Distro: Iron
  • OS Version: Ubuntu 22.04.3 LTS
  • Source or Binary build: Source (fresh install just now)

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 ur_pilz_demo ur_pilz.launch.py # custom package at https://github.com/ravijo/ur_pilz_demo

$ ros2 run moveit2_tutorials pilz_move_group # Panda variables are updated to UR

Backtrace or Console output

MoveIt Controller Terminal

$ ros2 launch ur_pilz_demo ur_pilz.launch.py 
[INFO] [launch]: All log files can be found below /home/user/.ros/log/2023-11-01-20-28-18-276591-dell-34728
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [move_group-1]: process started with pid [34735]
[INFO] [rviz2-2]: process started with pid [34737]
[rviz2-2] Warning: Ignoring XDG_SESSION_TYPE=wayland on Gnome. Use QT_QPA_PLATFORM=wayland to run on Wayland anyway.
[move_group-1] [WARN] [1698838098.834127381] [move_group]: Falling back to using the the move_group node namespace (deprecated behavior).
[move_group-1] [INFO] [1698838098.837228527] [move_group.rdf_loader]: Loaded robot model in 0.00296161 seconds
[move_group-1] [INFO] [1698838098.837258576] [moveit_robot_model.robot_model]: Loading robot model 'ur'...
[move_group-1] [INFO] [1698838098.837266761] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[move_group-1] [INFO] [1698838098.848976025] [moveit_kinematics_base.kinematics_base]: Joint weights for group 'ur_manipulator': 1 1 1 1 1 1
[move_group-1] [INFO] [1698838098.880799409] [move_group.planning_scene_monitor]: Publishing maintained planning scene on 'monitored_planning_scene'
[move_group-1] [INFO] [1698838098.880920430] [move_group.moveit_cpp]: Listening to 'joint_states' for joint states
[move_group-1] [INFO] [1698838098.881401155] [move_group.current_state_monitor]: Listening to joint states on topic 'joint_states'
[move_group-1] [INFO] [1698838098.881624685] [move_group.planning_scene_monitor]: Listening to '/attached_collision_object' for attached collision objects
[move_group-1] [INFO] [1698838098.881640262] [move_group.planning_scene_monitor]: Starting planning scene monitor
[move_group-1] [INFO] [1698838098.881776482] [move_group.planning_scene_monitor]: Listening to '/planning_scene'
[move_group-1] [INFO] [1698838098.881786334] [move_group.planning_scene_monitor]: Starting world geometry update monitor for collision objects, attached objects, octomap updates.
[move_group-1] [INFO] [1698838098.881974406] [move_group.planning_scene_monitor]: Listening to 'collision_object'
[move_group-1] [INFO] [1698838098.882143811] [move_group.planning_scene_monitor]: Listening to 'planning_scene_world' for planning scene world geometry
[move_group-1] [WARN] [1698838098.882887072] [move_group.occupancy_map_monitor]: Resolution not specified for Octomap. Assuming resolution = 0.1 instead
[move_group-1] [ERROR] [1698838098.882908517] [move_group.occupancy_map_monitor]: No 3D sensor plugin(s) defined for octomap updates
[move_group-1] [INFO] [1698838098.892399259] [moveit.pilz_industrial_motion_planner.joint_limits_aggregator]: Reading limits from namespace robot_description_planning
[move_group-1] [INFO] [1698838098.894742722] [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] [1698838098.894764173] [moveit.pilz_industrial_motion_planner]: About to load: pilz_industrial_motion_planner/PlanningContextLoaderCIRC
[move_group-1] [INFO] [1698838098.896245834] [moveit.pilz_industrial_motion_planner]: Registered Algorithm [CIRC]
[move_group-1] [INFO] [1698838098.896267473] [moveit.pilz_industrial_motion_planner]: About to load: pilz_industrial_motion_planner/PlanningContextLoaderLIN
[move_group-1] [INFO] [1698838098.897090363] [moveit.pilz_industrial_motion_planner]: Registered Algorithm [LIN]
[move_group-1] [INFO] [1698838098.897103154] [moveit.pilz_industrial_motion_planner]: About to load: pilz_industrial_motion_planner/PlanningContextLoaderPTP
[move_group-1] [INFO] [1698838098.897692775] [moveit.pilz_industrial_motion_planner]: Registered Algorithm [PTP]
[move_group-1] [INFO] [1698838098.897704747] [move_group.planning_pipeline]: Using planning interface 'Pilz Industrial Motion Planner'
[move_group-1] [INFO] [1698838098.902580296] [move_group.planning_pipeline]: Using planning request adapter 'Fix Workspace Bounds'
[move_group-1] [INFO] [1698838098.902617435] [move_group.planning_pipeline]: Using planning request adapter 'Fix Start State Bounds'
[move_group-1] [INFO] [1698838098.902625608] [move_group.planning_pipeline]: Using planning request adapter 'Fix Start State In Collision'
[move_group-1] [INFO] [1698838098.902629958] [move_group.planning_pipeline]: Using planning request adapter 'Fix Start State Path Constraints'
[move_group-1] [INFO] [1698838098.943431945] [moveit.plugins.moveit_simple_controller_manager]: Added FollowJointTrajectory controller for scaled_joint_trajectory_controller
[move_group-1] [INFO] [1698838098.944964028] [moveit.plugins.moveit_simple_controller_manager]: Added FollowJointTrajectory controller for joint_trajectory_controller
[move_group-1] [INFO] [1698838098.945069102] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-1] [INFO] [1698838098.945093851] [moveit.plugins.moveit_simple_controller_manager]: Returned 2 controllers in list
[move_group-1] [INFO] [1698838098.945339481] [move_group.trajectory_execution_manager]: Trajectory execution is not managing controllers
[move_group-1] [INFO] [1698838098.945356341] [move_group]: MoveGroup debug mode is ON
[move_group-1] [INFO] [1698838098.957841574] [moveit.pilz_industrial_motion_planner.move_group_sequence_action]: initialize move group sequence action
[move_group-1] [INFO] [1698838098.959520188] [moveit.pilz_industrial_motion_planner.joint_limits_aggregator]: Reading limits from namespace robot_description_planning
[move_group-1] [INFO] [1698838098.959667160] [moveit.pilz_industrial_motion_planner.joint_limits_aggregator]: Reading limits from namespace robot_description_planning
[move_group-1] [INFO] [1698838098.960100211] [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] *     - SequenceAction
[move_group-1] *     - SequenceService
[move_group-1] ********************************************************
[move_group-1] 
[move_group-1] [INFO] [1698838098.960131698] [move_group]: MoveGroup context using planning plugin pilz_industrial_motion_planner/CommandPlanner
[move_group-1] [INFO] [1698838098.960139257] [move_group]: 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] Loading 'pilz_industrial_motion_planner/MoveGroupSequenceAction'...
[move_group-1] Loading 'pilz_industrial_motion_planner/MoveGroupSequenceService'...
[move_group-1] 
[move_group-1] You can start planning now!
[move_group-1] 
[rviz2-2] [INFO] [1698838099.036679149] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-2] [INFO] [1698838099.036741905] [rviz2]: OpenGl version: 4.5 (GLSL 4.5)
[rviz2-2] [INFO] [1698838099.077150226] [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 321 in /opt/ros/iron/include/class_loader/class_loader/class_loader_core.hpp
[rviz2-2] [WARN] [1698838099.158682107] [rcl.logging_rosout]: Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic.
[rviz2-2] [ERROR] [1698838102.183884510] [rviz2_moveit.motion_planning_frame]: Action server: /recognize_objects not available
[rviz2-2] [INFO] [1698838102.214836678] [rviz2_moveit.motion_planning_frame]: MoveGroup namespace changed: / -> . Reloading params.
[rviz2-2] [INFO] [1698838102.330905816] [rviz2_moveit.rdf_loader]: Loaded robot model in 0.00353817 seconds
[rviz2-2] [INFO] [1698838102.330963483] [moveit_robot_model.robot_model]: Loading robot model 'ur'...
[rviz2-2] [INFO] [1698838102.330978360] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[rviz2-2] [INFO] [1698838102.348511774] [moveit_kinematics_base.kinematics_base]: Joint weights for group 'ur_manipulator': 1 1 1 1 1 1
[rviz2-2] [INFO] [1698838102.399168662] [rviz2_moveit.planning_scene_monitor]: Starting planning scene monitor
[rviz2-2] [INFO] [1698838102.400015379] [rviz2_moveit.planning_scene_monitor]: Listening to '/monitored_planning_scene'
[rviz2-2] [INFO] [1698838102.577053735] [interactive_marker_display_94330565171024]: Connected on namespace: /rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic
[rviz2-2] [INFO] [1698838102.582584504] [rviz2_moveit.motion_planning_frame]: group ur_manipulator
[rviz2-2] [INFO] [1698838102.582638291] [rviz2_moveit.motion_planning_frame]: Constructing new MoveGroup connection for group 'ur_manipulator' in namespace ''
[rviz2-2] [INFO] [1698838102.605098805] [rviz2_moveit.move_group_interface]: Ready to take commands for planning group ur_manipulator.
[rviz2-2] [INFO] [1698838102.737599828] [interactive_marker_display_94330565171024]: Sending request for interactive markers
[rviz2-2] [INFO] [1698838102.792452203] [interactive_marker_display_94330565171024]: Service response received for initialization
[rviz2-2] [WARN] [1698838117.531918272] [rcl.logging_rosout]: Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic.
[move_group-1] [INFO] [1698838164.950089833] [move_group]: MoveGroupMoveAction: Received request
[move_group-1] [INFO] [1698838164.950510153] [move_group]: executing..
[move_group-1] [INFO] [1698838164.953140900] [move_group]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[move_group-1] [WARN] [1698838164.953235151] [move_group]: Couldn't find requested planning pipeline 'pilz_industrial_motion_planner'
[move_group-1] [INFO] [1698838164.953280927] [move_group]: FAILURE

Pilz Move Group Terminal

$ ros2 run moveit2_tutorials pilz_move_group 
Error:   Semantic description is not specified for the same robot as the URDF
         at line 664 in ./src/model.cpp
[INFO] [1698838150.733456022] [moveit_384884973.rdf_loader]: Loaded robot model in 0.99007 seconds
[INFO] [1698838150.733541601] [moveit_robot_model.robot_model]: Loading robot model 'ur3e'...
[INFO] [1698838150.733553493] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint
[WARN] [1698838150.753168813] [moveit_384884973.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!
[INFO] [1698838150.773404033] [moveit_384884973.move_group_interface]: Ready to take commands for planning group ur_manipulator.
[INFO] [1698838150.774093816] [pilz_move_group_node.remote_control]: RemoteControl Ready.
[INFO] [1698838150.774133995] [pilz_move_group_node.remote_control]: Waiting to continue: Press 'Next' in the RVizVisualToolsGui window to plan
[INFO] [1698838154.939441078] [pilz_move_group_node.remote_control]: ... continuing
[INFO] [1698838154.942046598] [pilz_move_group_node.rviz_visual_tools]: Topic /rviz_visual_tools waiting 5 seconds for subscriber.
[WARN] [1698838159.944629943] [pilz_move_group_node.rviz_visual_tools]: Topic /rviz_visual_tools unable to connect to any subscribers within 5 sec. It is possible initially published visual messages will be lost.
[INFO] [1698838159.944772334] [pilz_move_group_node.rviz_visual_tools]: Topic /rviz_visual_tools waiting 5 seconds for subscriber.
[WARN] [1698838164.948312233] [pilz_move_group_node.rviz_visual_tools]: Topic /rviz_visual_tools unable to connect to any subscribers within 5 sec. It is possible initially published visual messages will be lost.
[INFO] [1698838164.949342729] [moveit_384884973.move_group_interface]: MoveGroup action client/server ready
[INFO] [1698838164.950371033] [moveit_384884973.move_group_interface]: Planning request accepted
[INFO] [1698838164.953814773] [moveit_384884973.move_group_interface]: Planning request aborted
[ERROR] [1698838164.954116516] [moveit_384884973.move_group_interface]: MoveGroupInterface::plan() failed or timeout reached
[ERROR] [1698838164.954294151] [pilz_move_group_node]: Planning failed!
[INFO] [1698838164.954733338] [pilz_move_group_node.remote_control]: Waiting to continue: Press 'Next' in the RVizVisualToolsGui window to plan

Additional Info

  • I can use the UR robot inside the RViz using Moveit's Motion Planning Plugin. See an example below:
    [rviz2-2] [INFO] [1698838261.089347766] [rviz2_moveit.move_group_interface]: MoveGroup action client/server ready
    [move_group-1] [INFO] [1698838261.089868338] [move_group]: MoveGroupMoveAction: Received request
    [move_group-1] [INFO] [1698838261.090110502] [move_group]: executing..
    [rviz2-2] [INFO] [1698838261.090379182] [rviz2_moveit.move_group_interface]: Planning request accepted
    [move_group-1] [INFO] [1698838261.094318079] [move_group]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
    [move_group-1] [INFO] [1698838261.094389495] [move_group]: Using planning pipeline 'move_group'
    [move_group-1] [INFO] [1698838261.094797990] [moveit.pilz_industrial_motion_planner.trajectory_generator_ptp]: Initialized Point-to-Point Trajectory Generator.
    [move_group-1] [INFO] [1698838261.094839802] [moveit.pilz_industrial_motion_planner.trajectory_generator]: Generating PTP trajectory...
    [move_group-1] [INFO] [1698838261.097346515] [move_group]: Motion plan was computed successfully.
    [rviz2-2] [INFO] [1698838261.097778163] [rviz2_moveit.move_group_interface]: Planning request complete!
    [rviz2-2] [INFO] [1698838261.097900212] [rviz2_moveit.move_group_interface]: time taken to generate plan: 0.00126171 seconds
    
  • The planning parameter on move_group node seems incorrect, as shown below:
    $ ros2 param list /move_group | grep pipeline
      default_planning_pipeline
    
    $ ros2 param get /move_group default_planning_pipeline
    String value is: move_group
    

Question

How to add default_planning_pipeline to ur_moveit.launch.py so that Pilz can be used?

After following modifications, it worked. So please allow me to share it below:

By looking at the incorrect value of default_planning_pipeline under move_group node, I got an idea to fix it first in the following manner:

    # Planning Configuration
    pilz_planning_pipeline_config = {
        "planning_pipelines": ["pilz_industrial_motion_planner"],  # <- Newly added
        "default_planning_pipeline": "pilz_industrial_motion_planner",  # <- Newly added
        "pilz_industrial_motion_planner": {},  # <- Newly added
        "move_group": {},
        "robot_description_planning":{},
    }
    pilz_planning_yaml = load_yaml("ur_pilz_demo", "config/pilz_industrial_motion_planner_planning.yaml")
    pilz_planning_pipeline_config["move_group"].update(pilz_planning_yaml)
    pilz_planning_pipeline_config["pilz_industrial_motion_planner"].update(pilz_planning_yaml)  # <- Newly added

    pilz_cartesian_limits_yaml = load_yaml("ur_pilz_demo", "config/pilz_cartesian_limits.yaml")
    pilz_planning_pipeline_config["robot_description_planning"].update(pilz_cartesian_limits_yaml)

This way, we have the correct parameter loaded. See below:

$ ros2 param get /move_group default_planning_pipeline
String value is: pilz_industrial_motion_planner

$ ros2 param get /move_group planning_pipelines
String values are: ['pilz_industrial_motion_planner']

Quick Question

The above configuration is duplicating pilz_industrial_motion_planner. Is there any way to make it cleaner? (The complete launch file can be seen here)