tutorials Adding course elements - osrf/vrx GitHub Wiki
The vrx_gazebo package has a basic RobotX course with water, sky, coastline, and some of the challenges in fixed positions. It is easy to create your own static course or even add new challenges into a running simulation.
This guide assumes you already have installed ROS and the vrx packages as covered in the setup instructions.
A world file defines the initial environment gazebo starts in, including lighting, sky, ground, and models. Let's copy one of the examples from vrx_gazebo as a starting point for our world file:
$ mkdir example_vrx_package
$ cd example_vrx_package/
$ roscp vrx_gazebo example_course.world.xacro .
Now you should have a file that looks something like this:
cat example_course.world.xacro
<?xml version="1.0" ?>
<!-- World containing sydneyregatta model and some course challenges -->
<sdf version="1.6" xmlns:xacro="http://ros.org/wiki/xacro">
<world name="robotx_example_course">
<xacro:include filename="$(find vrx_gazebo)/worlds/sydneyregatta.xacro" />
<xacro:sydneyregatta />
<!--Waves-->
<xacro:include filename="$(find wave_gazebo)/world_models/ocean_waves/model.xacro"/>
<xacro:ocean_waves scale="2.5"/>
<xacro:include filename="$(find vrx_gazebo)/worlds/xacros/usv_wind_plugin.xacro"/>
<xacro:usv_wind_gazebo>
<wind_objs>
<wind_obj>
<name>wamv</name>
<link_name>base_link</link_name>
<coeff_vector>.5 .5 .33</coeff_vector>
</wind_obj>
</wind_objs>
</xacro:usv_wind_gazebo>
</world>
</sdf>
Notice that this is an .xacro file. If you aren't familiar with xacro files, you should read this tutorial first.
Let's go through this file and make some changes. First, notice the next two lines within the tag:
<xacro:include filename="$(find vrx_gazebo)/worlds/sydneyregatta.xacro" />
<xacro:sydneyregatta />
The first line imports the sydneyregatta macro defined in vrx_gazebo. The second line calls the sydneyregatta
macro, which sets up an empty Sydney Regatta environment (only water, sky, and coastline). You will likely want to include these lines in your world files unless you are simulating a location other than Sydney Regatta.
The remainder of the file is simply adding different environmental elements, such as waves and wind.
Let's add a few buoys into the world to make some obstacles to avoid. Put these lines before tag:
<include>
<!-- Small buoy found in vrx_gazebo -->
<uri>model://polyform_a3</uri>
<!-- X Y Z roll pitch yaw, relative to center of gazebo world (a point out in the water) -->
<pose>-10 2 0 0 0 0</pose>
</include>
<include>
<uri>model://polyform_a7</uri>
<pose>-15 8 0 0 0 0</pose>
</include>
<include>
<uri>model://mb_marker_buoy_red</uri>
<pose>-12.5 -3 0 0 0 0</pose>
</include>
Now that you have created a new world file, you can launch the simulation again with this world:
First, generate the compiled XML from the xacro file using:
rosrun xacro xacro example_course.world.xacro > my_world.world
Next, run the simulation with a custom world argument:
roslaunch vrx_gazebo sydneyregatta.launch world:=`pwd`/my_world.world
If everything went well, you should see three new objects added into Gazebo: