MoveIt! SetupAssistant: 'Robot in Collision State' when it should not be

asked 2019-09-10 08:18:23 -0500

Roberto Z. gravatar image

updated 2019-09-10 10:39:22 -0500

I'm running ROS Kinetic with Gazebo 7 (7.11) on Ubuntu 16.04 (on a VM with Oracle VM VirtualBox). My goal is to setup a Gazebo simulation of an UR10 robot with (a custom) vacuum gripper end effector on a pedestal and use it with MoveIt! The universal_robot meta-package has served me as starting point from which to add the vacuum gripper and pedestal. To do so I created a new a wrapper xacro file that includes the pedestal xacro file, the original robot xacro file (ur10.urdf.xacro) and the end effector xacro file (called vacuum_gripper.urdf.xacro):

<robot name="workcell" xmlns:xacro="http://www.ros.org/wiki/xacro">

<link name="world" />

  <!-- Pedestal (includes Pedestal to World joint) -->
 <xacro:include filename="$(find pick_place)/urdf/robot_pedestal/robot_pedestal.urdf.xacro"/>
 <xacro:robot_pedestal_urdf pedestal_prefix="pedestal1_" pedestal_parent="world" pedestal_height="0.95">
 <origin xyz="0.5 1.8 0.0" rpy="0 0 0"/>
 </xacro:robot_pedestal_urdf>

<!-- Robot -->
<xacro:include filename="$(find ur_description)/urdf/ur10.urdf.xacro"/>
<xacro:ur10_robot prefix="" joint_limited="true"/>

<!-- End Effector -->
<xacro:include filename="$(find my_package)/urdf/vacuum_gripper/vacuum_gripper.urdf.xacro"/>
<xacro:vacuum_gripper_urdf prefix="end_effector1_"/>
...
</robot>

Also I included the Gazebo plugin for ROS Control (which is not included in the ur10.urdf.xacro file):

<xacro:include filename="$(find my_package)/urdf/common.gazebo.xacro" />

And the neccesary joints:

  <!-- Robot to Pedestal -->
  <joint name="robot_to_pedestal1" type="fixed">
  <origin xyz="0.0 0.0 0.95" rpy="0 0 0" />
  <parent link="pedestal1_pedestal_link" />
  <child link="base_link" />
  </joint>

  <!-- Gripper to Robot -->
  <joint name="gripper1_to_robot1" type="fixed">
  <parent link="tool0" /> 
  <origin xyz="0 0 0.116" rpy="3.14159 0 0"  />
  <child link="vacuum_gripper1_base_link" />
  </joint>

When using the MoveIt! SetupAssistant I get one link-pair (pedestal1_pedestal_link / vacuum_gripper1_base_link) as "Collision by Default" (red background), which, as far as I know, indicates that when the joints are at zero, those links are hitting something. Here is a screenshot where the Self-Collision Checking matrix can be seen. I have unchecked the mark symbol on that link-pair to enable collisions checking.

When moving on to the "Define Robot Poses" step I am having the issue of not being able to set/ define the robot poses I want because almost all poses show the warning message 'Robot in Collision State' when it is absolutely clear to me (from the 3d model on the screen) that the robot should not be in collision state.

Here is a screenshot where the problem can be seen.

Could anybody shed some light on what I'm missing or doing wrong? I'd greatly appreciate it.

edit retag flag offensive close merge delete