URDF parser eliminating inertialess non-fixed links

asked 2021-11-12 19:09:15 -0600

ivaughn gravatar image

Hello,

The urdf loader in Gazebo 9.0.0 seems to be eliminating all links, including a "revolute" link, that don't have an inertia tag. As an example, the following macro produces a model with model->GetJointCount() > 0:

<xacro:macro name="fin" params="name parent_link xyz rpy">
  <!-- First, define the link -->
  <link name="${name}_link">
    <visual>
      <origin xyz="0 0 -0.0762" rpy="0 0 0"/>
      <geometry>
          <mesh filename="package://shiny_robot/mesh/fin.stl"/>
      </geometry>
      <material name="orange"/>
    </visual>
    <inertial>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <mass value="0.1"/>
    </inertial>
  </link>

   <!-- Now apply the offsets -->
  <joint name="${name}_servo" type="revolute">
    <parent link="${parent_link}"/>
    <child link="${name}_link"/>
    <axis xyz="0 0 1"/>
    <limit lower="-${pi/4}" upper="${pi/4}" effort="10" velocity="10"/>
    <origin xyz="${xyz}" rpy="${rpy}"/>
  </joint>
</xacro:macro>

Interestingly, this keeps the link in place despite the inertial tag failing to parse because there's no inertial tensor. I note this is a change in behavior from earlier versions of Gazebo. Anyone know what's up with this?

edit retag flag offensive close merge delete