Disabling lumping on a fixed joint in a URDF results in a revolute joint

Issue #131 resolved
Michael Beardsworth created an issue

Parsing a URDF like the one below, (with 2 links connected by a fixed joint, lumping disabled), produces a model with 2 links joined by a revolute joint. This behavior seems surprising to me, but is clearly implemented intentionally (https://bitbucket.org/osrf/sdformat/src/a3fa3d1163cc2fe991ac106e51695b99f8b119ca/src/parser_urdf.cc?at=default&fileviewer=file-view-default#parser_urdf.cc-3221). Does anyone know the history of this behavior? It's a bit problematic for my application.

<robot name="robot">
  <link name="base_link">
    <visual>
      <origin rpy="1.570796326790 0 0" xyz="0 0 .215"/>
      <geometry>
        <box size="0.33 0.22 0.23"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="-0.05 0 0.1"/>
      <geometry>
        <box size="0.33 0.22 0.23"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="1.570796326790 0 0" xyz="0 0 .215"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
      <mass value="1"/>
    </inertial>
  </link>
  <link name="second_link">
    <visual>
      <origin rpy="1.570796326790 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder radius="0.16" length="0.3"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.02 0 0.15"/>
      <geometry>
        <cylinder radius="0.16" length="0.3"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="1.570796326790 0 0" xyz="0 0 0"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
      <mass value="1"/>
    </inertial>
  </link>
  <joint name="joint_base_second" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 .215"/>
    <parent link="base_link"/>
    <child link="second_link"/>
  </joint>
  <gazebo reference="joint_base_second">
    <disableFixedJointLumping>true</disableFixedJointLumping>
  </gazebo>
</robot>

Comments (5)

  1. Silvio Traversaro

    The option to disable fixed joint lumping was added at the end of 2014 [1], when fixed joints were not implemented in either SDF or Gazebo, and the canonical way to "simulate" them was through a revolute joint with min and max pos limits set to 0.

    The support for fixed joints was added in SDF and Gazebo in 2015 [2], [3]. At that time I did not modified the disableFixedJointLumping option to produce a fixed joint because it would have broken the case in which a recent SDFormat was compiled with an older version of Gazebo.

    Unfortunately this is still a possibility, given that there have been no new major version of SDFormat since then. @Jose Luis Rivero What do you think about this?

    Another possibility is to add a new option (called in a different way, to avoid breaking the disableFixedJointLumping behavior) that creates a fixed joint and deprecate the disableFixedJointLumping. This solution is not ideal for model mantainers, that have to have different options depending on the Gazebo version that they want to support. Furthermore it would relativly complicate the code.

    [1] : https://bitbucket.org/osrf/sdformat/pull-requests/133/added-urdf-gazebo-extension-option-to/diff

    [2] : https://bitbucket.org/osrf/sdformat/pull-requests/194/support-for-fixed-joints/diff

    [3] : https://bitbucket.org/osrf/gazebo/pull-requests/1747/support-for-fixed-joints

  2. Jose Luis Rivero

    From the packaging and maintaining point of view, breaking (runtime breakage or altering behavior) old versions of gazebo depending on sdformat2 is a bad plan. All gazebo series gazebo5 (which is still supported and used officially in ROS Jade) are using sdformat2 and, If I'm not wrong, the fixed joints were implement first in gazebo6 series.

    The best option I see would be what Silvio mentioned of adding a new option although I don't know the sdformat code base good enough to provide more details. I think that probably @Steven Peters or @Nate Koenig have a better understanding of all details and implications and might help with an alternative.

    Thanks Michael, SIlvio.

  3. Silvio Traversaro

    Another option (perhaps cleaner) is to add an attribute to the disableFixedJointLumping tag, specifying the type of the SDF joint. Once we release a new major version of SDF, we can switch the default value for that attribute to fixed.

  4. Log in to comment