Gazebo | Ignition | Community
Ask Your Question

Revision history [back]

As you observed, XACRO/URDF does not support closed kinematic loops.

However, SDF does support closed kinematic loops.

You either want to define your delta robot directly in SDF
or
include SDF elements within your XACRO/URDF using the <gazebo> tag.


Example Snippet (adding a gas-spring to a robot arm URDF model):

<?xml version="1.0" ?>
<robot name="HEBI_6_DOF_Arm_1">

  ...

  <link name="a_2040_01r_12Z">
    <visual>
      <origin rpy="0 0 0" xyz="0.00144337567 0.0366111248 -0.0110127649"/>
      <geometry>
        <mesh filename="package://hebi_6_dof_arm_generated_urdf/meshes/a_2040_01r_12z_prt.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.00144337567 0.0366111248 -0.0110127649"/>
      <geometry>
        <mesh filename="package://hebi_6_dof_arm_generated_urdf/meshes/a_2040_01r_12z_prt.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-0.0048895444636 0.025165657448 0.0321043733508"/>
      <mass value="0.20946134593484614"/>
      <inertia ixx="0.000172350274153" ixy="6.95173997536e-06" ixz="-1.73640622883e-06" iyy="0.000214786314285" iyz="-3.45081093975e-05" izz="0.000121134255458"/>
    </inertial>
  </link>
  <gazebo reference="a_2040_01r_12Z">
    <selfCollide>True</selfCollide>
    <material>Gazebo/Black</material>
    <mu1>0.1</mu1>
    <mu2>0.1</mu2>
    <kp>10000000</kp>
    <kd>1</kd>
    <minDepth>0.0005</minDepth>
    <maxVel>100</maxVel>
  </gazebo>

  <joint name="a_2040_01r_12Z_to_hebi_x5_9_16Z" type="fixed">
    <parent link="a_2040_01r_12Z"/>
    <child link="hebi_x5_9_16Z"/>
    <origin rpy="1.57079632679 -0.0 -3.14159265359" xyz="-5.38184507892e-17 0.03750000003 0.055"/>
  </joint>

  <gazebo>
    <!-- Add a_2040_01r_12Z to cylinder ball joint -->
    <joint name="a_2040_01r_12Z_to_cylinder" type="ball">
      <parent>a_2040_01r_12Z</parent>
      <child>cylinder</child>
      <pose>0 0 0 0 0 0</pose>
      <axis>
        <limit>
          <lower>-0.785</lower>
          <upper>0.785</upper>
        </limit>
        <xyz>0.0 -1.0 0.0</xyz>
        <dynamics>
          <damping>2.0</damping>
          <friction>0.5</friction>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
          <cfm_damping>1</cfm_damping>
          <limit>
            <cfm>0</cfm>
            <erp>0.2</erp>
          </limit>
        </ode>
      </physics>
    </joint>

    <!-- Add cylinder link -->
    <link name="cylinder">
      <pose frame=''>0.045 -0.05 0.05 0 1.3 0</pose>
      <inertial>
        <pose frame=''>0 0 0.06 0 0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>6.1e-05</ixx>
          <ixy>0.0</ixy>
          <ixz>0.0</ixz>
          <iyy>6.1e-05</iyy>
          <iyz>0.0</iyz>
          <izz>1e-06</izz>
        </inertia>
      </inertial>
      <visual name="cylinder_visual">
        <pose frame=''>0 0 0.06 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.12</length>
            <radius>0.0075</radius>
          </cylinder>
        </geometry>
        <material>
          <script>
            <uri>file://media/materials/scripts/gazebo.material</uri>
            <name>Gazebo/Green</name></script>
        </material>
      </visual>
      <collision name="cylinder_collision">
        <pose frame=''>0 0 0.06 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.12</length>
            <radius>0.0075</radius>
          </cylinder>
        </geometry>
      </collision>
      <velocity_decay/>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>

    <!-- Add cylinder to piston prismatic joint -->
    <joint name="cylinder_to_piston" type="prismatic">
      <parent>cylinder</parent>
      <child>piston</child>
      <pose>0 0 0 0 0 0</pose>
      <axis>
        <limit>
          <lower>-0.1</lower>
          <upper>0.1</upper>
        </limit>
        <xyz>0.0 0.0 1.0</xyz>
        <dynamics>
          <spring_stiffness>2500</spring_stiffness>
          <!--  <spring_stiffness>2000</spring_stiffness> -->
          <!--  <spring_stiffness>111.1111</spring_stiffness> -->
          <spring_reference>0.06</spring_reference>
          <damping>20.0</damping>
          <friction>0.75</friction>
        </dynamics>
        <use_parent_model_frame>0</use_parent_model_frame>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
          <cfm_damping>1</cfm_damping>
          <limit>
            <cfm>0</cfm>
            <erp>0.2</erp>
          </limit>
        </ode>
      </physics>
    </joint>

    <!-- Add piston link -->
    <link name="piston">
      <pose frame=''>0.08356 -0.05 0.06068 0 1.3 0</pose>
      <inertial>
        <pose frame=''>0 0 0.06 0 0 0</pose>
        <mass>0.05</mass>
        <inertia>
          <ixx>6.008e-05</ixx>
          <ixy>0.0</ixy>
          <ixz>0.0</ixz>
          <iyy>6.008e-05</iyy>
          <iyz>0.0</iyz>
          <izz>1.6e-07</izz>
        </inertia>
      </inertial>
      <visual name="cylinder_visual">
        <pose frame=''>0 0 0.06 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.12</length>
            <radius>0.0025</radius>
          </cylinder>
        </geometry>
        <material>
          <script>
            <uri>file://media/materials/scripts/gazebo.material</uri>
            <name>Gazebo/Green</name>
          </script>
        </material>
      </visual>
      <collision name="cylinder_collision">
        <pose frame=''>0 0 0.06 0 0 0</pose>
        <geometry>
          <cylinder>
            <length>0.12</length>
            <radius>0.0025</radius>
          </cylinder>
        </geometry>
      </collision>
      <velocity_decay/>
      <gravity>1</gravity>
      <velocity_decay/>
      <self_collide>0</self_collide>
    </link>

    <!-- Add piston to tubepar_3Z ball joint -->
    <joint name="piston_to_tubepar_3Z" type="ball">
      <parent>piston</parent>
      <child>tubepar_3Z</child>
      <pose>0.2 0.01 -0.0152 0 0 0</pose>
      <axis>
        <xyz>0.0 0.0 -1.0</xyz>
        <dynamics>
          <damping>2.0</damping>
          <friction>0.5</friction>
        </dynamics>
        <use_parent_model_frame>0</use_parent_model_frame>
      </axis>
      <physics>
        <ode>
          <implicit_spring_damper>1</implicit_spring_damper>
          <cfm_damping>1</cfm_damping>
          <limit>
            <cfm>0</cfm>
            <erp>0.2</erp>
          </limit>
        </ode>
      </physics>
    </joint>

  </gazebo>

  <link name="tubepar_3Z">
    <visual>
      <origin rpy="0 0 0" xyz="-1.04532313799e-18 -0.3 -3.11352413402e-18"/>
      <geometry>
        <mesh filename="package://hebi_6_dof_arm_generated_urdf/meshes/tubepar_3z_prt.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="-1.04532313799e-18 -0.3 -3.11352413402e-18"/>
      <geometry>
        <mesh filename="package://hebi_6_dof_arm_generated_urdf/meshes/tubepar_3z_prt.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="-1.04532313799e-18 -0.15 -3.11352413402e-18"/>
      <mass value="0.12133427279164029"/>
      <inertia ixx="0.000923727684155" ixy="0.0" ixz="0.0" iyy="2.74413054377e-05" iyz="0.0" izz="0.000923727713157"/>
    </inertial>
  </link>
  <gazebo reference="tubepar_3Z">
    <selfCollide>True</selfCollide>
    <material>Gazebo/Grey</material>
    <mu1>0.05</mu1>
    <mu2>0.05</mu2>
    <kp>10000000</kp>
    <kd>1</kd>
    <minDepth>0.0005</minDepth>
    <maxVel>100</maxVel>
  </gazebo>

  ...

</robot>