-
Notifications
You must be signed in to change notification settings - Fork 15
API
The communication with the LRAUV is done using Gazebo transport. It provides message passing, services, and data logging. It can use either topics or services. To have a look at what are the main ones that will be used in an LRAUV simulation here is a snapshot of the common ones when running something like gz sim buoyant_tethys.sdf
.
Here are the topics clasified by the Plugin or Entity responsible of them.
Topic | Message | Usage |
---|---|---|
/comms/internal |
lrauv_ignition_plugins::msgs:: LRAUVInternalComms | Default topic on which to send and listen for internal packets. A prefix can be set through conifiguration. |
/comms/external/<address>/rx |
lrauv_ignition_plugins::msgs:: LRAUVAcousticMessage | Topic on which this plugin will publish received messages. |
/comms/external/<address>/tx |
lrauv_ignition_plugins::msgs:: LRAUVAcousticMessage | This is where the plugin receives the data. |
| Science Sensors System | /chlorophyll
| gz::msgs::Float_V | Sensor readings for chlorophyll based on data loaded through csv
. |
| Science Sensors System | /temperature
| gz::msgs::Float_V | Sensor readings for temperature based on data loaded through csv
. |
| Science Sensors System | /salinity
| gz::msgs::Float_V | Sensor readings for salinity based on data loaded through csv
. |
| Science Sensors System | /current
| gz::msgs::Vector3d | Sensor readings for current based on data loaded through csv
. |
| Science Sensors System |/science_data
| gz::msgs::PointCloudPacked | Topic to publish the science data point cloud.|
| Linear Battery Plugin |/model/tethys/battery/linear_battery/state
| gz::msgs.BatteryState | State of the linear battery. This plugin may publish other topics if enabled through the SDF configuration. |
|Buoyancy Engine |/model/tethys/buoyancy_engine
|gz::msgs::Double| Subscribes to this topic. This is the set point for the engine. Defaults to /buoyancy_engine if no <namespace>
was defined. |
| Buoyancy Engine |/model/tethys/buoyancy_engine/current_volume
|gz::msgs::Double| Publishes the current volume. Defaults to /buoyancy_engine if no <namespace>
was defined. |
| Science Sensors System |/model/tethys/chlorophyll
|gz::msgs::Float_V | Sensor readings for chlorophyll based on data loaded through csv
. |
|Science Sensors System |/model/tethys/current
|gz::msgs::Float_V | Sensor readings for temperature based on data loaded through csv
. |
|Science Sensors System |/model/tethys/salinity
| gz::msgs::Float_V | Sensor readings for salinity based on data loaded through csv
. |
|Science Sensors System |/model/tethys/temperature
|gz::msgs::Float_V | Sensor readings for temperature based on data loaded through csv
. |
| Deatachable Joint |/model/tethys/drop_weight
| gz::msgs::Empty| Listens on this topic for deattaching connections. Topic defined through <topic>
. |
| Joint Position Controller |/model/tethys/joint/battery_joint/0/cmd_pos
| gz::msgs::Double| Joint position controller for the battery joint, defaults to "/model/<model_name>/joint/<joint_name>/<joint_index>/cmd_pos" if no <topic>
is provided. |
| Joint Position Controller |/model/tethys/joint/horizontal_fins_joint/0/cmd_pos
| gz::msgs::Double| Joint position controller for the horizontal fins joint, defaults to "/model/<model_name>/joint/<joint_name>/<joint_index>/cmd_pos" if no <topic>
is provided. |
| Joint Position Controller |/model/tethys/joint/vertical_fins_joint/0/cmd_pos
| gz::msgs::Double| Joint position controller for the vertical fins joint, defaults to "/model/<model_name>/joint/<joint_name>/<joint_index>/cmd_pos" if no <topic>
is provided. |
| Thruster |/model/tethys/joint/propeller_joint/cmd_vel
| gz::msgs::Double | Topic to receive joint velocity commands. The plugin will listen on the topic /model/{namespace}/joint/{joint_name}/cmd_thrust
or /model/{namespace}/joint/{joint_name}/cmd_vel
depending on the mode of operation (see <velocity_control>
). |
| Thruster |/model/tethys/joint/propeller_joint/force
| gz::msgs::Double | If <use_angvel_cmd>
is set to true it publishes force in Newtons instead to /model/{ns}/joint/{joint_name}/force
. |
| IMU |/tethys/ahrs/imu
| gz::msgs::IMU | Topic to publish IMU vertical position, angular velocity and lienar acceleration readings.|
| Magnetometer |/tethys/ahrs/magnetometer
| gz::msgs::Magnetometer | Topic to report the magnetic field in its current location. |
| Thethys Comm Plugin |/tethys/command_topic
| lrauv_ignition_plugins::msgs:: LRAUVCommand | Topic on which robot commands are received. |
| NavSat |/tethys/navsat
| gz::msgs::NavSat | Topic where NavSat reports position and velocity in spherical coordinates (latitude / longitude). Defined by <topic>
. |
| Range Bearing Plugin | /tethys/range_bearing/requests
| rauv_ignition_plugins::msgs:: LRAUVRangeBearingRequest | Topic where the plugin listens for range bearing requests. |
| Range Bearing Plugin | /tethys/range_bearing/responses
| lrauv_ignition_plugins::msgs:: LRAUVRangeBearingResponse | Topic where the range bearing responses are published.|
| Thethys Comm Plugin |/tethys/state_topic
| lrauv_ignition_plugins::msgs:: LRAUVState | Topic on which robot state is published. |
| Scene Broadcaster Plugin |/world/buoyant_tethys/dynamic_pose/info
| gz::msgs::Pose_V | Dynamic pose publisher, for non-static model poses. |
|Scene Broadcaster Plugin |/world/buoyant_tethys/pose/info
| gz::msgs::Pose_V | Pose publisher. |
|Scene Broadcaster Plugin |/world/buoyant_tethys/scene/deletion
| gz::msgs::UInt32_V | Topic used by the scene broadcaster to request entities to be removed.
|Scene Broadcaster Plugin |/world/buoyant_tethys/state
| gz::msgs::SerializedSetpMap | Topic where state is published |
| World Config Plugin |/world/science_sensor/environment_data_path
| gz::msgs::StringMsg | This plugin will publish the data file path here when loaded through the GUI. |
|Scene Broadcaster Plugin |/world/buoyant_tethys/scene/info
| gz::msgs::Scene | Topic where scene are published. |
| Gazebo Server |/world/buoyant_tethys/clock
| gz::msgs::Clock | Server world clock.|
|Gazebo Server |/world/buoyant_tethys/stats
| gz::msgs::Clock | Provides statistics about the world, such as the time elapsed and the paused state.|
| Gazebo Simulation Runner |/clock
| gz::msgs::Clock | Publishes Gazebo simulation time.|
| Gazebo Simulation Runner |/stats
| gz::msgs::Clock | Provides statistics about the simulation, such as the time elapsed and the paused state. |
Most of the services that appear when running gz sim buoyant_tethys.sdf
belong to gazebo plugins so please refer to the [official Gazebo documentation] for more info. The services more closely related to LRAUV are:
Plugin/Entity responsible | Service | Message to recieve | Message sent | Usage |
---|---|---|---|---|
Science Sensors System | /model/tethys/chlorophyll/set_rate |
gz::msgs::Double | gz::msgs::Empty | Sets the rate for the chlorophyll sensor. |
Science Sensors System | /model/tethys/current/set_rate |
gz::msgs::Double | gz::msgs::Empty | Sets the rate for the current sensor. |
Science Sensors System | /model/tethys/salinity/set_rate |
gz::msgs::Double | gz::msgs::Empty | Sets the rate for the salinity sensor. |
Science Sensors System | /model/tethys/temperature/set_rate |
gz::msgs::Double | gz::msgs::Empty | Sets the rate for the temperature sensor. |
Science Sensors System | /science_data |
gz::msgs::Empty | gz::msgs::PointCloudPacked | Service to request the science data point cloud. |
Linear Battery Plugin | /model/tethys/battery/linear_battery/recharge/start |
gz::msgs::Boolean | gz::msgs::Empty | Start recharging battery. |
Linear Battery Plugin | /model/tethys/battery/linear_battery/recharge/stop |
gz::msgs::Boolean | gz::msgs::Empty | Stop recharging battery. |
IMU | /tethys/ahrs/imu/set_rate |
gz::msgs::IMU | gz::msgs::Double | Set IMU sensor rate. |
Magnetometer | /tethys/ahrs/magnetometer/set_rate |
gz::msgs::Double | gz::msgs::Empty | Set magnetometer sensor rate. |