Building your own robot#

In this tutorial we will learn how to build our own robot in SDFormat. We will build a simple two wheeled robot.

You can find the finished SDF file for the tutorial here.

What is SDF#

SDFormat (Simulation Description Format), sometimes abbreviated as SDF, is an XML format that describes objects and environments for robot simulators, visualization, and control.

Building a world#

We will start by building a simple world and then build our robot in it. Open a new file called building_robot.sdf and copy the following code to it.

<?xml version="1.0" ?>
<sdf version="1.10">
    <world name="car_world">
        <physics name="1ms" type="ignored">
            <max_step_size>0.001</max_step_size>
            <real_time_factor>1.0</real_time_factor>
        </physics>
        <plugin
            filename="gz-sim-physics-system"
            name="gz::sim::systems::Physics">
        </plugin>
        <plugin
            filename="gz-sim-user-commands-system"
            name="gz::sim::systems::UserCommands">
        </plugin>
        <plugin
            filename="gz-sim-scene-broadcaster-system"
            name="gz::sim::systems::SceneBroadcaster">
        </plugin>

        <light type="directional" name="sun">
            <cast_shadows>true</cast_shadows>
            <pose>0 0 10 0 0 0</pose>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.2 0.2 0.2 1</specular>
            <attenuation>
                <range>1000</range>
                <constant>0.9</constant>
                <linear>0.01</linear>
                <quadratic>0.001</quadratic>
            </attenuation>
            <direction>-0.5 0.1 -0.9</direction>
        </light>

        <model name="ground_plane">
            <static>true</static>
            <link name="link">
                <collision name="collision">
                <geometry>
                    <plane>
                    <normal>0 0 1</normal>
                    </plane>
                </geometry>
                </collision>
                <visual name="visual">
                <geometry>
                    <plane>
                    <normal>0 0 1</normal>
                    <size>100 100</size>
                    </plane>
                </geometry>
                <material>
                    <ambient>0.8 0.8 0.8 1</ambient>
                    <diffuse>0.8 0.8 0.8 1</diffuse>
                    <specular>0.8 0.8 0.8 1</specular>
                </material>
                </visual>
            </link>
        </model>
    </world>
</sdf>

Save the file, navigate to the directory where you saved the file and launch the simulator:

gz sim building_robot.sdf

Note: You can name your file any name and save it anywhere on your computer.

You should see an empty world with just a ground plane and a sun light. Check World demo to learn how to build your own world.

Building a model#

Under the </model> tag we will add our robot model as follows:

Defining the model#

<model name='vehicle_blue' canonical_link='chassis'>
    <pose relative_to='world'>0 0 0 0 0 0</pose>

Here we define the name of our model vehicle_blue, which should be a unique name among its siblings (other tags or models on the same level). Each model may have one link designated as the canonical_link, the implicit frame of the model is attached to this link. If not defined, the first <link> will be chosen as the canonical link. The <pose> tag is used to define the position and orientation of our model and the relative_to attribute is used to define the pose of the model relative to any other frame. If relative_to is not defined, the model’s <pose> will be relative to the world.

Let’s make our pose relative to the world. The values inside the pose tag are as follows: <pose>X Y Z R P Y</pose>, where the X Y Z represent the position of the frame and R P Y represent the orientation in roll pitch yaw. We set them to zeros which makes the two frames (the model and the world) identical.

Conclusion#

Run the world:

gz sim building_robot.sdf

It should look like this:

two_wheeled_robot

Hurray! We build our first robot. You can learn more details about SDFormat tags here. In the next tutorial we will learn how to move our robot around.

Video walk-through#

A video walk-through of this tutorial is available from our YouTube channel: Gazebo tutorials: Building a robot.