Customizing the WAM V - osrf/vrx GitHub Wiki

Overview

The purpose of this tutorial is to demonstrate how to create a custom WAM-V thruster and component configuration. This involves writing a user-generated thruster YAML file and a user-generated component YAML file, and then running a script that will generate a custom WAM-V URDF file with the specified thrusters and components. This WAM-V URDF file can then be passed in as a parameter to the VRX simulation launch files.

In addition, this script also makes sure that the requested thruster and component configurations are in compliance with basic VRX constraints. More details about compliance below.

Quick Start Instructions:

Example 1: How to use generate_wamv.launch

  • First, be sure your VRX workspace is built and sourced. Then launch the example world:

    ros2 launch vrx_gz competition.launch.py world:=sydney_regatta
    
  • Look at the WAM-V in the Sydney Regatta Centre. It currently has the default thruster configuration and component configuration for sydneyregatta.launch (as of December, 2022, the default configuration is the H thruster configuration, three cameras, one laser, one ball shooter, one GPS and one IMU).

    Screenshot from 2022-12-22 21-39-08

  • Close gazebo

  • Make a directory for your custom WAM-V, eg:

    mkdir ~/my_wamv
    cd ~/my_wamv
    
  • Copy the file vrx_urdf/vrx_gazebo/config/wamv_config/example_component_config.yaml.

    cp <VRX_WS>/vrx_urdf/vrx_gazebo/config/wamv_config/example_component_config.yaml .
    

    Later, you can edit this file to customize further your WAM-V.

  • Copy the file vrx_urdf/vrx_gazebo/config/wamv_config/example_thruster_config.yaml.

    cp <VRX_WS>/vrx_urdf/vrx_gazebo/config/wamv_config/example_thruster_config.yaml .
    

    Later, you can edit this file to customize further your WAM-V.

  • Run the script to generate your WAM-V's URDF with these newly specified thrusters and components. Note: on most systems, $HOME is /home/<username>. If this is not the case, you can change all uses of $HOME to /home/<username>.

    ros2 launch vrx_gazebo generate_wamv.launch.py component_yaml:=`pwd`/example_component_config.yaml thruster_yaml:=`pwd`/example_thruster_config.yaml wamv_target:=`pwd`/wamv_target.urdf wamv_locked:=False
    

    Parameters Explained:

    • thruster_yaml: input, the full path of the thruster YAML configuration file. If not given, uses the default thruster yaml

    • component_yaml: input, the full path of the component YAML configuration file. If not given, uses the default component yaml

    • wamv_target: output, the full path to the WAM-V URDF, which will be generated

  • See the following confirmation message in the terminal with no errors present

[INFO] [launch]: All log files can be found below /home/caguero/.ros/log/2022-12-22-21-53-36-523165-cold-3060856
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [generate_wamv.py-1]: process started with pid [3060857]
[generate_wamv.py-1] [INFO] [1671742416.733867948] [configure_wamv]: 
[generate_wamv.py-1] Using /home/caguero/my_wamv/example_thruster_config.yaml as the thruster configuration yaml file
[generate_wamv.py-1] 
[generate_wamv.py-1] [INFO] [1671742416.734094421] [configure_wamv]: 
[generate_wamv.py-1] Trying to open /home/caguero/my_wamv/example_thruster_config.xacro 
[generate_wamv.py-1] 
[generate_wamv.py-1] [INFO] [1671742416.737537713] [configure_wamv]: 
[generate_wamv.py-1] Using /home/caguero/my_wamv/example_component_config.yaml as the component configuration yaml file
[generate_wamv.py-1] 
[generate_wamv.py-1] WAM-V urdf file sucessfully generated. File location: /home/caguero/my_wamv/wamv_target.urdf
[INFO] [generate_wamv.py-1]: process has finished cleanly [pid 3060857]

  • Launch the example world with your WAM-V:

    ros2 launch vrx_gz competition.launch.py world:=sydney_regatta urdf:=`pwd`/wamv_target.urdf
    
  • Look at the WAM-V in the Sydney Regatta Centre. It should have your thruster and component configurations. If everything went correctly and you used the example thruster and component configuration yaml files below, you should see the desired components. Note the new configuration with the three cameras.

