Skip to content

Sec. 3: Creating a custom robot and sensor model

Ramviyas Parasuraman edited this page Feb 23, 2018 · 1 revision

Creating a custom robot with a custom sensor on Gazebo using SDF files

Overview

In the previous section, we learned how to run and control an existing robot on Gazebo. If our work requires a custom robot to be built, this section provides introductory instructions on how to get started with a basic setup. The Model Editor in later versions of Gazebo lets us construct simple models right in the Graphical User Interface (GUI). But for more complex models, you'll need to learn how to write SDF files.

This tutorial demonstrates Gazebo's basic model management, and exercises familiarity with basic model representation inside the model database by taking the user through the process of creating a .sdf file for a two-wheeled mobile robot that uses:

  • a differential drive mechanism for movement
  • a mesh as visual
  • a custom light sensor based on camera for reading the environment

Setup your model directory

When creating our own model, we must adhere to the formatting rules for the Gazebo Model Database directory structure. Therefore, it is recommended that you familiarize yourself with the Model Database documentation and model description formats at SDF reference.

  1. Create a model directory where we call our robot '2wd_mr', short for 2 wheel drive mobile robot:

    mkdir -p ~/.gazebo/models/2wd_mr
    
  2. Create a model config file:

    gedit ~/.gazebo/models/2wd_mr/model.config
    
  3. Paste in the following contents:

    <?xml version="1.0"?>
    <model>
      <name>2wd_mr</name>
      <version>1.0</version>
      <sdf version='1.4'>model.sdf</sdf>
    
      <author>
       <name>My Name</name>
       <email>me@my.email</email>
      </author>
    
      <description>
        My awesome robot with an awesome sensor.
      </description>
    </model>
    
  4. Create a model.sdf file:

    gedit ~/.gazebo/models/2wd_mr/model.sdf
    
  5. Paste in the following:

    <?xml version='1.0'?>
    <sdf version='1.4'>
      <model name="2wd_mr">
      </model>
    </sdf>
    

At this point, we have the basic content for a model. The model.config file describes the robot with some extra metadata. The model.sdf file contains the necessary tags to instantiate a model named 2wd_mr using Gazebo linked against SDF version 1.4.

Build the Model's Structure

Our first robot will have a rectangular base with two wheels on the side and a caster wheel at the rear. First, we lay out the basic shapes of the model. To do this we will make our model static, which means it will be ignored by the physics engine. As a result, the model will stay in one place and allow us to properly align all the components.

Open the ~/.gazebo/models/2wd_mr/model.sdf file.

  1. Make the model static by adding a <static>true</static> element:
    <?xml version='1.0'?>
    <sdf version='1.4'>
      <model name="2wd_mr">
        <static>true</static>
      </model>
    </sdf>
  1. Add the rectangular base of size 0.4 x 0.2 x 0.1 meters:
    <?xml version='1.0'?>
      <sdf version='1.4'>
        <model name="2wd_mr">
        <static>true</static>
          <link name='chassis'>
            <pose>0 0 .1 0 0 0</pose>

            <collision name='collision'>
              <geometry>
                <box>
                  <size>.4 .2 .1</size>
                </box>
              </geometry>
            </collision>

            <visual name='visual'>
              <geometry>
                <box>
                  <size>.4 .2 .1</size>
                </box>
              </geometry>
            </visual>
          </link>
      </model>
    </sdf>

The collision element specifies the shape used by the collision detection engine. The visual element specifies the shape used by the rendering engine.

  1. Try out your model by running gazebo, and importing your model through the Insert Model interface on the GUI.

    gazebo
    

    You should see a white box floating .1 meters above the ground plane.

  2. Now we can add a caster to the robot. The caster is a sphere with no friction. This kind of caster is better than adding a wheel with a joint since it places fewer constraints on the physics engine.

    <?xml version='1.0'?>
    <sdf version='1.4'>
      <model name="2wd_mr">
        <static>true</static>
        <link name='chassis'>
          <pose>0 0 .1 0 0 0</pose>
          <collision name='collision'>
            <geometry>
              <box>
                <size>.4 .2 .1</size>
              </box>
            </geometry>
          </collision>

          <visual name='visual'>
            <geometry>
              <box>
                <size>.4 .2 .1</size>
              </box>
            </geometry>
          </visual>
          <collision name='caster_collision'>
            <pose>-0.15 0 -0.05 0 0 0</pose>
            <geometry>
                <sphere>
                <radius>.05</radius>
              </sphere>
            </geometry>

            <surface>
              <friction>
                <ode>
                  <mu>0</mu>
                  <mu2>0</mu2>
                  <slip1>1.0</slip1>
                  <slip2>1.0</slip2>
                </ode>
              </friction>
            </surface>
          </collision>

          <visual name='caster_visual'>
            <pose>-0.15 0 -0.05 0 0 0</pose>
            <geometry>
              <sphere>
                <radius>.05</radius>
              </sphere>
            </geometry>
          </visual>
        </link>
      </model>
    </sdf>

