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

Revision history [back]

I had the same problem with a pioneer3at package I found on the web. The problem was that the inertia information for the wheels was set to be the identity matrix:

  <inertial>
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <mass value="1"/>
  <inertia  ixx="1" ixy = "0" ixz = "0"  iyy="1"  iyz = "0"  izz="1" /> 
  </inertial>

When ever I would move the robot through teleopt, I would get some bouncing behavior. I replaced it with the proper formula for a the interia matrix of a cylinder, and the runs smoothly:

<macro name="cylinder_inertia" params="m r h">
          <inertia  ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
                    iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
                    izz="${m*r*r/2}" /> 
</macro>


    <inertial>
        <origin xyz="0 0 0" rpy="0 0 0"/>
            <mass value="1"/>
            <cylinder_inertia  m="1" r="0.1" h="0.11" />
   </inertial>

When you run Gazebo, go to the visualusation tabe and check the inertia view and you will see pink boxes. These should be more or less within the meshes of your vehicle. I now have fully working version of the pioneer3at for indigo under ubuntu 14.04