moveit / moveit2

:robot: MoveIt for ROS 2
https://moveit.ai/
BSD 3-Clause "New" or "Revised" License
1.03k stars 508 forks source link

hello_moveit does not work when demo.launch.py is modified to include use of occupancy map monitor plugin #1843

Closed ummy11 closed 1 year ago

ummy11 commented 1 year ago

Description

The hello_moveit.cpp from the moveit tutorials gives an error when run after launching a modified version of the demo.launch.py (from this point called modified_demo.launch.py ) file in the moveit_resources_panda_moveit_config package installed from binary.

The modification made to the demo.launch.py was inclusion of octomap_config and octomap_updater_config. These are passed as parameters to the move_group node. A static transform publisher node for a transform between the sensor and robot is also added to the launch file.

Is there a reason why hello_moveit.cpp from the tutorials works for the demo.launch.py but not when it is modified to use the occupancy map monitor plug in? What can I do to make it work?

Your environment

Steps to reproduce

Expected behaviour

Expected behavior is the robot plans and execute the plan for movement to desired pose as it does in the tutorials but considering the octomap as collisions as well. Screenshot from 2023-01-06 10-55-28

static_scene

When hello_moveit is run, the console should show: [INFO] [1672998878.468416619] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.913291 seconds [INFO] [1672998878.468490889] [moveit_robot_model.robot_model]: Loading robot model 'panda'... [WARN] [1672998878.479513849] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml! [INFO] [1672998878.509538800] [move_group_interface]: Ready to take commands for planning group panda_arm. [INFO] [1672998878.511006317] [hello_moveit.remote_control]: RemoteControl Ready. [INFO] [1672998878.540426754] [hello_moveit.remote_control]: Waiting to continue: Press 'next' in the RvizVisualToolsGui window to plan [INFO] [1672998892.671144197] [hello_moveit.remote_control]: ... continuing [INFO] [1672998892.674363876] [move_group_interface]: MoveGroup action client/server ready [INFO] [1672998892.675401208] [move_group_interface]: Planning request accepted [INFO] [1672998892.814546036] [move_group_interface]: Planning request complete! [INFO] [1672998892.874845633] [move_group_interface]: time taken to generate plan: 0.0564173 seconds [INFO] [1672998892.876929978] [hello_moveit.remote_control]: Waiting to continue: Press 'next' in the RvizVisualToolsGui window to execute [INFO] [1672998902.382881790] [hello_moveit.remote_control]: ... continuing [INFO] [1672998902.384829591] [move_group_interface]: Execute request accepted

Actual behaviour

After launching the modified_demo.launch.py and then run the hello_moveit package from the moveit tutorials, you see the following error: `[ERROR] [1672992484.308163480] [hello_moveit]: Could not find parameter robot_description_semantic and did not receive robot_description_semantic via std_msgs::msg::String subscription within 10.000000 seconds. Error: Could not parse the SRDF XML File. Error=XML_ERROR_EMPTY_DOCUMENT ErrorID=13 (0xd) Line number=0 at line 715 in ./src/model.cpp [ERROR] [1672992484.389012759] [moveit_rdf_loader.rdf_loader]: Unable to parse SRDF [FATAL] [1672992484.389099204] [move_group_interface]: Unable to construct robot model. Please make sure all needed information is on the parameter server. terminate called after throwing an instance of 'std::runtime_error' what(): Unable to construct robot model. Please make sure all needed information is on the parameter server.

`

wangnan1987 commented 1 year ago

Actual behaviour

After launching the modified_demo.launch.py and then run the hello_moveit package from the moveit tutorials, you see the following error:

moveit_config = (
    MoveItConfigsBuilder("moka_mr12_2010")
    .robot_description(file_path="config/your.urdf.xacro")
    .robot_description_semantic(file_path="config/your.srdf")
    .trajectory_execution(file_path="config/moveit_controllers.yaml")
    .robot_description_kinematics(file_path="config/kinematics.yaml")
    .planning_scene_monitor(
    publish_robot_description=True, publish_robot_description_semantic=True
)
   .to_moveit_configs()
)

Maybe you can try like this in your demo.launch.py... i can run it successfully. we're not using the same demo,but we had the same problem.

And i had other peoblems.

Console Output

[INFO] [1673353155.594580094] [moveit_rdf_loader.rdf_loader]: Loaded robot model in 0.696475 seconds [INFO] [1673353155.594725573] [moveit_robot_model.robot_model]: Loading robot model 'moka_mr12_2010'... [INFO] [1673353155.594783733] [moveit_robot_model.robot_model]: No root/virtual joint specified in SRDF. Assuming fixed joint [WARN] [1673353156.316204424] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml! [INFO] [1673353156.393356887] [move_group_interface]: Ready to take commands for planning group manipulator. [INFO] [1673353156.407584246] [robot_service_node.remote_control]: RemoteControl Ready.