Screenshot from 2022-12-22 21-46-04

Example 2: Non-compliance

Next, let's see how compliance works.

  • Scroll down this tutorial and copy the contents of Example Non-compliant Yaml Thruster Configuration File. Next, paste those contents into the example_thruster_config.yaml file, replacing all previous text. Note the addition of the third thruster in a non-compliant position.

       $ gedit ~/my_wamv/example_thruster_config.yaml
    
  • Scroll down this tutorial and copy the contents of Example Non-compliant Yaml Component Configuration File. Next, paste those contents into the component_config.yaml file, replacing all previous text. Note the addition of 5 cameras.

       $ gedit ~/my_wamv/example_component_config.yaml
    
  • Next, we need to run generate_wamv.launch again to use these new yamls files to create a new urdf file.

       $ ros2 launch vrx_gazebo generate_wamv.launch.py component_yaml:=`pwd`/example_component_config.yaml thruster_yaml:=`pwd`/example_thruster_config.yaml wamv_target:=`pwd`/wamv_target_2.urdf wamv_locked:=False
    
  • See the following messages in the terminal

[INFO] [launch]: All log files can be found below /home/caguero/.ros/log/2022-12-22-22-35-39-966859-cold-3067211
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [generate_wamv.py-1]: process started with pid [3067212]
[generate_wamv.py-1] [INFO] [1671744940.180974378] [configure_wamv]: 
[generate_wamv.py-1] Using /home/caguero/my_wamv/example_thruster_config.yaml as the thruster configuration yaml file
[generate_wamv.py-1] 
[generate_wamv.py-1] [INFO] [1671744940.181217251] [configure_wamv]: 
[generate_wamv.py-1] Trying to open /home/caguero/my_wamv/example_thruster_config.xacro 
[generate_wamv.py-1] 
[generate_wamv.py-1] [ERROR] [1671744940.184488473] [compliance]: engine second_right is out of bounds
[generate_wamv.py-1] [ERROR] [1671744940.184698986] [compliance]: engine second_right is at xyz=(-2.373776, -1.027135, 0.318237), it must fit in at least one of the following boxes with remaining space:
[generate_wamv.py-1] [ERROR] [1671744940.184906448] [compliance]:   <Box name:thruster_compliance_port_aft x:[-1.75, -2.75] y:[1.5,0.5] z:[0.6,-0.6]                remaining_space:0>
[generate_wamv.py-1] [ERROR] [1671744940.185110821] [compliance]:   <Box name:thruster_compliance_star_aft x:[-1.75, -2.75] y:[-0.5,-1.5] z:[0.6,-0.6]                remaining_space:0>
[generate_wamv.py-1] [ERROR] [1671744940.185323194] [compliance]:   <Box name:thruster_compliance_port_for x:[1.75, 0.75] y:[1.5,0.5] z:[0.6,-0.6]                remaining_space:1>
[generate_wamv.py-1] [ERROR] [1671744940.185535786] [compliance]:   <Box name:thruster_compliance_star_for x:[1.75, 0.75] y:[-0.5,-1.5] z:[0.6,-0.6]                remaining_space:1>
[generate_wamv.py-1] [ERROR] [1671744940.185748079] [compliance]:   <Box name:thruster_compliance_middle x:[1.5, -1.0] y:[0.5,-0.5] z:[0.6,-0.6]                remaining_space:1>
[generate_wamv.py-1] [INFO] [1671744940.186929714] [configure_wamv]: 
[generate_wamv.py-1] Using /home/caguero/my_wamv/example_component_config.yaml as the component configuration yaml file
[generate_wamv.py-1] 
[generate_wamv.py-1] [ERROR] [1671744940.191308478] [compliance]: Too many wamv_camera requested
[generate_wamv.py-1] [ERROR] [1671744940.191511711] [compliance]:   maximum of 3 wamv_camera allowed
[generate_wamv.py-1] [ERROR] [1671744940.370982269] [configure_wamv]: 
[generate_wamv.py-1] This component/thruster configuration is NOT compliant with the (current) VRX constraints. A urdf file will be created, but please note that the above errors must be fixed for this to be a valid configuration for the VRX competition.
[generate_wamv.py-1] 
[generate_wamv.py-1] WAM-V urdf file sucessfully generated. File location: /home/caguero/my_wamv/wamv_target_2.urdf
[INFO] [generate_wamv.py-1]: process has finished cleanly [pid 3067212]