Try out your model to make sure the caster appears at the end of the robot (you don't need to restart Gazebo; it will reload your modified model from disk each time you insert it):

  1. Add a left wheel:
    <?xml version='1.0'?>
    <sdf version='1.4'>
      <model name="2wd_mr">
        <static>true</static>
        <link name='chassis'>
          <pose>0 0 .1 0 0 0</pose>
          <collision name='collision'>
            <geometry>
              <box>
                <size>.4 .2 .1</size>
              </box>
            </geometry>
          </collision>

          <visual name='visual'>
            <geometry>
              <box>
                <size>.4 .2 .1</size>
              </box>
            </geometry>
          </visual>

          <collision name='caster_collision'>
            <pose>-0.15 0 -0.05 0 0 0</pose>
            <geometry>
              <sphere>
              <radius>.05</radius>
            </sphere>
          </geometry>

          <surface>
            <friction>
              <ode>
                <mu>0</mu>
                <mu2>0</mu2>
                <slip1>1.0</slip1>
                <slip2>1.0</slip2>
              </ode>
            </friction>
          </surface>
        </collision>

        <visual name='caster_visual'>
          <pose>-0.15 0 -0.05 0 0 0</pose>
          <geometry>
            <sphere>
              <radius>.05</radius>
            </sphere>
          </geometry>
        </visual>
      </link>
      <link name="left_wheel">
        <pose>0.1 0.13 0.1 0 1.5707 1.5707</pose>
        <collision name="collision">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </visual>
      </link>
      </model>
    </sdf>

Run Gazebo, insert your robot model and make sure the wheel has appeared and is in the correct location.

  1. We can make a right wheel by copying the left wheel, and adjusting the wheel link's pose:
    <?xml version='1.0'?>
    <sdf version='1.4'>
      <model name="2wd_mr">
        <static>true</static>
        <link name='chassis'>
          <pose>0 0 .1 0 0 0</pose>
          <collision name='collision'>
            <geometry>
              <box>
                <size>.4 .2 .1</size>
              </box>
            </geometry>
          </collision>

          <visual name='visual'>
            <geometry>
              <box>
                <size>.4 .2 .1</size>
              </box>
            </geometry>
          </visual>

          <collision name='caster_collision'>
            <pose>-0.15 0 -0.05 0 0 0</pose>
            <geometry>
              <sphere>
              <radius>.05</radius>
            </sphere>
          </geometry>

          <surface>
            <friction>
              <ode>
                <mu>0</mu>
                <mu2>0</mu2>
                <slip1>1.0</slip1>
                <slip2>1.0</slip2>
              </ode>
            </friction>
          </surface>
        </collision>

        <visual name='caster_visual'>
          <pose>-0.15 0 -0.05 0 0 0</pose>
          <geometry>
            <sphere>
              <radius>.05</radius>
            </sphere>
          </geometry>
        </visual>
      </link>
      <link name="left_wheel">
        <pose>0.1 0.13 0.1 0 1.5707 1.5707</pose>
        <collision name="collision">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </visual>
      </link>
      <link name="right_wheel">
        <pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose>
        <collision name="collision">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </visual>
      </link>
      </model>
    </sdf>

At this point, the robot should have a chassis with a caster and two wheels as shown below.

  1. Make the model dynamic by setting <static> to false, and add two hinge joints for the left and right wheels.
    <?xml version='1.0'?>
    <sdf version='1.4'>
      <model name="2wd_mr">
        <static>false</static>
        <link name='chassis'>
          <pose>0 0 .1 0 0 0</pose>
          <collision name='collision'>
            <geometry>
              <box>
                <size>.4 .2 .1</size>
              </box>
            </geometry>
          </collision>

          <visual name='visual'>
            <geometry>
              <box>
                <size>.4 .2 .1</size>
              </box>
            </geometry>
          </visual>

          <collision name='caster_collision'>
            <pose>-0.15 0 -0.05 0 0 0</pose>
            <geometry>
              <sphere>
              <radius>.05</radius>
            </sphere>
          </geometry>

          <surface>
            <friction>
              <ode>
                <mu>0</mu>
                <mu2>0</mu2>
                <slip1>1.0</slip1>
                <slip2>1.0</slip2>
              </ode>
            </friction>
          </surface>
        </collision>

        <visual name='caster_visual'>
          <pose>-0.15 0 -0.05 0 0 0</pose>
          <geometry>
            <sphere>
              <radius>.05</radius>
            </sphere>
          </geometry>
        </visual>
      </link>
      <link name="left_wheel">
        <pose>0.1 0.13 0.1 0 1.5707 1.5707</pose>
        <collision name="collision">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </visual>
      </link>

      <link name="right_wheel">
        <pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose>
        <collision name="collision">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <cylinder>
              <radius>.1</radius>
              <length>.05</length>
            </cylinder>
          </geometry>
        </visual>
      </link>
      <joint type="revolute" name="left_wheel_hinge">
        <pose>0 0 -0.03 0 0 0</pose>
        <child>left_wheel</child>
        <parent>chassis</parent>
        <axis>
          <xyz>0 1 0</xyz>
        </axis>
      </joint>

      <joint type="revolute" name="right_wheel_hinge">
        <pose>0 0 0.03 0 0 0</pose>
        <child>right_wheel</child>
        <parent>chassis</parent>
        <axis>
          <xyz>0 1 0</xyz>
        </axis>
      </joint>
      </model>
    </sdf>

The two joints rotate about the y-axis <xyz>0 1 0</xyz>, and connect each wheel to the chassis.

  1. Start gazebo and spawn your robot model. Select your robot model and click on the dots to the right of the screen and drag them to the left to open the hidden panel.

  2. Under the Force tab, increase the force applied to each joint to about 0.1N-m. The robot should start to move!

Congrats! you now have a basic mobile robot.

Attach a Mesh as Visual

Meshes can add realism to a model both visually and for sensors. This section demonstrates how the user can use custom meshes to define how their model will appear in the simulation. The most common use case for a mesh is to create a realistic looking visual.

  1. Navigate to the 2wd_mr directory

    cd ~/.gazebo/models/2wd_mr
    
  2. Open the model.sdf file using your favorite editor

    gedit ~/.gazebo/models/2wd_mr/model.sdf
    
  3. To add a mesh to the chassis visual, find name=visual, which looks like:

        <visual name='visual'>
          <geometry>
            <box>
              <size>.4 .2 .1</size>
            </box>
          </geometry>
        </visual>
    
  4. A mesh can come from a file on disk, or from another model. In this example, we'll use a mesh from the pioneer2dx model. Change the visual element to the following (but keep the rest of the file intact):

        <visual name='visual'>
          <geometry>
            <mesh>
              <uri>model://pioneer2dx/meshes/chassis.dae</uri>
            </mesh>
          </geometry>
        </visual>
    
  5. Look in your locally cached model database to see if you have the pioneer2dx model referenced by above <mesh> block:

    ls -l ~/.gazebo/models/pioneer2dx/meshes/chassis.dae
    

If the mesh file does not exist, make Gazebo pull the model from the Model Database by spawning the Pioneer 2DX model at least once in Gazebo (under Insert->http://gazebosim.org/models).

Or manually download the model files to your local cache:

    cd ~/.gazebo/models
    wget -q -R *index.html*,*.tar.gz --no-parent -r -x -nH http://models.gazebosim.org/pioneer2dx/
  1. In Gazebo, drag the 2wd_mr model in the world. The visual for the chassis will look like a pioneer2dx.

  2. If the chassis is obviously too big for our robot, we need to scale the visual and change pose. Modify the visual to have a scaling factor:

    <visual name='visual'>
      <geometry>
        <mesh>
          <uri>model://pioneer2dx/meshes/chassis.dae</uri>
          <scale>0.9 0.5 0.5</scale>
        </mesh>
      </geometry>
    </visual>

And raise the chassis up a little by specifying a pose for the visual:

    <visual name='visual'>
      <pose>0 0 0.05 0 0 0</pose>
      <geometry>
        <mesh>
          <uri>model://pioneer2dx/meshes/chassis.dae</uri>
          <scale>0.9 0.5 0.5</scale>
        </mesh>
      </geometry>
    </visual>

The figures below illustrate the changes.

Note that at this point we have simply modified the <visual> elements of the robot, so the robot will look like a scaled-down version of the Pioneer 2DX model through the GUI and to GPU based sensors such as camera, a depth camera, and GPU Lasers. Since we did not modify the <collision> elements in this model, the box geometry will still be used by the physics engine for collision dynamics and by CPU based ray sensors.