New in C Turtle

(!) Please ask about problems and questions regarding this tutorial on answers.gazebosim.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Simulate a Spinning Top

Description: Simulate a Spinning Top

Tutorial Level: BEGINNER

Users are highly discouraged from using the documentation and tutorials for Gazebo on this page. Gazebo is now a stand alone project at gazebosim.org. See documentation there, thanks!

Create a Spinning Top

dreidel.png

Suppose we wanted to simulate dynamics of a top inside of Gazebo simulation, first we need to create a simple top model. To use a custom STL mesh as visual and collision geometry of the top, download this STL mesh and copy it into gazebo_worlds by:

Next, create an simple urdf model for the top and save it as top.urdf:

  • <robot name="top_model">
      <link name="my_top">
        <inertial>
          <mass value="1.0" />
          <!-- center of mass (com) is defined w.r.t. link local coordinate system -->
          <!-- give a little y-offset to make the top precess -->
          <origin xyz="0 0.1 2" /> 
          <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
        </inertial>
        <visual>
          <!-- visual origin is defined w.r.t. link local coordinate system -->
          <origin xyz="0 0 0" rpy="-1.5708 0 0" />
          <geometry>
            <mesh filename="dreidel.stl" />
          </geometry>
        </visual>
        <collision>
          <!-- collision origin is defined w.r.t. link local coordinate system -->
          <origin xyz="0 0 0" rpy="-1.5708 0 0" />
          <geometry>
            <mesh filename="dreidel.stl" />
          </geometry>
        </collision>
      </link>
      <gazebo reference="my_top">
        <mu1>10</mu1>
        <mu2>10</mu2>
        <material>Gazebo/Blue</material>
        <turnGravityOff>true</turnGravityOff>
      </gazebo>
    </robot>

    Here the mesh file dreidel.stl is referenced by the visual and collision geometry of the urdf model. Notice that the center of mass location is offset in y-direction by 10cm. This makes the top precess as it spins. If the offset was removed, the top spins upright along its geometric symmetry axis. In the above urdf, the referenced mesh file dreidel.stl is located in the gazebo media resource path as explained here. Alternatively, one can specify the mesh file by using the package:// convention as such:

            <mesh filename="package://gazebo_worlds/Media/models/dreidel.stl" />

To see the top model we've just created in action, start up simulator with an empty world:

  • roslaunch gazebo_worlds empty_world.launch

Next, spawn the top 0.5m above the ground:

  • rosrun gazebo spawn_model -file top.urdf -urdf -model top -z 0.5

Spin up the top by applying a rotational torque:

  • rosservice call gazebo/apply_body_wrench '{body_name: "top::my_top" , wrench: { force: { x: 0.0, y: 0, z: 0 } , torque: { x: 0.0, y: 0 , z: 5.0 } }, start_time: 10000000000, duration: 1000000000 }'

Simulate gravity by applying a downward force on the top:

  • rosservice call gazebo/apply_body_wrench '{body_name: "top::my_top" , wrench: { force: { x: 0.0, y: 0, z: -0.1 } , torque: { x: 0.0, y: 0 , z: 0.0 } }, start_time: 10000000000, duration: -1000000000 }'

The top falls and makes contact with the ground, it stays upright and precesses as it spins.

However, when you apply an opposite wrench and stop the top from spinning the top falls over:

  • rosservice call gazebo/apply_body_wrench '{body_name: "top::my_top" , wrench: { force: { x: 0.0, y: 0, z: 0 } , torque: { x: 0.0, y: 0 , z: -5.0 } }, start_time: 10000000000, duration: 1000000000 }'

For reference, to clear all forces acting on the top, call the corresponding service to clear wrenches:

  • rosservice call gazebo/clear_body_wrenches '{body_name: "top::my_top"}' 

Lastly, clean up the world by deleting the top:

  • rosservice call gazebo/delete_model '{model_name: "top"}'

Wiki: simulator_gazebo/Tutorials/CreatingASpinningTopInGazebo (last edited 2013-06-19 00:05:52 by davetcoleman)