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

Revision history [back]

click to hide/show revision 1
initial version

The problem occurs because of two reasons:

  • Gazebo "merges" child links to their parent when they are connected via a fixed joint, creating only one link with the name of the parent link;
  • Gazebo ignores links without inertial properties

In the first case you have one link that has no inertia: "junta1". However, Gazebo merges all the links that are created by the "barra_model" macro into the "junta1" link, because they are all connected through fixed joints. Then "junta1" "gains" inertia, since the inertia objects of its child links now belong to it. Then it is not ignored.

In the second case, you have two links without inertia, "junta1" and "junta2". They are connected through a continuous joint, so Gazebo will not merge them. This lets "junta1" without inertia, and it gets ignored. Since there is no "junta1", all its children (i.e the whole bar) are not created. That's why the bar disappears.

The solution is to give a simple inertial block to the links, with a small mass. In the code below, I copied the same inertial properties from the spheres in the bar, and added the third link to create the ball joint.

<?xml version="1.0"?>

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

<xacro:macro name="junta_model" params="name parent child *origin">

  <joint name="${name}_joint" type="continuous">
    <parent link="base_link"/>
    <child link="junta1"/>
    <axis xyz="0 1 0" />
  </joint>

  <link name="junta1">
    <inertial>
      <mass value="0.025" />
      <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
    </inertial>
  </link>

  <joint name="${name}_joint2" type="continuous">
    <parent link="junta1"/>
    <child link="junta2"/>
    <axis xyz="0 0 1" />
  </joint>

  <link name="junta2">
    <inertial>
      <mass value="0.025" />
      <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
    </inertial>  
  </link>

  <joint name="${name}_joint3" type="continuous">
    <parent link="junta1"/>
    <child link="junta3"/>
    <axis xyz="1 0 0" />
  </joint>

  <link name="junta3">
    <inertial>
      <mass value="0.025" />
      <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
    </inertial>  
  </link>

<joint name="${name}_jointfixed" type="fixed">
    <xacro:insert_block name="origin" />    
    <parent link="junta3"/>
    <child link="${child}"/>
  </joint>
</xacro:macro>

</robot>

I hope it helps.

The problem occurs because of two reasons:

  • Gazebo "merges" child links to their parent when they are connected via a fixed joint, creating only one link with the name of the parent link;
  • Gazebo ignores links without inertial properties

In the first case you have one link that has no inertia: "junta1". However, Gazebo merges all the links that are created by the "barra_model" macro into the "junta1" link, because they are all connected through fixed joints. Then "junta1" "gains" inertia, since the inertia objects of its child links now belong to it. Then it is not ignored.

In the second case, you have two links without inertia, "junta1" and "junta2". They are connected through a continuous joint, so Gazebo will not merge them. This lets "junta1" without inertia, and it gets ignored. Since there is no "junta1", all its children (i.e the whole bar) are not created. That's why the bar disappears.

The solution is to give a simple inertial block to the links, with a small mass. In the code below, I copied the same inertial properties from the spheres in the bar, and added the third link to create the ball joint.

<?xml version="1.0"?>

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

<xacro:macro name="junta_model" params="name parent child *origin">

  <joint name="${name}_joint" type="continuous">
    <parent link="base_link"/>
    <child link="junta1"/>
    <axis xyz="0 1 0" />
  </joint>

  <link name="junta1">
    <inertial>
      <mass value="0.025" />
      <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
    </inertial>
  </link>

  <joint name="${name}_joint2" type="continuous">
    <parent link="junta1"/>
    <child link="junta2"/>
    <axis xyz="0 0 1" />
  </joint>

  <link name="junta2">
    <inertial>
      <mass value="0.025" />
      <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
    </inertial>  
  </link>

  <joint name="${name}_joint3" type="continuous">
    <parent link="junta1"/>
    <child link="junta3"/>
    <axis xyz="1 0 0" />
  </joint>

  <link name="junta3">
    <inertial>
      <mass value="0.025" />
      <inertia ixx="5.8083e-4" ixy="0" ixz="0" iyy="3.0833e-5" iyz="0" izz="5.9083e-4" />
    </inertial>  
  </link>

<joint name="${name}_jointfixed" type="fixed">
    <xacro:insert_block name="origin" />    
    <parent link="junta3"/>
    <child link="${child}"/>
  </joint>
</xacro:macro>

</robot>

</robot>

I hope it helps. helps.