-
Notifications
You must be signed in to change notification settings - Fork 13
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Update message documentation style #119
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||
---|---|---|---|---|---|---|
|
@@ -33,66 +33,114 @@ import "ignition/msgs/header.proto"; | |||||
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) | ||||||
// \TODO(chapulina) Update coordinate frame convention for all pose fields: | ||||||
message LRAUVState | ||||||
{ | ||||||
/// \brief Optional header data | ||||||
/// Stamped with simulation time. | ||||||
ignition.msgs.Header header = 1; | ||||||
|
||||||
/// \brief Not populated | ||||||
int32 errorPad_ = 2; | ||||||
|
||||||
/// \brief Not populated | ||||||
int32 utmZone_ = 3; | ||||||
|
||||||
/// \brief Not populated | ||||||
int32 northernHemi_ = 4; | ||||||
float propOmega_ = 5; // Current angular velocity of the | ||||||
// propeller. Unit: rad / s. Positive | ||||||
// values rotate the propeller | ||||||
// clockwise when looking from the back, | ||||||
// and propel the vehicle forward. | ||||||
float propThrust_ = 6; // Not populated | ||||||
float propTorque_ = 7; // Not populated | ||||||
float rudderAngle_ = 8; // Angle that the rudder joint is | ||||||
// currently at. Unit: radians. | ||||||
// Higher values have the vertical fins | ||||||
// rotated more clockwise when looking | ||||||
// from the top (i.e. to starboard) | ||||||
|
||||||
/// \brief Current angular velocity of the propeller. Unit: rad / s. Positive | ||||||
/// values rotate the propeller clockwise when looking from the back, | ||||||
/// and propel the vehicle forward. | ||||||
float propOmega_ = 5; | ||||||
|
||||||
/// \brief Not populated | ||||||
float propThrust_ = 6; | ||||||
|
||||||
/// \brief Not populated | ||||||
float propTorque_ = 7; | ||||||
|
||||||
/// \brief Angle that the rudder joint is currently at. Unit: radians. | ||||||
/// Higher values have the vertical fins rotated more clockwise when looking | ||||||
/// from the top (i.e. to starboard) | ||||||
float rudderAngle_ = 8; | ||||||
|
||||||
/// \brief Angle that the elevator joint is currently at. Unit: radians. | ||||||
/// Higher values have the horizontal fins rotated more counter-clockwise when | ||||||
/// looking from starboard, which tilts the nose downward when moving forward. | ||||||
float elevatorAngle_ = 9; | ||||||
float massPosition_ = 10; // Position of the battery's joint. | ||||||
// Unit: meters. Positive values have | ||||||
// the battery forward, tilting the | ||||||
// nose downward. | ||||||
float buoyancyPosition_ = 11; // Volume of the VBS. Unit: cubic | ||||||
// meters. Volumes higher than the | ||||||
// neutral volume push the vehicle | ||||||
// upwards. | ||||||
|
||||||
/// \brief Position of the battery's joint. Unit: meters. Positive values have | ||||||
/// the battery forward, tilting the nose downward. | ||||||
float massPosition_ = 10; | ||||||
|
||||||
/// \brief Volume of the VBS. Unit: cubic meters. Volumes higher than the | ||||||
/// neutral volume push the vehicle upwards. | ||||||
float buoyancyPosition_ = 11; | ||||||
|
||||||
/// \brief Vertical position of the vehicle with respect to sea level. Higher | ||||||
/// values are deeper, negative values are above water. Unit: meters. | ||||||
float depth_ = 12; | ||||||
|
||||||
ignition.msgs.Vector3d rph_ = 13; // roll_, pitch_, heading_ in SimResultStruct (rad) | ||||||
/// \brief Duplicate of posRPH_ | ||||||
ignition.msgs.Vector3d rph_ = 13; | ||||||
|
||||||
/// \brief TODO(chapulina) | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
float speed_ = 14; | ||||||
|
||||||
float speed_ = 14; // Magnitude of linear velocity in the | ||||||
// world frame. Unit: m / s | ||||||
/// \brief Latitude in degrees | ||||||
double latitudeDeg_ = 15; | ||||||
|
||||||
/// \brief Longitude in degrees | ||||||
double longitudeDeg_ = 16; | ||||||
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 | ||||||
|
||||||
/// \brief Net buoyancy forces applied to the vehicle. Unit: Newtons. Currently not populated. | ||||||
float netBuoy_ = 17; | ||||||
|
||||||
/// \brief Not populated | ||||||
ignition.msgs.Vector3d force_ = 18; | ||||||
|
||||||
/// \brief \TODO(chapulina) | ||||||
ignition.msgs.Vector3d pos_ = 19; | ||||||
|
||||||
/// \brief \TODO(chapulina) | ||||||
ignition.msgs.Vector3d posRPH_ = 20; | ||||||
|
||||||
/// \brief \TODO(chapulina) | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I removed these on purpose, I'm adding the clearer explanation on https://github.com/osrf/lrauv/pull/81/files#diff-638da727e840523f41a6bdea345acc02e4ab2b12ee06b88aa70ac15ae8b07654. |
||||||
ignition.msgs.Vector3d posDot_ = 21; | ||||||
|
||||||
/// \brief \TODO(chapulina) | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
ignition.msgs.Vector3d rateUVW_ = 22; | ||||||
|
||||||
/// \brief \TODO(chapulina) | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
ignition.msgs.Vector3d ratePQR_ = 23; | ||||||
|
||||||
/// \brief Northward sea water velocity collected from current sensor. Unit: m/s. | ||||||
float northCurrent_ = 24; | ||||||
|
||||||
/// \brief Eastward sea water velocity collected from current sensor. Unit: m/s. | ||||||
float eastCurrent_ = 25; | ||||||
|
||||||
/// \brief Not populated | ||||||
float vertCurrent_ = 26; | ||||||
|
||||||
/// \brief Not populated | ||||||
float magneticVariation_ = 27; | ||||||
|
||||||
/// \brief Not populated | ||||||
float soundSpeed_ = 28; | ||||||
float temperature_ = 29; // Celsius | ||||||
float salinity_ = 30; // PSU | ||||||
float density_ = 31; // Density of the surrounding water in Kg / m ^ 3 | ||||||
repeated float values_ = 32; // Size 4 (0: chlorophyll in ug / L, 1: pressure in Pa) | ||||||
|
||||||
/// \brief Data collected from temperature sensor. Unit: Celsius | ||||||
float temperature_ = 29; | ||||||
|
||||||
/// \brief Data collected from salinity sensor. Unit: PSU | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
float salinity_ = 30; | ||||||
|
||||||
/// \brief Density of the surrounding water in kg / m ^ 3 | ||||||
float density_ = 31; | ||||||
|
||||||
/// \brief Size 4 | ||||||
// 0: Data collected from Chlorophyll sensor. Unit: ug / L | ||||||
// 1: Pressure calculated from current depth and latitude. Unit: Pa | ||||||
repeated float values_ = 32; | ||||||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Sea level is ambiguous with tides. There's MSL or there's depth to current surface, or several other semi-obscure options. This could be alternatively switched to a TODO.