Skip to content

Commit

Permalink
Documenting and cleaning up last message fields
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Nov 23, 2021
1 parent 4f7259a commit 0f8c4be
Show file tree
Hide file tree
Showing 8 changed files with 416 additions and 89 deletions.
18 changes: 18 additions & 0 deletions lrauv_ignition_plugins/models/axes/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<!--
Development of this module has been funded by the Monterey Bay Aquarium
Research Institute (MBARI) and the David and Lucile Packard Foundation
-->
<model>
<name>axes</name>
<version>1.0</version>
<sdf version="1.6">model.sdf</sdf>

<author>
<name>Louise Poubel</name>
<email>[email protected]</email>
</author>

<description>
</description>
</model>
48 changes: 48 additions & 0 deletions lrauv_ignition_plugins/models/axes/model.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
<?xml version="1.0"?>
<!--
Development of this module has been funded by the Monterey Bay Aquarium
Research Institute (MBARI) and the David and Lucile Packard Foundation
-->
<sdf version="1.6">
<model name="axes">
<link name="link">
<pose degrees="true">0 0 0 0 180 -90</pose>
<visual name="X">
<pose degrees="true">0.5 0 0 0 90 0</pose>
<geometry>
<cylinder>
<length>1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<material>
<diffuse>1 0 0</diffuse>
</material>
</visual>
<visual name="Y">
<pose degrees="true">0 0.5 0 90 0 0</pose>
<geometry>
<cylinder>
<length>1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<material>
<diffuse>0 1 0</diffuse>
</material>
</visual>
<visual name="Z">
<pose degrees="true">0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<length>1</length>
<radius>0.1</radius>
</cylinder>
</geometry>
<material>
<diffuse>0 0 1</diffuse>
</material>
</visual>
</link>
</model>
</sdf>
6 changes: 3 additions & 3 deletions lrauv_ignition_plugins/proto/lrauv_command.proto
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ message LRAUVCommand
// Volumes higher than the neutral volume
// make the vehicle float.

float density_ = 13;
float dt_ = 14;
double time_ = 15;
float density_ = 13; // Not used
float dt_ = 14; // Not used
double time_ = 15; // Not used
}
104 changes: 76 additions & 28 deletions lrauv_ignition_plugins/proto/lrauv_state.proto
Original file line number Diff line number Diff line change
Expand Up @@ -34,15 +34,34 @@ import "ignition/msgs/vector3d.proto";

// Mirrors SimResultStruct
// Note coordinate frame convention for all pose fields:
// FSK (x fore or forward, y starboard or right, z keel or down)
//
// Reference frames:
//
// * Vehicle frame: FSK
// * X: Fore or forward
// * Y: Starboard or right
// * Z: Keel or down
// * Roll: Clockwise rotation when looking from the back.
// * Pitch: Positive angles bring the nose up.
// * Yaw: Positive angles bring the nose to the right / starboard.
//
// * World frame: NED
// * X: North
// * Y: East
// * Z: Down
// * Roll: Right-hand rotation about North
// * Pitch: Right-hand rotation about East
// * Yaw: Right-hand rotation about Down
//
message LRAUVState
{
/// \brief Optional header data
/// Stamped with simulation time.
ignition.msgs.Header header = 1;

int32 errorPad_ = 2;
int32 utmZone_ = 3;
int32 northernHemi_ = 4;
int32 errorPad_ = 2; // Not populated.
int32 utmZone_ = 3; // Not populated.
int32 northernHemi_ = 4; // Not populated.
float propOmega_ = 5; // Current angular velocity of the
// propeller. Unit: rad / s. Positive
// values rotate the propeller
Expand All @@ -64,35 +83,64 @@ message LRAUVState
// meters. Volumes higher than the
// neutral volume push the vehicle
// upwards.
float depth_ = 12;
float depth_ = 12; // Vertical position of the vehicle
// with respect to sea level. Higher
// values are deeper, negative values
// are above water. Unit: meters.

ignition.msgs.Vector3d rph_ = 13; // roll_, pitch_, heading_ in SimResultStruct (rad)
ignition.msgs.Vector3d rph_ = 13; // Duplicate of posRPH_

float speed_ = 14; // Magnitude of linear velocity in the
// world frame. Unit: m / s
double latitudeDeg_ = 15;
double longitudeDeg_ = 16;
float speed_ = 14; // Magnitude of vehicle's linear velocity
// in the world frame. It's always positive.
// Unit: m/s
double latitudeDeg_ = 15; // Latitude in degrees
double longitudeDeg_ = 16; // Longitude in degrees
float netBuoy_ = 17; // Net buoyancy forces applied to the
// vehicle. Unit: Newtons. Currently
// not populated.

ignition.msgs.Vector3d force_ = 18; // forceX_, forceY_, forceZ_ in SimResultStruct
ignition.msgs.Vector3d pos_ = 19; // posX_, posY_, posZ_ in SimResultStruct
ignition.msgs.Vector3d posRPH_ = 20; // posRoll_, posPitch_, posHeading_ in SimResultStruct
ignition.msgs.Vector3d posDot_ = 21; // posXDot_, posYDot_, posZDot_ in SimResultStruct
// Velocity wrt ground
ignition.msgs.Vector3d rateUVW_ = 22; // rateU_, rateV_, rateW_ in SimResultStruct
// Water velocity
ignition.msgs.Vector3d ratePQR_ = 23; // rateP_, rateQ_, rateR_ in SimResultStruct
// for roll, pitch, yaw rates, respectively

float northCurrent_ = 24; // +Y velocity in m / s
float eastCurrent_ = 25; // +X velocity in m / s
float vertCurrent_ = 26; // +Z velocity in m / s
float magneticVariation_ = 27;
float soundSpeed_ = 28;
float temperature_ = 29; // Celsius
float salinity_ = 30; // PSU
float density_ = 31;
repeated float values_ = 32; // Size 4 (0: chlorophyll in ug / L, 1: pressure in Pa)

ignition.msgs.Vector3d pos_ = 19; // Vehicle's offset position in "world frame"
// (see above) with respect to its initial
// position. The vehicle starts facing West.
// Unit: meters

ignition.msgs.Vector3d posRPH_ = 20; // Vehicle's offset orientation in "world frame"
// (see above) with respect to its initial
// orientation. The vehicle starts facing West.
// Unit: rad

ignition.msgs.Vector3d posDot_ = 21; // Vehicle's instantaneous linear velocity in
// "world frame" (see above). Units: m / s

ignition.msgs.Vector3d rateUVW_ = 22; // Vehicle's instantaneous linear velocity in
// "vehicle frame" (see above). Units: m / s

ignition.msgs.Vector3d ratePQR_ = 23; // Vehicle's instantaneous angular velocity in
// "vehicle frame" (see above). Units: rad / s

float northCurrent_ = 24; // Northward sea water velocity collected
// from current sensor. Unit: m/s.

float eastCurrent_ = 25; // Eastward sea water velocity collected
// from current sensor. Unit: m/s.

float vertCurrent_ = 26; // Not populated.
float magneticVariation_ = 27; // Not populated.
float soundSpeed_ = 28; // Not populated.

float temperature_ = 29; // Data collected from temperature sensor.
// Unit: Celsius

float salinity_ = 30; // Data collected from salinity sensor.
// Unit: PSU

float density_ = 31; // Not populated

repeated float values_ = 32; // Size 4
// 0: Data collected from Chlorophyll
// sensor. Unit: ug / L
// 1: Pressure calculated from current
// depth and latitude. Unit: Pa
}
Loading

0 comments on commit 0f8c4be

Please sign in to comment.