-
Notifications
You must be signed in to change notification settings - Fork 196
Adding course elements_tutorial
VRX has a basic set of worlds with water, sky, coastline, and some of the RobotX elements in fixed positions. It is easy to create your own static course or even add new elements into a running simulation.
This guide assumes you already have installed ROS 2 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 as a starting point for our world file:
$ mkdir example_vrx_package
$ cd example_vrx_package/
$ cp <YOUR_VRX_INSTALLATION>/src/vrx/vrx_gz/worlds/sydney_regatta.sdf sydney_regatta_custom.sdf
Notice that this is an .sdf file. If you aren't familiar with SDF files, you should read this tutorial first.
Let's go through this file and make some changes. Open sydney_regatta_custom
with your favorite editor. First, notice the next two lines within the tag:
<include>
<pose> 0 0 0.2 0 0 0 </pose>
<uri>https://fuel.gazebosim.org/1.0/openrobotics/models/sydney_regatta</uri>
</include>
This block sets up an empty Sydney Regatta environment (only water, sky, and coastline) downloading it from Fuel .
The remainder of the file is simply adding different environmental elements, such as waves and wind.
Let's add a buoy into the world to make an obstacle to avoid. Put these lines before tag:
<include>
<name>mb_round_buoy_orange_custom</name>
<pose>-520 180 0 0 1.57 0</pose>
<uri>https://fuel.gazebosim.org/1.0/openrobotics/models/mb_round_buoy_orange</uri>
<plugin name="vrx::PolyhedraBuoyancyDrag"
filename="libPolyhedraBuoyancyDrag.so">
<fluid_density>1000</fluid_density>
<fluid_level>0.0</fluid_level>
<linear_drag>25.0</linear_drag>
<angular_drag>2.0</angular_drag>
<buoyancy name="collision_outer">
<link_name>link</link_name>
<pose>0 0 0 0 0 0</pose>
<geometry>
<sphere>
<radius>0.25</radius>
</sphere>
</geometry>
</buoyancy>
<wavefield>
<size>1000 1000</size>
<cell_count>50 50></cell_count>
<wave>
<model>PMS</model>
<period>5.0</period>
<number>3</number>
<scale>1.1</scale>
<gain>0.3</gain>
<direction>1 0</direction>
<angle>0.4</angle>
<tau>2.0</tau>
<amplitude>0.0</amplitude>
<steepness>0.0</steepness>
</wave>
</wavefield>
</plugin>
</include>
Now that you have created a new world file, you can launch the simulation again with this world:
First, update the GZ_SIM_RESOURCE_PATH
environment variable to let Gazebo know that there's a new directory containing world files:
export GZ_SIM_RESOURCE_PATH=/home/caguero/example_vrx_package:$GZ_SIM_RESOURCE_PATH
Next, run the simulation with a custom world argument:
ros2 launch vrx_gz competition.launch.py world:=sydney_regatta_custom
If everything went well, you should see a new orange buoy added into Gazebo.
Back: Thruster Articulation | Top: VRX Tutorials | Next: Using the Acoustic Pinger |
---|