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

MoveIt! rviz MotionPlanning plugin broken Robot geometry

asked 2017-11-14 07:02:08 -0500

bas gravatar image

updated 2017-11-17 00:19:14 -0500

I followed the Moveit Setup Assistant Tutorial to configure a manipulator for use with MoveIt. I did

  • load the URDF/Xacro file
  • set the virtual joint
  • add a planning group
  • define a robot pose
  • generate the configuration files without problems.

I left out the end effector part, because I do not have a real end effector. The manipulator has three DOF.

Now, when I start the demo.launch file rviz starts up, but the robot geometry is broken. The position of every link under "MotionPlanning->Scene Robot" is [0,0,0] and its orientation is set to some obviously incorrect value. Metaphorically speaking, the robot in rviz consists of a heap of links (robot parts).

Furthermore, I am missing the interactive markers. Searching the web the missing markers relate to the message No active joints or end effectors found for group ''. which I receive during the launch of rviz and which I cannot get rid of.

I have tested my xacro file with gazebo and it works flawlessly.

Here my updated and simplified SRDF file:

<?xml version="1.0" ?>
<robot name="mugator_manip">
    <group name="manipulator">
        <chain base_link="rotatory_base" tip_link="rotatory_drive" />
    </group>
    <group_state name="home" group="manipulator">
        <joint name="q0" value="0" />
    </group_state>
    <virtual_joint name="virtual_joint" type="fixed" parent_frame="world" child_link="footprint" />
    <disable_collisions link1="rotatory_base" link2="rotatory_drive" reason="Adjacent" />
</robot>

And the relevant output during launch of rviz:

[ INFO] [1510658130.699292603]: MoveGroup context using planning plugin ompl_interface/OMPLPlanner
[ INFO] [1510658130.699318489]: MoveGroup context initialization complete

You can start planning now!

libpng warning: iCCP: known incorrect sRGB profile
[ INFO] [1510658134.100829824]: Loading robot model 'mugator_manip'...
[ INFO] [1510658134.548891308]: Starting scene monitor
[ INFO] [1510658134.554074274]: Listening to '/move_group/monitored_planning_scene'
[ INFO] [1510658134.875040587]: No active joints or end effectors found for group ''. Make sure you have defined an end effector in your SRDF file and that kinematics.yaml is loaded in this node's namespace.
[ INFO] [1510658134.875249162]: No active joints or end effectors found for group 'manipulator'. Make sure you have defined an end effector in your SRDF file and that kinematics.yaml is loaded in this node's namespace.
[ INFO] [1510658134.876849619]: No active joints or end effectors found for group 'manipulator'. Make sure you have defined an end effector in your SRDF file and that kinematics.yaml is loaded in this node's namespace.
[ INFO] [1510658134.877298190]: Constructing new MoveGroup connection for group 'manipulator' in namespace ''
[ INFO] [1510658136.007301565]: Ready to take commands for planning group manipulator.
[ INFO] [1510658136.007387218]: Looking around: no
[ INFO] [1510658136.007429894]: Replanning: no

Any help is appreciated.

Edit: Screen shot of rviz: RViz GUI with broken geometry

Edit: Screen shot of the Displays area of rviz. Displays area of rviz

Edit: Simplified URDF file which still shows a broken geometry:

<?xml version="1.0" ?>
<robot name="mugator_manip" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <gazebo>
    <static>false</static>
    <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
      <robotNamespace>/mugator_manip</robotNamespace>
    </plugin>
  </gazebo>

  <link name="footprint"/>

  <joint name="p_joint" type="fixed">
    <parent link="footprint"/>
    <origin rpy="0 0 0" xyz="0 0 0.19"/>
    <child link="rotatory_base"/>
  </joint ...
(more)
edit retag flag offensive close merge delete

Comments

<chain base_link="Rotatory Base" tip_link="Cutter Drive" />

Suggestion: remove all spaces from your link and joint names and try again.

I don't believe it's made explicit, but TF frames should also follow ROS Naming conventions. Support for whitespace is spotty.

gvdhoorn gravatar image gvdhoorn  ( 2017-11-14 07:21:05 -0500 )edit

Thanks for your advice regarding ROS Naming conventions. I removed the spaces. Unfortunately it did not change anything. Geometry is still broken :(

bas gravatar image bas  ( 2017-11-14 07:55:35 -0500 )edit

You removed the spaces from your urdf, recreated the moveit config pkg and then rebuilt your workspace?

gvdhoorn gravatar image gvdhoorn  ( 2017-11-14 07:59:12 -0500 )edit

The 'broken geometry' is a sign of missing TF frames. This can happen if robot_state_publisher isn't started, joint_state_publisher isn't started, they can't find each other or MoveIt cannot work with your URDF.

Without your urdf this may be difficult to debug.

gvdhoorn gravatar image gvdhoorn  ( 2017-11-14 08:01:09 -0500 )edit

If you could include a screenshot of your RViz window that could maybe help.

gvdhoorn gravatar image gvdhoorn  ( 2017-11-14 08:01:29 -0500 )edit

I removed the spaces. To be honest, i did not think about recompiling, but to make sure I deleted the moveit config pkg, recreated it again and recompiled the whole workspace with catkin_make. No change. The geometry is still broken.

bas gravatar image bas  ( 2017-11-14 08:07:06 -0500 )edit

Please make the Displays area a little larger. I'm mostly interested in the Fixed Frame field and those around it.

If you add a Robot Model display to RViz, does it also not show your robot correctly?

gvdhoorn gravatar image gvdhoorn  ( 2017-11-14 08:30:14 -0500 )edit

To be honest, i did not think about recompiling

I did not write 'compiling', but 'rebuilding'. The former is for code, the latter is to update your workspace with info about the new MoveIt config pkg that you created.

gvdhoorn gravatar image gvdhoorn  ( 2017-11-14 08:30:53 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2017-11-20 07:52:41 -0500

bas gravatar image

I investigated this issue further and found a bug in ros/urdfdom_headers/urdf_model/include/urdf_model/pose.h. In pose.h std::stod is used to parse floating point values from a urdf file. std::stod's parsing bahaviour is depending on your locale. With my german locale std:stod expected a comma instead of a dot as a decimal delimiter. This way e.g. pi/2 is parsed to 1.

The easiest workaround is to set the locale LC_NUMERIC to "en_US.UTF-8". This can be done temporarily for each shell by issuing

export LC_NUMERIC="en_US.UTF-8"

in the shell or permanently for all shells e.g. in .bashrc.

edit flag offensive delete link more

Comments

gvdhoorn gravatar image gvdhoorn  ( 2017-11-20 07:54:11 -0500 )edit
1

@gvdhoorn Thank you for your enormous support. THUMBS_UP

bas gravatar image bas  ( 2017-11-20 07:58:16 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2017-11-14 07:02:08 -0500

Seen: 962 times

Last updated: Nov 20 '17