-
Notifications
You must be signed in to change notification settings - Fork 194
vrx_2023 wamv_compliance
All WAM-V configuration files submitted as part of VRX competition solutions must adhere to the following 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:
- All thrusters must be contained within one of the thruster bounding boxes (details here). The image below shows the position of the bounding boxes:
-
The numbers of each component and thruster in the configuration must be within the limits defined here for components and here for thrusters.
-
Additionally, there can only be one thruster in each bounding box. This is to prevent stacking thrusters together in one location, which is physically infeasible.
- The script
generate_wamv.launch
will print error messages if it is called on non-compliant configuration YAML files. - 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.
Supported thrusters and components can be seen in allowed thrusters and allowed components (currently we have only one thruster type).
A number of parameters are available to help configure components and thrusters. These include name
, prefix
, position
, orientation
, x
, y
, z
, R
, P
, Y
, post_Y
, depending on the component or thruster.
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"
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.
# 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)}
Back: WAM-V Compliance | Top: VRX Tutorials | Next: Validation |
---|