Home | Tutorials | Wiki | Issues
Ask Your Question

Revision history [back]

The <visual> and <collision> elements of your wheel links do not line up:

To see this,

  1. Load your model in Gazebo.
  2. Select View > Show collision.
  3. Select View > Transparent.
    (You can learn about the other View options in the Gazebo GUI Tutorial)

image description


Looking at your wheel link macro, the <visual> element is rolled by pi/2 radians but the <collision> element is not...

Broken:

  <xacro:macro name="wheel_position_macro" params="prefix suffix reflect1 reflect2">
    <link name="${prefix}_${suffix}_wheel">
      <visual>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
        <geometry>
          <cylinder radius="${wheel_diameter/2}" length="${wheel_thickness}"/>
        </geometry>
        <material name="black"/>
      </visual>
      <collision>
        <geometry>
          <cylinder radius="${wheel_diameter/2}" length="${wheel_thickness}"/>
        </geometry>  
        ...
      </collision>
      <xacro:default_inertial mass="${wheel_mass}"/>
    </link>
    ...
  </xacro:macro>

Fixed:

  <xacro:macro name="wheel_position_macro" params="prefix suffix reflect1 reflect2">
    <link name="${prefix}_${suffix}_wheel">
      <visual>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
        <geometry>
          <cylinder radius="${wheel_diameter/2}" length="${wheel_thickness}"/>
        </geometry>
        <material name="black"/>
      </visual>
      <collision>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
        <geometry>
          <cylinder radius="${wheel_diameter/2}" length="${wheel_thickness}"/>
        </geometry>  
        ...
      </collision>
      <xacro:default_inertial mass="${wheel_mass}"/>
    </link>
    ...
  </xacro:macro>

(You can learn more about URDF XML at http://wiki.ros.org/urdf/XML/link)


One final note:

The inertial values are too high. Check out the Inertial parameters of triangle meshes.

The <visual> and <collision> elements of your wheel links do not line up:

To see this,

  1. Load your model in Gazebo.
  2. Select View > Show collision.
  3. Select View > Transparent.
    (You can learn about the other View options in the Gazebo GUI Tutorial)

image description


Looking at your wheel link macro, the <visual> element is rolled by pi/2 radians but the <collision> element is not...

Broken:

  <xacro:macro name="wheel_position_macro" params="prefix suffix reflect1 reflect2">
    <link name="${prefix}_${suffix}_wheel">
      <visual>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
        <geometry>
          <cylinder radius="${wheel_diameter/2}" length="${wheel_thickness}"/>
        </geometry>
        <material name="black"/>
      </visual>
      <collision>
        <geometry>
          <cylinder radius="${wheel_diameter/2}" length="${wheel_thickness}"/>
        </geometry>  
        ...
      </collision>
      <xacro:default_inertial mass="${wheel_mass}"/>
    </link>
    ...
  </xacro:macro>

Fixed:

  <xacro:macro name="wheel_position_macro" params="prefix suffix reflect1 reflect2">
    <link name="${prefix}_${suffix}_wheel">
      <visual>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
        <geometry>
          <cylinder radius="${wheel_diameter/2}" length="${wheel_thickness}"/>
        </geometry>
        <material name="black"/>
      </visual>
      <collision>
        <origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
        <geometry>
          <cylinder radius="${wheel_diameter/2}" length="${wheel_thickness}"/>
        </geometry>  
        ...
      </collision>
      <xacro:default_inertial mass="${wheel_mass}"/>
    </link>
    ...
  </xacro:macro>

(You can learn more about URDF XML at http://wiki.ros.org/urdf/XML/link)


One final note:

The inertial values are too high. Check out the Inertial parameters of triangle meshes.

tutorial.