[INFO] [1673353156.408647043] [moveit_ros.current_state_monitor]: Listening to joint states on topic 'joint_states' [ERROR] [1673353156.427415450] [moveit_robot_state.robot_state]: No kinematics solver instantiated for group 'manipulator'

Descroption

I have already set "robot_description_kinematics(file_path="config/kinematics.yaml")" in moveit_configs,why is there a warnning?

[WARN] [1673353156.316204424] [moveit_ros.robot_model_loader]: No kinematics plugins defined. Fill and load kinematics.yaml!

And I don't understand when I Instantiate an object in the program like this:

moveit::core::RobotState start_state(*(moka_.getMoveGroup()->getCurrentState()));
geometry_msgs::msg::Pose start_pose;
start_pose.orientation.w = 1.0;
start_pose.position.x = 0.55;
start_pose.position.y = -0.05;
start_pose.position.z = 0.8;
start_state.setFromIK(joint_model_group, start_pose);

Why is there a ERROR?

[ERROR] [1673353156.427415450] [moveit_robot_state.robot_state]: No kinematics solver instantiated for group 'manipulator'

And I don't understand why moveit worked fine...It can generate all the trajectories I need it to generate.

kinematics.yaml

manipulator: kinematics_solver: moka_mr12_2010_manipulator/IKFastKinematicsPlugin kinematics_solver_search_resolution: 0.0050000000000000001 kinematics_solver_timeout: 0.0050000000000000001

@AndyZe

Sorry to trouble you again and again....

henningkayser commented 1 year ago

@ummy11, @wangnan1987, I think these are two issues but they have a somewhat related cause: since the hello_moveit executable is not launched with any parameters and can't access SRDF or kinematics config on its own. By default, that's ok since the SRDF would be loaded by subscribing to a topic. If the MoveGroup node fails for some reason or is blocked otherwise, syncing the SRDF may fail which will result in the first error Could not find parameter robot_description_semantic and did not receive robot_description_semantic via std_msgs::msg::String subscription within 10.000000 seconds. Error: Could not parse the SRDF XML File. -> I would look for issues in the MoveGroup node, possibly related to the enabled octomap monitor (full logs would be helpful). The second error can only be fixed by passing the kinematics.yaml config to the hello_moveit node, ideally using a launch file like the one here in the MoveGroupInterface tutorial.

I realize that the hello world demo is maybe a bit short on explanation, that the MGI will have to be launched as a node in more advanced applications. Would either of you mind adding some notes or references to the hello world tutorial that would have helped you not running into this issue in particular? (It's easy for us maintainers to have a blind eye for content gaps like this).

wangnan1987 commented 1 year ago

@ummy11, @wangnan1987, I think these are two issues but they have a somewhat related cause: since the hello_moveit executable is not launched with any parameters and can't access SRDF or kinematics config on its own. By default, that's ok since the SRDF would be loaded by subscribing to a topic. If the MoveGroup node fails for some reason or is blocked otherwise, syncing the SRDF may fail which will result in the first error Could not find parameter robot_description_semantic and did not receive robot_description_semantic via std_msgs::msg::String subscription within 10.000000 seconds. Error: Could not parse the SRDF XML File. -> I would look for issues in the MoveGroup node, possibly related to the enabled octomap monitor (full logs would be helpful). The second error can only be fixed by passing the kinematics.yaml config to the hello_moveit node, ideally using a launch file like the one here in the MoveGroupInterface tutorial.

I realize that the hello world demo is maybe a bit short on explanation, that the MGI will have to be launched as a node in more advanced applications. Would either of you mind adding some notes or references to the hello world tutorial that would have helped you not running into this issue in particular? (It's easy for us maintainers to have a blind eye for content gaps like this).

Thanks for your reply.

The problems I encountered have been solved.

Personally, of course I don't mind.

As an application layer program developer, I am more concerned about whether the logic of the program itself is correct. Many times, I have to spend a lot of energy to understand things other than business logic. Of course, I am also very interested. This is a very excellent application, however, It does take a lot of time to configure and use it correctly.

I guess it's my problem and not yours, but, it does break me down sometimes.

If you'd like to do that, it's much appreciated.

henningkayser commented 1 year ago

I'm closing this since the cause is clearly a shortcoming in the tutorial, and not in MoveIt itself. For further discussion and effort tracking, please refer to https://github.com/ros-planning/moveit2_tutorials/issues/582