Skip to content

roboboat_customizing_tutorial

Carlos Agüero edited this page Dec 22, 2023 · 9 revisions

Overview

The purpose of this tutorial is to demonstrate how to modify one of the provided Roboboat reference models.

Creating your custom workspace

Create a workspace to store your brand new model named my_roboboat.

mkdir -p ~/gazebo_maritime/models/my_roboboat && cd ~/gazebo_maritime/models/my_roboboat

Let's download the template of this model:

curl https://raw.githubusercontent.com/wiki/osrf/vrx/files/my_roboboat/model.config -o model.config
curl https://raw.githubusercontent.com/wiki/osrf/vrx/files/my_roboboat/model.sdf -o model.sdf
mkdir meshes
curl https://raw.githubusercontent.com/wiki/osrf/vrx/files/my_roboboat/meshes/gps.dae -o meshes/gps.dae
curl https://raw.githubusercontent.com/wiki/osrf/vrx/files/my_roboboat/meshes/gps.png -o meshes/gps.png

For now, this is a very similar model to the RoboBoat01 available in VRX. Let's test it. Open the <YOUR_VRX_WORKSPACE/src/vrx/vrx_gz/worlds/npark.sdf file from your VRX workspace with your favorite editor. Then add your custom roboboat model within the <world> tag:

<!-- My custom roboboat -->
<include>
  <name>my_roboboat</name>
  <pose>-175 1120 0 0 0 3.14</pose>
  <uri>my_roboboat</uri>
</include>

Go to your VRX workspace, recompile, and run Gazebo:

export GZ_SIM_RESOURCE_PATH=:$HOME/gazebo_maritime/models:$GZ_SIM_RESOURCE_PATH
cd ~/vrx_2023
colcon build --merge-install
ros2 launch vrx_gz vrx_environment.launch.py world:=nbpark

You should see your model successfully loaded within the Nathan Benderson park.

Screenshot from 2023-12-21 21-30-00

Adding a sensor

Let's add a GPS sensor to your custom model. Open ~/gazebo_maritime/models/my_roboboat/model.sdf and uncomment the following block:

<!-- Uncomment to add GPS sensor -->
<visual name="gps_visual">
  <pose>0.3 0.0 0.25 0 0 0</pose>
  <geometry>
     <mesh>
      <uri>file://my_roboboat/meshes/gps.dae</uri>
    </mesh>
  </geometry>
</visual>
<sensor name="navsat" type="navsat">
  <pose>0.3 0.0 0.25 0 0 0</pose>
  <always_on>1</always_on>
  <update_rate>1</update_rate>
</sensor>

Note that we're adding a sensor and a visual. The visual just adds an antenna at the same position where we're adding the sensor for visual fidelity. The sensor type is navsat, generating new measurements at 1 Hz, and located at the <pose>0.3 0.0 0.25 0 0 0</pose> from the base_link.

Let's test our modification in Gazebo:

ros2 launch vrx_gz vrx_environment.launch.py world:=nbpark

Screenshot from 2023-12-21 21-39-41

And you can test that you get GPS readings:

gz topic -e -t /world/nbpark/model/my_roboboat/link/base_link/sensor/navsat/navsat

header {
  stamp {
    sec: 21
  }
  data {
    key: "seq"
    value: "21"
  }
}
latitude_deg: 27.377363426535567
longitude_deg: -82.452893421152822
altitude: 0.49600635841488838
velocity_east: 2.4807375001142368e-08
velocity_north: -1.8977398210552808e-10
velocity_up: 0.00099993929300069969
frame_id: "my_roboboat::base_link::navsat"
Clone this wiki locally