Home | Tutorials | Wiki | Issues
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

The issue is that <origin>, <mass>, and <inertia> tags must be nested inside a <inertial> element for each of the links, instead of being nested in the <link> tag.

correct:

    <link name="${leg_name}_psi_link">
        <visual><geometry><sphere radius=".01"/></geometry></visual>
        <collision><geometry><sphere radius=".005"/></geometry></collision>
        <inertial>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <mass value="${gimbal_link_mass}"/>
            <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1"  iyz="0.0" izz="0.1"/>
        </inertial>
    </link>

incorrect:

    <link name="${leg_name}_psi_link">
        <visual><geometry><sphere radius=".01"/></geometry></visual>
        <collision><geometry><sphere radius=".005"/></geometry></collision>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <mass value="${gimbal_link_mass}"/>
        <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/>
    </link>

additional notes:

  • un-actuated joints should not have a <transmission> tag
    • gazebo will not load links with zero mass