Issue in moveit2 tutorial regarding robot_description_semantic parameter
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.
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
https://github.com/ros-planning/movei...
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
Thanks .. worked