This tutorial was written for 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. |
Gazebo ROS API for C-Turtle
Description: Gazebo ROS API for C-Turtle. Manipulate and interact with simulation and simulated objects.Tutorial Level: BEGINNER
Next Tutorial: Simulate a Spinning Top in Gazebo
Contents
- Tutorial Introduction
- Start Up Simulator
- Gazebo ROS Parameters, Services and Topics
- Spawn and Delete Models in Simulation
- Set and Get Model Pose and Twist in Simulation via Service
- Retrieving Simulation World and Object Properties
- Retrieving Model and Link States Using Topics
- Apply Wrenches to Links
- Apply Efforts to Joints in Simulation
- Pausing and Unpausing Physics
- Set Model Pose and Twist in Simulation via Topics
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!
Tutorial Introduction
As of C Turtle release, Gazebo provides a set of ROS API's that allows users to modify and get information about various aspects of the simulated world. In the following sections, we will demonstrate some of the utilities for manipulating the simulation world and objects. The complete list of ROS messages and services for gazebo can be found here.
Terminologies
In the following context, the pose and twist of a rigid body object is referred to as its state. An object also has intrinsic properties, such as mass and friction coefficients. In Gazebo, a Body refers to a rigid body, synonymous to Link in the urdf context. A Gazebo Model is a conglomeration of Bodies connected by Joints.
Start Up Simulator
- Make sure gazebo is compiled
rosmake gazebo_worlds
- Startup a roscore and launch an empty world with only the ground plane
roslaunch gazebo_worlds empty_world.launch
For the rest of the tutorial, we'll assume the empty world is running.
Gazebo ROS Parameters, Services and Topics
Details of ROS parameters, services and topics for gazebo simulation can be found on gazebo page.
Spawn and Delete Models in Simulation
Spawn Model
Models in gazebo can be spawned and deleted dynamically using the services gazebo/spawn_model and gazebo/delete_model. A helper script spawn_model is provided for calling the model spawning services offered by gazebo ros node. Here's an example on how to use the script.
- Spawn a gazebo table model by the issuing the following command in another terminal
rosrun gazebo spawn_model -file `rospack find gazebo_worlds`/objects/desk1.model -gazebo -model desk1 -x 0
Where the various options for the helper script are defined as:$ rosrun gazebo spawn_model Commands: -[urdf|gazebo] - specify incoming xml is urdf or gazebo format -[file|param] [<file_name>|<param_name>] - source of the model xml -model <model_name> - name of the model to be spawned. -reference_frame <entity_name> - optinal: name of the model/body where initial pose is defined. If left empty or specified as "world", gazebo world frame is used. -namespace <ros_namespace> - optional: all subsequent ROS interface plugins will be inside of this namespace. -x <x in meters> - optional: initial pose, use 0 if left out -y <y in meters> - optional: initial pose, use 0 if left out -z <z in meters> - optional: initial pose, use 0 if left out -R <roll in radians> - optional: initial pose, use 0 if left out -P <pitch in radians> - optional: initial pose, use 0 if left out -Y <yaw in radians> - optional: initial pose, use 0 if left out
Alternatively, by storing the model XML on the ROS parameter server allows other ROS applications to access the same model urdf at a later time for other purposes. To spawn a model from a ROS parameter, first call rosparam to push the model XML onto the ROS parameter server.
rosparam load `rospack find gazebo_worlds`/objects/coffee_cup.model coffee_cup_description
Then use -param option in spawn_model to spawn:
rosrun gazebo spawn_model -param coffee_cup_description -gazebo -model coffee_cup -x 0 -z 2
Delete Model
- Try deleting the coffee cup from simulation by calling the model deletion service:
rosservice call gazebo/delete_model '{model_name: coffee_cup}'
Above calls the gazebo/delete_model service offered by the gazebo node and passing in DeleteModel service request with model_name set to the name of the model you wish to delete.
Set and Get Model Pose and Twist in Simulation via Service
- To demonstrate how to manipulate pose and twist of a model in simulation, first spawn a model:
rosrun gazebo spawn_model -file `rospack find gazebo_worlds`/objects/000.580.67.model -gazebo -model cup -z 2
Note that the model 000.580.67.model has gravity disabled1.
Next, we can set the pose and twist of the floating cup by calling the /gazebo/set_model_state service:
rosservice call /gazebo/set_model_state '{model_state: { model_name: cup, pose: { position: { x: 0, y: 0 ,z: 1 }, orientation: {x: 0, y: 0.491983115673, z: 0, w: 0.870604813099 } }, twist: { linear: {x: 0.0 , y: 0 ,z: 0 } , angular: { x: 0.0 , y: 0 , z: 0.0 } } , reference_frame: world } }'
The above service call fills the service request and sets the position and orientation of the cup model to some custom pose with respect to the gazebo-world frame 2, and sets the body twists to zero.
- To verify what we've done above, you can retrieve the pose and twist of a model by calling:
rosservice call gazebo/get_model_state '{model_name: cup}'
you should see something that looks like this:pose: position: x: 2.0439552828e-11 y: 0.0 z: 0.999999956873 orientation: x: 0.0 y: 0.491983115673 z: 0.0 w: 0.870604813099 twist: linear: x: 0.0 y: 0.0 z: 0.0 angular: x: 0.0 y: 0.0 z: 0.0 success: True status_message: GetModelState: got properties
- Finally, let's test a nonzero angular twist (0,0,0.1) to make the cup rotate in place:
rosservice call /gazebo/set_model_state '{model_state: { model_name: cup, pose: { position: { x: 0, y: 0 ,z: 1 }, orientation: {x: 0.491983115673, y: 0, z: 0, w: 0.870604813099 } }, twist: { linear: {x: 0.0 , y: 0 ,z: 0 } , angular: { x: 0.0 , y: 0 , z: 0.1 } } , reference_frame: world } }'
Retrieving Simulation World and Object Properties
- Continuing from last step, you can get a list of models (cup and desk) in the world by running:
$ rosservice call gazebo/get_world_properties sim_time: 364.582 model_names: ['clock', 'gplane', 'point_white', 'desk1', 'cup'] rendering_enabled: True success: True status_message: GetWorldProperties: got properties
- and retrieve details of a specific model by
$ rosservice call gazebo/get_model_properties '{model_name: desk1}' parent_model_name: '' canonical_body_name: '' body_names: ['desk1'] geom_names: ['desk1base_geom', 'desk1leg_geom', 'desk1top_geom'] joint_names: [] child_model_names: ['desk1'] is_static: False success: True status_message: GetModelProperties: got properties
Retrieving Model and Link States Using Topics
Gazebo publishes /gazebo/link_states and /gazebo/model_states topic, containing pose and twist information of objects in simulation with respect to the gazebo world frame. You can see these in action by typing:
rostopic echo -n 1 /gazebo/model_states
orrostopic echo -n 1 /gazebo/link_states
To reiterate, a link is defined as a rigid body with given inertial, visual and collision properties. Whereas, a model is defined as a collection of links and joints. The state of a model is the state of its canonical link. Given that urdf enforces a tree structure, the canonical link of a model is defined by its root link.
Lastly, delete the current model from simulation by calling gazebo/delete_model service:
rosservice call gazebo/delete_model '{model_name: cup}'
Apply Wrenches to Links
- To demonstrate wrench applications on a gazebo body, let's spawn an object with gravity turned off,
rosrun gazebo spawn_model -file `rospack find gazebo_worlds`/objects/000.580.67.model -gazebo -model cup -z 1
Apply a 0.01 Nm torque at the cup origin for 1 second duration by calling the gazebo/apply_body_wrench service, and you should see the cup spin up along the positive x-axis:
rosservice call gazebo/apply_body_wrench '{body_name: "cup::000_580_67_body" , wrench: { torque: { x: 0.01, y: 0 , z: 0 } }, start_time: 10000000000, duration: 1000000000 }'
- Apply a reverse -0.01 Nm torque for 1 second duration at the cup origin and the cup should stop rotating:
rosservice call gazebo/apply_body_wrench '{body_name: "cup::000_580_67_body" , wrench: { torque: { x: -0.01, y: 0 , z: 0 } }, start_time: 10000000000, duration: 1000000000 }'
- In general, torques with a negative duration persists indefinitely. To clear any active wrenches applied to the body, you can:
rosservice call gazebo/clear_body_wrenches '{body_name: "cup::000_580_67_body"}'
- Finally, clean up our simulation world by deleting the cup:
rosservice call gazebo/delete_model '{model_name: cup}'
Apply Efforts to Joints in Simulation
You can also apply efforts to joints, but to do so you will need a more complex model that has a joint. Create an urdf file and call it single_joint.urdf
<?xml version="1.0" ?> <robot name="single_joint"> <gazebo reference="base"> <material>Gazebo/GrassFloor</material> </gazebo> <link name="world"/> <joint name="link_joint" type="continuous"> <axis xyz="0 0 1"/> <parent link="world"/> <origin rpy="0 0 0" xyz="0 0 1"/> <child link="link"/> <dynamics damping="0.1"/> </joint> <link name="link"> <inertial> <mass value="10"/> <origin xyz="0 0 0"/> <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/> </inertial> <visual> <origin rpy="0 0 1" xyz="0 0 0"/> <geometry> <box size="0.2 1.0 0.2"/> </geometry> </visual> <collision> <origin rpy="0 0 1" xyz="0 0 0"/> <geometry> <box size="0.2 1.0 0.2"/> </geometry> </collision> </link> <gazebo reference="link"> <material>Gazebo/GrassFloor</material> <turnGravityOff>true</turnGravityOff> </gazebo> </robot>
- Spawn the model you have just created:
rosrun gazebo spawn_model -file single_joint.urdf -urdf -model single_joint
Next, call gazebo/apply_joint_effort to apply torque to the joint
rosservice call gazebo/apply_joint_effort '{joint_name: link_joint, effort: 0.01, start_time: 10000000000, duration: 1000000000}'
And the link should start rotating.- To clear efforts on joints for a specific joint, call
rosservice call gazebo/clear_joint_forces '{joint_name: link_joint}'
- Finally,
rosservice call gazebo/delete_model '{model_name: single_joint}'
Pausing and Unpausing Physics
- You can pause physics engine by calling
rosservice call gazebo/pause_physics
When simulation is paused, simulation time is stopped and objects become static. However, gazebo's internal update loop (such as custom dynamic plugin updates) are still running, but given that the simulation time is not changing, anything throttled by simulation time will not update. - To resume simulation, unpause the physic engine by calling
rosservice call gazebo/unpause_physics
Set Model Pose and Twist in Simulation via Topics
Topics can be used to set the pose and twist of a model rapidly without waiting for the pose setting action to complete. To do so, publish the desired model state message to gazebo/set_model_state topic. For example, to test pose setting via topics, spawn a table
rosrun gazebo spawn_model -file `rospack find gazebo_worlds`/objects/desk1.model -gazebo -model desk1
and set the pose of the table by publishing on the gazebo/set_model_state topic:
rostopic pub -r 10 gazebo/set_model_state gazebo/ModelState '{model_name: desk1, pose: { position: { x: 0, y: 0, z: 2 }, orientation: {x: 0, y: 0.491983115673, z: 0, w: 0.870604813099 } }, twist: { linear: { x: 0, y: 0, z: 0 }, angular: { x: 0, y: 0, z: 0} }, reference_frame: world }'
In this example, ModelState message is published at 10Hz, you can see the table falling between every publication.