Skip to content

Acoustic pinger_tutorial

M1chaelM edited this page May 12, 2023 · 2 revisions

Acoustic Beacon

Some of the RobotX Challenge tasks make use of an underwater acoustic beacon. As an example, the RobotX "Entrance and Exit Gates" task, requires teams to detect an active beacon and transit through the gate in which the beacon is located.

Reading acoustic beacon messages

The VRX WAM-V is equipped with a sensor that detects the underwater acoustic beacon. The sensor periodically publishes data to the ROS 2 topic /wamv/pingers/pinger/range_bearing using the ParamVec message definition.

You can use ros2 topic echo command to read the output of this sensor as follows:

  • Launch the VRX simulation environment:
ros2 launch vrx_gz competition.launch.py world:=gymkhana_task
  • Show the data published by the acoustic sensor:
ros2 topic echo /wamv/pingers/pinger/range_bearing

You should see a stream of messages similar to this one:

---
header:
  stamp:
    sec: 5
    nanosec: 0
  frame_id: wamv/pinger
params:
- name: elevation
  value:
    type: 3
    bool_value: false
    integer_value: 0
    double_value: 0.007911467873143386
    string_value: ''
    byte_array_value: []
    bool_array_value: []
    integer_array_value: []
    double_array_value: []
    string_array_value: []
- name: bearing
  value:
    type: 3
    bool_value: false
    integer_value: 0
    double_value: 0.22815154700097853
    string_value: ''
    byte_array_value: []
    bool_array_value: []
    integer_array_value: []
    double_array_value: []
    string_array_value: []
- name: range
  value:
    type: 3
    bool_value: false
    integer_value: 0
    double_value: 139.4759424138178
    string_value: ''
    byte_array_value: []
    bool_array_value: []
    integer_array_value: []
    double_array_value: []
    string_array_value: []
---

Notes:

  • The sensor gives you a distance (range) and two angles (bearing and elevation).
  • The value that you'll get from the sensor includes some noise.

Change the pinger location

The topic /wamv/pingers/pinger/set_pinger_position allows you to change the beacon location. You need to publish a Vector3 message. Here's the message definition.

For example, to change the pinger location to the origin, you would run:

ros2 topic pub --once /wamv/pingers/pinger/set_pinger_position geometry_msgs/msg/Vector3 "x: 0
y: 0
z: 0"

Try this command while echoing your pinger data and see how the range value changes drastically.

Back: Adding Course Elements Top: VRX Tutorials Next: Visualizing with Rviz
Clone this wiki locally