This tutorial describes the details of a SDF Model Object.
SDF Models can range from simple shapes to complex robots. It refers to the <model>
SDF tag, and is essentially a collection of links, joints, collision objects, visuals, and plugins. Generating a model file can be difficult depending on the complexity of the desired model. This page will offer some tips on how to build your models.
Links: A link contains the physical properties of one body of the model. This can be a wheel, or a link in a joint chain. Each link may contain many collision and visual elements. Try to reduce the number of links in your models in order to improve performance and stability. For example, a table model could consist of 5 links (4 for the legs and 1 for the top) connected via joints. However, this is overly complex, especially since the joints will never move. Instead, create the table with 1 link and 5 collision elements.
Collision: A collision element encapsulates a geometry that is used for collision checking. This can be a simple shape (which is preferred), or a triangle mesh (which consumes greater resources). A link may contain many collision elements.
Visual: A visual element is used to visualize parts of a link. A link may contain 0 or more visual elements.
Inertial: The inertial element describes the dynamic properties of the link, such as mass and rotational inertia matrix.
Sensor: A sensor collects data from the world for use in plugins. A link may contain 0 or more sensors.
Light: A light element describes a light source attached to a link. A link may contain 0 or more lights.
Joints: A joint connects two links. A parent and child relationship is established along with other parameters such as axis of rotation, and joint limits.
Plugins: A plugin is a shared library created by a third party to control a model.
This step involves gathering all the necessary 3D mesh files that are required to build your model. Gazebo provides a set of simple shapes: box, sphere, and cylinder. If your model needs something more complex, then continue reading.
Meshes come from a number of places. Google's 3D warehouse is a good repository of 3D models. Alternatively, you may already have the necessary files. Finally, you can make your own meshes using a 3D modeler such as Blender or Sketchup.
Gazebo requires that mesh files be formatted as STL, Collada or OBJ, with Collada and OBJ being the preferred formats.
Tip: Use your 3D modeling software to move each mesh so that it is centered on the origin. This will make placement of the model in Gazebo significantly easier.
Tip: Collada and OBJ file formats allow you to attach materials to the meshes. Use this mechanism to improve the visual appearance of your meshes.
Tip: Keep meshes simple. This is especially true if you plan on using the mesh as a collision element. A common practice is to use a low polygon mesh for a collision element, and higher polygon mesh for the visual. An even better practice is to use one of the built-in shapes (box, sphere, cylinder) as the collision element.
Start by creating an extremely simple model file, or copy an existing model file. The key here is to start with something that you know works, or can debug very easily.
Here is a very rudimentary minimum box model file with just a unit sized box shape as a collision geometry and the same unit box visual with unit inertias:
Create the box.sdf
model file
gedit box.sdf
Copy the following contents into box.sdf:
<?xml version='1.0'?>
<sdf version="1.4">
<model name="my_model">
<pose>0 0 0.5 0 0 0</pose>
<static>true</static>
<link name="link">
<inertial>
<mass>1.0</mass>
<inertia> <!-- inertias are tricky to compute -->
<!-- http://gazebosim.org/tutorials?tut=inertia&cat=build_robot -->
<ixx>0.083</ixx> <!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
<ixy>0.0</ixy> <!-- for a box: ixy = 0 -->
<ixz>0.0</ixz> <!-- for a box: ixz = 0 -->
<iyy>0.083</iyy> <!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
<iyz>0.0</iyz> <!-- for a box: iyz = 0 -->
<izz>0.083</izz> <!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
</link>
</model>
</sdf>
Note that the origin of the Box-geometry is at the geometric center of the box, so in order to have the bottom of the box flush with the ground plane, an origin of <pose>0 0 0.5 0 0 0</pose>
is added to raise the box above the ground plane.
Tip: The above example sets the simple box model to be static, which makes the model immovable. This feature is useful during model creation. Once you are done creating your model, set the
<static>
tag to false if you want your model to be movable.
With a working .sdf
file, slowly start adding in more complexity.
Here is a good order in which to add features:
With each new addition, load the model using the graphical client to make sure your model is correct.
However, the box.sdf
file alone isn't enough to be able to load the model into the graphical client. You must also setup your model directory correctly, which you will learn in the next tutorial: Make a Mobile Robot.