(!) Please ask about problems and questions regarding this tutorial on answers.ros.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.

Create your own object

Description: This tutorial shows how to model your own object and add it to gazebo

Tutorial Level:

Modelling

In general: avoid zero thickness for planes, this will cause rendering problems

Model the object using urdf

see urdf/Tutorials/Building a Visual Robot Model with URDF from Scratch

Model the object using Google Sketchup

1. Model your object in Google Sketchup using SI-Units, e.g. meter.

2. Export to dae format in Sketchup

3. Put the resulting dae file into the package cob_gazebo_objects into the folder Media/models/. The folder with the textures (same name as dae-filename) should also be added to this folder.

4. Create a new object file in the package cob_gazebo_objects in the folder objects named "MY_OBJECT.urdf". You can use the following template and replace the dae filenames in line 12 and line 18. Note the scaling in order to reduce the model to metric values (SketchUp is using inch when exporting).

   1 <?xml version="1.0" ?> 
   2 <robot name="my_object">
   3   <link name="base_link">
   4   <inertial>
   5     <mass value="5.0" />
   6     <origin xyz="0 0 0.0" />
   7     <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
   8   </inertial>
   9   <visual>
  10    <origin xyz="0 0 0.0" rpy="0 0 0" />
  11    <geometry>
  12      <mesh filename="package://cob_gazebo_objects/Media/models/my_object.dae"/>
  13    </geometry>
  14   </visual>
  15   <collision>
  16    <origin xyz="0 0 0.072" rpy="0 0 0" />
  17    <geometry>
  18      <mesh filename="package://cob_gazebo_objects/Media/models/my_object.dae">
  19    </geometry>
  20   </collision>     
  21   </link>
  22 </robot>

5. Define a object position You have to define a position for this object in the package cob_gazebo_objects, for each world there a configuration file in: cob_gazebo_objects/config/WORLD_NAME/object_locations.yaml. The format for this file is:

MY_OBJECT:
  model: MY_OBJECT
  model_type: urdf
  position: [X,Y,Z]
  orientation: [0, 0, 0]

6. Start Gazebo and spawn the object

You have to spawn the world (for example you can use ipa-apartment):

roslaunch cob_gazebo_worlds WORLD_NAME.launch

It is necessary load the position of the object as a parameter:

roslaunch cob_gazebo_objects upload_param.launch

And spawn your object using the node spawn object:

rosrun cob_bringup_sim spawn_object.py MY_OBJECT

Wiki: cob_gazebo_objects/Tutorials/Create and spawn new objects (last edited 2012-11-20 10:35:45 by NadiaHammoudeh)