ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Issue in moveit2 tutorial regarding robot_description_semantic parameter

asked 2022-10-02 15:08:53 -0500

Sahil Goyal gravatar image

I am trying to complete the moveit2 tutorial - Your First C++ MoveIt Project. Code file is given at the end of the linked webpage. When I run the node hello_moveit with ros2 run hello_moveit hello_moveit, I get the error

[ERROR] [1664720561.886608829] [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] [1664720561.900546627] [moveit_rdf_loader.rdf_loader]: Unable to parse SRDF
[FATAL] [1664720561.901184806] [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.
[ros2run]: Aborted

This type of error is mentioned on the website which appear when demo file is not launched first. But, I have launched the demo file first by ros2 launch moveit2_tutorials demo.launch.py and then ran the command ros2 run hello_moveit hello_moveit.

The error mentions could not find the parameter robot_description_semantic but when I run ros2 param list | grep robot_description_semantic(while rviz2 launched from demo file is already running in background), I get

publish_robot_description_semantic
robot_description_semantic
publish_robot_description_semantic
robot_description_semantic
publish_robot_description_semantic
robot_description_semantic

which means that the parameter is present. These parameters are associated with the nodes /move_group, /moveit_simple_controller_manager, /rviz2 where each topic has the paramters publish_robot_description_semantic and robot_description_semantic.

When I run ros2 param get /rviz2 robot_description_semantic I get the contents of the following file(as mentioned by path)

String value is:<?xml version="1.0"?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from /home/sahil/Desktop/moveit_practice/ws_moveit2/install/moveit_resources_panda_moveit_config/share/moveit_resources_panda_moveit_config/config/panda_arm_hand.srdf.xacro | -->

if I do for other nodes, it is all same.

If I do ros2 param get /rviz2 publish_robot_description_semantic, I get Parameter not set and for the remaining two nodes I get Boolean value is: False.

OS - Ubuntu 22.04

Any help would be appreciated.

edit retag flag offensive close merge delete

Comments

I have also followed the same steps and getting the same error any progress till yet if you have resolved it

I have altried it on ros2 humble Ubuntu 22 and getting same issue

OS - Ubuntu 20.04 ros2 galactic

any help

Osal22 gravatar image Osal22  ( 2022-10-18 09:01:32 -0500 )edit
1

I have resolved it by adding planning_scene_monitor_parameters = { "publish_planning_scene": True, "publish_geometry_updates": True, "publish_state_updates": True, "publish_transforms_updates": True, "publish_robot_description":True, "publish_robot_description_semantic":True

}

they were not set by default "publish_robot_description":True, "publish_robot_description_semantic":True

Osal22 gravatar image Osal22  ( 2022-10-19 05:50:25 -0500 )edit

Thanks .. worked

Arshad gravatar image Arshad  ( 2023-07-06 22:52:08 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2023-05-03 10:06:37 -0500

130s gravatar image

updated 2023-06-04 10:33:32 -0500

Assuming https://github.com/ros-planning/movei... is opened by OP, resolution there was simply wrong software version https://github.com/ros-planning/movei.... In OP's case, which uses the specific tutorial, that was probably it.


A bit more generic answer:

The error Could not find parameter robot_description_semantic and ... can happen (not limited to the referenced tutorial). I keep getting it.

Potential root causes: A MoveGroup node is unable to "get (ROS) parameter" robot_description* somehow.

Recommended steps to narrow down a root cause and solve:

Step-1. Identify which node the error is happening in. In terminal output you should see the node name along with the error. In the following example, I can see robot-laputa node:

Eg.

[robot-laputa-24] [ERROR] [1685818539.857625507] [robot-laputa]: Could not find parameter robot_description_semantic and did not receive robot_description_semantic via std_msgs::msg::String subscription within 10.000000 seconds.
[robot-laputa-24] Error:   Could not parse the SRDF XML File. Error=XML_ERROR_EMPTY_DOCUMENT ErrorID=15 (0xf) Line number=0
[robot-laputa-24]          at line 694 in /tmp/binarydeb/ros-galactic-srdfdom-2.0.3/src/model.cpp
[robot-laputa-24] [ERROR] [1685818539.863908388] [moveit_rdf_loader.rdf_loader]: Unable to parse SRDF                                      
[robot-laputa-24] [FATAL] [1685818539.864152922] [move_group_interface]: Unable to construct robot model. Please make sure all needed information is on the parameter server.
[robot-laputa-24] terminate called after throwing an instance of 'std::runtime_error'
[robot-laputa-24]   what():  Unable to construct robot model. Please make sure all needed information is on the parameter server.

Step-2. Try 'get parameter' by yourself before the error occurs, if you could, to see what parameters are set or not. In my case when this error is happening, ros2 param get tends to fail with another errors though.

Step-3. Fix where params set e.g. .launch.py if any. You may have something like the following.:

E.g.

_node_motion = Node(
    package="foo", executable="node_exec", arguments=[],
    name="node_exec_name",
    parameters=[
        robot_description,
        robot_description_semantic,
        robot_description_kinematics,
    ],        
)

Make sure the specific parameter that is causing an error is generated as expected. Also make sure parameter names are correct (one of my error modes was I was passing a wrong key name, e.g. In the following, key "robot_desc" is not what Moveit is looking for, but this as a ROS parameter is totally valid so setting it doesn't cause any error. Moveit returns the error because there's simply no parameter with a key "robot_description")..

robot_description = {"robot_desc": robot_description_config.toxml()}

Btw for how those parameters are generated, as a ROS2 learner I've been seeing 2 ways to generate these params in .launch.py. I'm listing them up here since I haven't seen anywhere where these are summarized.

Option-a. "Manual" approach where you generate each variable by referring to the corresponding resources: moveit2_tutorials/doc/tutorials/quickstart_in_rviz/launch/demo.launch.py#L105:

:
robot_description_config = xacro.process_file(
    os.path.join(
        get_package_share_directory("moveit_resources_panda_moveit_config"),
        "config",
        "panda.urdf.xacro",
    )
)
robot_description = {"robot_description": robot_description_config.toxml()}

robot_description_semantic_config = load_file(
    "moveit_resources_panda_moveit_config", "config/panda.srdf"
)
robot_description_semantic = {
    "robot_description_semantic": robot_description_semantic_config
}

:

# Start the actual move_group node/action server
run_move_group_node = Node(
    package="moveit_ros_move_group",
    executable="move_group",
    output="screen",
    parameters=[
        robot_description,
        robot_description_semantic,
        kinematics_yaml,
        ompl_planning_pipeline_config,
        trajectory_execution,
        moveit_controllers,
        planning_scene_monitor_parameters,
    ],
)

Option-b. Automated approach: moveit2_tutorials/doc ... (more)

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2022-10-02 15:08:53 -0500

Seen: 1,688 times

Last updated: Jun 04 '23