(!) 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 world

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

Tutorial Level:

Modelling

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

Model the world using urdf

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

Model the worlds using Google Sketchup

1. Model your world 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_worlds 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 world file in the package cob_gazebo_worlds in the folder common/worlds named "YOUR_NEW_ENVIRONMENT.world". You can use the following template and replace the dae filenames in line 23 and line 28. Note the scaling in order to reduce the model to metric values (SketchUp is using inch when exporting).

   1 <?xml version="1.0"?> 
   2 <gazebo version="1.0">
   3 <world name="default">
   4     <scene>
   5       <ambient rgba="0.5 0.5 0.5 1"/>
   6       <background rgba="0.5 0.5 0.5 1"/>
   7       <shadows enabled="false"/>
   8     </scene>
   9 
  10     <physics type="ode">
  11       <gravity xyz="0 0 -9.8"/>
  12       <ode>
  13         <solver type="quick" dt="0.001" iters="10" sor="1.3"/>
  14         <constraints cfm="0.0" erp="0.2" contact_max_correcting_vel="100.0" contact_surface_layer="0.001"/>
  15       </ode>
  16     </physics>
  17 
  18      <model name="environment_model" static="true">
  19       <link name="environment_model_link">
  20         <origin pose="-10 -25 0 0 0 0"/>
  21         <collision name="environment_model_collision">
  22           <geometry>
  23             <mesh filename="Industriestrasse.dae" scale="0.0254 0.0254 0.0254"/>
  24           </geometry>
  25         </collision>
  26         <visual name="environment_model_visual" cast_shadows="false">
  27           <geometry>
  28             <mesh filename="Industriestrasse.dae" scale="0.0254 0.0254 0.0254"/>
  29           </geometry>
  30         </visual>
  31       </link>
  32     </model>
  33 
  34     <!-- Ground Plane -->
  35     <model name="plane1_model" static="true">
  36       <link name="body">
  37         <collision name="geom_1">
  38           <geometry>
  39             <plane normal="0 0 1"/>
  40           </geometry>
  41           <surface>
  42             <friction>
  43               <ode mu="10.0" mu2="10.0" fdir1="0 0 0" slip1="0" slip2="0"/>
  44             </friction>
  45             <bounce restitution_coefficient="0" threshold="1000000.0"/>
  46             <contact>
  47               <ode soft_cfm="0" soft_erp="0.2" kp="1e10" kd="1" max_vel="100.0" min_depth="0.0001"/>
  48             </contact>
  49           </surface>
  50         </collision>
  51 
  52         <visual name="visual_1" cast_shadows="false">
  53           <geometry>
  54             <plane normal="0 0 1"/>
  55           </geometry>
  56           <material script="Gazebo/Grey"/>
  57         </visual>
  58       </link>
  59     </model>
  60 
  61     <light type="directional" name="my_light" cast_shadows="false">
  62       <origin pose="0 0 30 0 0 0"/>
  63       <diffuse rgba=".9 .9 .9 1"/>
  64       <specular rgba=".1 .1 .1 1"/>
  65       <attenuation range="20"/>
  66       <direction xyz="0 0 -1"/>
  67     </light>
  68   </world>
  69 </gazebo>

5. Create a new "YOUR_NEW_ENVIRONMENT.launch" launch file in the package cob_gazebo_worlds in the folder ros/launch with the content:

   1 <?xml version="1.0"?>
   2 <launch>
   3         <!-- start gazebo world from .world file -->
   4         <include file="$(find cob_gazebo_worlds)/ros/launch/world.launch" />
   5 </launch>

6. Export ROBOT_ENV to your new world name and start simulation

Articulate your world

see urdf/Tutorials/Building a Movable Robot Model with URDF

example is elevator in ipa-apartment

Wiki: cob_gazebo_worlds/Tutorials/Create your own world (last edited 2012-11-29 14:01:40 by GustavoVelasco)