The URDF file is still created, but these error messages show why your configuration is not compliant. There are too many cameras and two thrusters that are too close together (more details about this in the Compliance section).

Next, launch the example world with your WAM-V:

$ ros2 launch vrx_gz competition.launch.py world:=sydney_regatta urdf:=`pwd`/wamv_target_2.urdf

Look at the WAM-V in the Sydney Regatta Centre. It should have your new thruster and component configurations. If everything went correctly and you used the example thruster and component configuration yaml files below, you should see the desired components and thrusters. Please note the multiple cameras.

Screenshot from 2022-12-22 22-38-51

Compliance

As of December, 2022 there are 3 main compliance rules

  • All components must be contained within one of the component bounding boxes (details here). The image below shows the position of the bounding boxes as of July 15, 2021.

Sensor_Bounding_Boxes.png

  • All thrusters must be contained within one of the thruster bounding boxes (details here). The image below shows the position of the bounding boxes as of July 15, 2021.

Thruster_Bounding_Boxes.png

  • The number of each component and thruster in the configuration must be within the limit defined here for components and here for thrusters.

  • For thrusters, there can only be one thruster in each bounding box. This is to prevent stacking thrusters together in one location, which is physically infeasible.

Please note that if you call generate_wamv.launch on non-compliant configuration YAML files, error messages will be printed but the URDF file will still be created and be able to be used as usual. However, it is not a valid configuration for a VRX competition.

Important Cases

  • To setup a WAM-V with no thruster and no components, you can create empty files empty_thruster_config.yaml and empty_component_config.yaml and then pass them in as parameters to generate_wamv.launch

  • When sydneyregatta.launch or any other simulation launch file is called, if the urdf parameter is given, it will use that file for the WAM-V configuration. If the urdf parameter is not given, then it will use the default configuration given in the launch file.

Supported Thrusters and Components

Supported thrusters and components can be seen in allowed thrusters and allowed components (currently as of December, 2022 we have only one thruster type).

Thrusters and Components Default and Required Parameters

All components and thrusters have numerous parameters. As of December 2022, these include name, prefix, position, orientation, x, y, z, R, P, Y, post_Y, depending on the component or thruster. You can view the parameters for components here and the parameters for thrusters here.

As of Dec 2022, you can click on wamv_camera.xacro and you will see:

<xacro:macro name="wamv_camera" params="name x:=0.5 y:=0 z:=1.5 post_z_from:=1.2965 R:=0 P:=0 Y:=0 post_Y:=0 visualize:=False">

This means that name is a required parameter, and the others all have defaults.

As of Dec 2022, you can click on engine.xacro and you will see:

<xacro:macro name="engine" params="prefix position:='0 0 0' orientation:='0 0 0'">

This means that prefix is a required parameter, and that position and orientation have defaults.

Examples

Example Non-compliant Yaml Thruster Configuration File

engine:
  - prefix: "left"
    position: "-2.373776 1.027135 0.318237"
    orientation: "0.0 0.0 0.0"
  - prefix: "right"
    position: "-2.373776 -1.027135 0.318237"
    orientation: "0.0 0.0 0.0"

  # Adding new thruster in non-compliant position
  - prefix: "second_right"
    position: "-2.373776 -1.027135 0.318237"
    orientation: "0.0 0.0 0.0"

Example Non-compliant Yaml Component Configuration File

# Too many cameras
wamv_camera:
    - name: front_left_camera
      x: 0.75
      y: 0.1
      P: ${radians(15)}
    - name: front_right_camera
      x: 0.75
      y: -0.1
      P: ${radians(15)}
    - name: front_far_left_camera
      x: 0.75
      y: 0.3
      P: ${radians(15)}
    - name: front_far_right_camera
      x: 0.75
      y: -0.3
      P: ${radians(15)}
    - name: middle_left_camera
      x: 0.6
      y: 0.4
      P: ${radians(15)}
      Y: ${radians(90)}
      post_Y: ${radians(90)}
⚠️ **GitHub.com Fallback** ⚠️