Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Is there a way to disable fixed joint reduction? #2732

Closed
toliver opened this issue May 11, 2020 · 5 comments
Closed

Is there a way to disable fixed joint reduction? #2732

toliver opened this issue May 11, 2020 · 5 comments

Comments

@toliver
Copy link

toliver commented May 11, 2020

When it converts a URDF to SDF, Gazebo reduces successive links that are united via fixed joints into a single link.
Is there a way to tell Gazebo to not do that (at least for a specific joint that we are interested in)?

The main reason to ask this is that this makes it impossible to declare a force torque sensor attached to a fixed joint, as it is suggested in the last section of this tutorial.

When I try to do that in the URDF, the sensor is removed together with the joint, and it does not appear in the final SDF file.

@traversaro
Copy link
Collaborator

You can use the preserveFixedJoint tag, that unfortunately it is not documented, see osrf/gazebo_tutorials#91 .

@toliver
Copy link
Author

toliver commented May 15, 2020

Thanks for your quick answer @traversaro . That has worked well, although I've bumped into some unexpected beahviour.
It seems that gazebo silently removes any links that don't contain an <inertial> element, even if those links were necessary as an attachment point for subsequent links.

Not sure if I should file this as a bug, but I would expect some kind of warning at least.

As an example, the following URDF:

<robot name='test_robot'>
  <link name='link1'>
    <inertial>
      <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0'/>
      <mass value='1.0'/>
      <inertia ixx='1.0' ixy='0.0' ixz='0.0'
               iyy='1.0' iyz='0.0' izz='1.0'/>
    </inertial>
  </link>
  <link name='link2'>
    <visual>
      <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0'/>
      <geometry>
        <cylinder radius="0.01" length="0.01"/>
      </geometry>
    </visual>
    <inertial>
      <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0'/>
      <mass value='1.0'/>
      <inertia ixx='1.0' ixy='0.0' ixz='0.0'
               iyy='1.0' iyz='0.0' izz='1.0'/>
    </inertial>
    <collision>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
      <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0'/>
    </collision>
  </link>
  <joint name='joint1_2' type='revolute'>
    <parent link='link1' />
    <child  link='link2' />
    <axis xyz="0 0 1" />
    <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0' />
    <limit lower="0.0" upper="1.53" effort="-1" velocity="-1"/>
  </joint>
  
  <link name='camera_attachment_point'/>
  <joint name='joint1_camera_attachment_point' type='fixed'>
    <parent link='link1' />
    <child  link='camera_attachment_point' />
    <origin xyz='0.0 0.0 0.5' rpy='0.0 0.0 0.0' />
  </joint>

  <link name='camera'>
    <visual>
      <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0'/>
      <geometry>
        <cylinder radius="0.01" length="0.01"/>
      </geometry>
    </visual>
    <inertial>
      <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0'/>
      <mass value='1.0'/>
      <inertia ixx='1.0' ixy='0.0' ixz='0.0'
               iyy='1.0' iyz='0.0' izz='1.0'/>
    </inertial>
    <collision>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
      <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0'/>
    </collision>
  </link>
  <joint name='joint_camera' type='fixed'>
    <parent link='camera_attachment_point' />
    <child  link='camera' />
    <origin xyz='0.0 0.0 0.0' rpy='0.0 0.0 0.0' />
  </joint>

  <gazebo reference='joint1_camera_attachment_point'>
    <preserveFixedJoint>true</preserveFixedJoint>
  </gazebo>
  <gazebo reference='joint_camera'>
    <preserveFixedJoint>true</preserveFixedJoint>
  </gazebo>
</robot>

Is converted to the following SDF:

<sdf version='1.6'>
  <model name='test_robot'>
    <link name='link1'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>1</mass>
        <inertia>
          <ixx>1</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1</iyy>
          <iyz>0</iyz>
          <izz>1</izz>
        </inertia>
      </inertial>
    </link>
    <link name='link2'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>1</mass>
        <inertia>
          <ixx>1</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1</iyy>
          <iyz>0</iyz>
          <izz>1</izz>
        </inertia>
      </inertial>
      <collision name='link2_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.01 0.01 0.01</size>
          </box>
        </geometry>
      </collision>
      <visual name='link2_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <cylinder>
            <length>0.01</length>
            <radius>0.01</radius>
          </cylinder>
        </geometry>
      </visual>
    </link>
    <joint name='joint1_2' type='revolute'>
      <child>link2</child>
      <parent>link1</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>0</lower>
          <upper>1.53</upper>
          <effort>-1</effort>
          <velocity>-1</velocity>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
  </model>
</sdf>

Where the camera_attachment_point has been removed and the subsequent camera link has also been removed.

@traversaro
Copy link
Collaborator

Hi @toliver, I guess this is an interesting corner case in the URDF --> SDF conversions, and I guess indeed the correct way to proceed is probably to open a dedicated issue in https://github.com/osrf/sdformat . Related issues are:

@traversaro
Copy link
Collaborator

In that specific case, a possible workaround is just to directly attach camera to link2.

@toliver
Copy link
Author

toliver commented May 18, 2020

Thanks @traversaro . It seems that gazebosim/sdformat#199 is the correct place to continue this discussion.
I'm closing this issue.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants