Note: This tutorial assumes that you have completed the previous tutorials: Installing and Starting Gazebo. |
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. |
Creating and Spawning Custom URDF Objects in Simulation
Description: Creating and Spawning Custom URDF objects in simulationTutorial Level: BEGINNER
Next Tutorial: Manipulating objects in the simulation world using ROS API
Contents
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!
Spawning Custom Objects in Simulation
Description: Here we demonstrate how to create a simple box urdf model using the box geometric primitive and spawn it in a simulated empty world.
Start Simulation of an Empty World
Start an empty world simulation
roslaunch gazebo_worlds empty_world.launch
Create a Simple Box URDF
Create an URDF for an object and save it as object.urdf:
1 <robot name="simple_box">
2 <link name="my_box">
3 <inertial>
4 <origin xyz="2 0 0" />
5 <mass value="1.0" />
6 <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="100.0" iyz="0.0" izz="1.0" />
7 </inertial>
8 <visual>
9 <origin xyz="2 0 1"/>
10 <geometry>
11 <box size="1 1 2" />
12 </geometry>
13 </visual>
14 <collision>
15 <origin xyz="2 0 1"/>
16 <geometry>
17 <box size="1 1 2" />
18 </geometry>
19 </collision>
20 </link>
21 <gazebo reference="my_box">
22 <material>Gazebo/Blue</material>
23 </gazebo>
24 </robot>
Here the origins of the inertial center, visual and collision geometry centers are offset in +x by 2m relative to the model origin. The box geometry primitive is used here for visual and collision geometry, and has sizes 1m wide, 1m deep and 2m tall. Note that visual and collision geometries do not always have to be the same, sometimes you want to use a simpler collision geometry to save collision detection time when running a dynamic simulation. The box inertia is defined as 1kg mass and principal moments of inertia ixx=izz=1 kg*m2 and iyy=100 kg*m2.
Spawn Model in Simulation
To spawn above URDF object at height z = 1 meter and assign the name of the model in simulation to be my_object:
rosrun gazebo_ros spawn_model -file `pwd`/object.urdf -urdf -z 1 -model my_object
Here spawn_model from gazebo package is a convenience command-line tool for accessing gazebo spawning service gazebo/spawn_model.
Spawn Additional Example Objects in Simulation
Several sample objects are provided in gazebo_worlds/objects. For example, you can spawn a desk by typing
roslaunch gazebo_worlds table.launch
This should create a table in the simulator GUI (you might have to zoom out and mouse around to find it), then terminate.
Taking a brief look at table.launch:
1 <launch>
2 <!-- send table urdf to param server -->
3 <param name="table_description" command="$(find xacro)/xacro.py $(find gazebo_worlds)/objects/table.urdf.xacro" />
4
5 <!-- push table_description to factory and spawn robot in gazebo -->
6 <node name="spawn_table" pkg="gazebo" type="spawn_model" args="-urdf -param table_description -z 0.01 -model table_model" respawn="false" output="screen" />
7 </launch>
The launch file loads table.urdf.xacro urdf XML file onto the ROS parameter server (after first passing it through the xacro preprocessor). Error: No code_block found
Then calls spawn_model node to spawn the model in simulation. Error: No code_block found The spawn_table node gets the XML string from the parameter server and passes it on to Gazebo to spawn the object in the simulated world.
- Similarly, to spawn a coffee cup on the table:
roslaunch gazebo_worlds coffee_cup.launch
Disclaimer: Spawning the coffee cup currently does not work on ROS version more recent than electric.
Next Tutorial: Manipulating objects in the simulation world