Skip to content

Commit

Permalink
Added generic estimator messages.
Browse files Browse the repository at this point in the history
  • Loading branch information
jgoppert authored and TSC21 committed Mar 27, 2018
1 parent 8cf87fc commit 02a0364
Showing 1 changed file with 260 additions and 0 deletions.
260 changes: 260 additions & 0 deletions message_definitions/v1.0/common.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2885,6 +2885,218 @@
<description>North, East, Down</description>
</entry>
</enum>
<enum name="MAV_FIELD">
<description>This describes the type of a field in an array, for example usage (see ESTIMATOR_STATE)</description>
<entry value="0" name="MAV_FIELD_UNUSED">
<description>Unused state.</description>
</entry>
<!--XY Position -->
<entry value="1" name="MAV_FIELD_POS_N">
<description>Position North, m</description>
</entry>
<entry value="2" name="MAV_FIELD_POS_E">
<description>Position East, m</description>
</entry>
<!--Altitude -->
<entry value="3" name="MAV_FIELD_POS_D">
<description>Position Down, m</description>
</entry>
<entry value="4" name="MAV_FIELD_ASL">
<description>Altitude above sea level, m</description>
</entry>
<entry value="5" name="MAV_FIELD_AGL">
<description>Altitude above ground level, m</description>
</entry>
<!--Velocity -->
<entry value="6" name="MAV_FIELD_VEL_N">
<description>Velocity North, m/s</description>
</entry>
<entry value="7" name="MAV_FIELD_VEL_E">
<description>Velocity East, m/s</description>
</entry>
<entry value="8" name="MAV_FIELD_VEL_D">
<description>Velocity Down, m/s</description>
</entry>
<entry value="9" name="MAV_FIELD_VEL_X">
<description>Velocity body x (forward), m/s</description>
</entry>
<entry value="10" name="MAV_FIELD_VEL_Y">
<description>Velocity body y (right), m/s</description>
</entry>
<entry value="11" name="MAV_FIELD_VEL_Z">
<description>Velocity body z (down), m/s</description>
</entry>
<!--Acceleration -->
<entry value="12" name="MAV_FIELD_ACC_N">
<description>Acceleration North, m/s</description>
</entry>
<entry value="13" name="MAV_FIELD_ACC_E">
<description>Acceleration East, m/s</description>
</entry>
<entry value="14" name="MAV_FIELD_ACC_D">
<description>Acceleration Down, m/s</description>
</entry>
<entry value="15" name="MAV_FIELD_ACC_X">
<description>Acceleration body x (forward), m/s</description>
</entry>
<entry value="16" name="MAV_FIELD_ACC_Y">
<description>Acceleration body y (right), m/s</description>
</entry>
<entry value="17" name="MAV_FIELD_ACC_Z">
<description>Acceleration body z (down), m/s</description>
</entry>
<!--Attitude -->
<entry value="18" name="MAV_FIELD_Q0">
<description>Quaternion from nav to body scalar component</description>
</entry>
<entry value="19" name="MAV_FIELD_Q1">
<description>Quaternion from nav to body vector[0] component</description>
</entry>
<entry value="20" name="MAV_FIELD_Q2">
<description>Quaternion from nav to body vector[1] component</description>
</entry>
<entry value="21" name="MAV_FIELD_Q3">
<description>Quaternion from nav to body vector[2] component</description>
</entry>
<entry value="22" name="MAV_FIELD_ROLL">
<description>Euler Body 3-2-1 (Tait-Bryan) roll angle, radians</description>
</entry>
<entry value="23" name="MAV_FIELD_PITCH">
<description>Euler Body 3-2-1 (Tait-Bryan) pitch angle, radians</description>
</entry>
<entry value="24" name="MAV_FIELD_YAW">
<description>Euler Body 3-2-1 (Tait-Bryan) yaw angle, radians</description>
</entry>
<!--Angular Velocity-->
<entry value="25" name="MAV_FIELD_ANGVEL_X">
<description>Euler Body x rate, radians/second</description>
</entry>
<entry value="26" name="MAV_FIELD_ANGVEL_Y">
<description>Euler Body y rate, radians/second</description>
</entry>
<entry value="27" name="MAV_FIELD_ANGVEL_Z">
<description>Euler Body z rate, radians/second</description>
</entry>
<entry value="28" name="MAV_FIELD_ROLLRATE">
<description>Euler Body 3-2-1 (Tait-Bryan) roll angle rate, radians/second</description>
</entry>
<entry value="29" name="MAV_FIELD_PITCHRATE">
<description>Euler Body 3-2-1 (Tait-Bryan) pitch angle rate, radians/second</description>
</entry>
<entry value="30" name="MAV_FIELD_YAWRATE">
<description>Euler Body 3-2-1 (Tait-Bryan) yaw angle rate, radians/second</description>
</entry>
<!--Geodetic Position -->
<entry value="31" name="MAV_FIELD_LAT">
<description>Latitude, radians</description>
</entry>
<entry value="32" name="MAV_FIELD_LON">
<description>Longitude, radians</description>
</entry>
<!-- Sensor Bias NAV Frame -->
<entry value="33" name="MAV_FIELD_BIAS_N">
<description>North bias</description>
</entry>
<entry value="34" name="MAV_FIELD_BIAS_E">
<description>East bias</description>
</entry>
<entry value="35" name="MAV_FIELD_BIAS_D">
<description>Down z bias</description>
</entry>
<!--Sensor Bias Body Frame -->
<entry value="36" name="MAV_FIELD_BIAS_X">
<description>Body x bias</description>
</entry>
<entry value="37" name="MAV_FIELD_BIAS_Y">
<description>Body y bias</description>
</entry>
<entry value="38" name="MAV_FIELD_BIAS_Z">
<description>Body z bias</description>
</entry>
<!--Terrain -->
<entry value="39" name="MAV_FIELD_TERRAIN_ASL">
<description>Altitude of terrain above sea level, m</description>
</entry>
<!--Airspeed -->
<entry value="40" name="MAV_FIELD_AIRSPEED">
<description>Airspeed, m/s</description>
</entry>
<!--Optical Flow -->
<entry value="41" name="MAV_FIELD_FLOW_X">
<description>Optical flow in body x, radians</description>
</entry>
<entry value="42" name="MAV_FIELD_FLOW_Y">
<description>Optical flow in body y, radians</description>
</entry>
<!--Magnetic field -->
<entry value="43" name="MAV_FIELD_MAG_X">
<description>Magnetic field, body x, Gauss</description>
</entry>
<entry value="44" name="MAV_FIELD_MAG_Y">
<description>Magnetic field, body y, Gauss</description>
</entry>
<entry value="45" name="MAV_FIELD_MAG_Z">
<description>Magnetic field, body z, Gauss</description>
</entry>
<entry value="46" name="MAV_FIELD_MAG_HDG">
<description>Magnetic heading, radians</description>
</entry>
<!--Distance -->
<entry value="47" name="MAV_FIELD_DIST_BOTTOM">
<description>Distance bottom, m</description>
</entry>
<entry value="48" name="MAV_FIELD_DIST_TOP">
<description>Distance top, m</description>
</entry>
<entry value="49" name="MAV_FIELD_DIST_FRONT">
<description>Distance front, m</description>
</entry>
<entry value="50" name="MAV_FIELD_DIST_BACK">
<description>Distance back, m</description>
</entry>
<entry value="51" name="MAV_FIELD_DIST_LEFT">
<description>Distance left, m</description>
</entry>
<entry value="52" name="MAV_FIELD_DIST_RIGHT">
<description>Distance right, m</description>
</entry>
</enum>
<enum name="MAV_SENSOR_TYPE">
<description>Sensor type</description>
<entry value="0" name="MAV_SENSOR_TYPE_NONE">
<description>No associated sensor</description>
</entry>
<entry value="1" name="MAV_SENSOR_TYPE_GPS">
<description>GPS</description>
</entry>
<entry value="2" name="MAV_SENSOR_TYPE_SONAR">
<description>Sonar</description>
</entry>
<entry value="3" name="MAV_SENSOR_TYPE_LIDAR">
<description>Lidar</description>
</entry>
<entry value="4" name="MAV_SENSOR_TYPE_GYRO">
<description>Gyroscope</description>
</entry>
<entry value="5" name="MAV_SENSOR_TYPE_ACCEL">
<description>Accelerometer</description>
</entry>
<entry value="6" name="MAV_SENSOR_TYPE_MAG">
<description>Magnetometer</description>
</entry>
<entry value="7" name="MAV_SENSOR_TYPE_BARO">
<description>Barometric altimeter</description>
</entry>
<entry value="8" name="MAV_SENSOR_TYPE_PITOT">
<description>Pitot tube</description>
</entry>
<entry value="9" name="MAV_SENSOR_TYPE_MOCAP">
<description>Motion capture</description>
</entry>
<entry value="10" name="MAV_SENSOR_TYPE_FLOW">
<description>Optical flow</description>
</entry>
</enum>
</enums>
<messages>
<message id="0" name="HEARTBEAT">
Expand Down Expand Up @@ -4521,6 +4733,7 @@
<field type="uint8_t" name="target_component">component ID of the target</field>
<field type="uint16_t" name="sequence">sequence number (must match the one in LOGGING_DATA_ACKED)</field>
</message>
<<<<<<< 1d007c59dbe0121b7f2063a8919a44703634a5ef
<message id="269" name="VIDEO_STREAM_INFORMATION">
<description>WIP: Information about video stream</description>
<field type="uint8_t" name="camera_id">Camera ID (1 for first, 2 for second, etc.)</field>
Expand Down Expand Up @@ -4622,6 +4835,53 @@
<field type="uint8_t" name="increment" units="deg">Angular width in degrees of each array element.</field>
<field type="uint16_t" name="min_distance" units="cm">Minimum distance the sensor can measure in centimeters.</field>
<field type="uint16_t" name="max_distance" units="cm">Maximum distance the sensor can measure in centimeters.</field>
<message id="335" name="ESTIMATOR_STATE">
<description>An estimator agnostic state message</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (microseconds since system boot or since UNIX epoch)</field>
<field type="uint8_t" name="n">Number of states, max 21</field>
<field type="uint8_t[21]" name="id" enum="MAV_FIELD">An array describing field type (see MAV_FIELD)</field>
<field type="uint8_t[21]" name="sensor" enum="MAV_SENSOR_TYPE">An array describing the sensor associated with the field (see MAV_SENSOR_TYPE)</field>
<field type="float[21]" name="state">The estimator state</field>
</message>
<message id="336" name="ESTIMATOR_STATE_STD">
<description>An estimator agnostic state standard deviation message</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (microseconds since system boot or since UNIX epoch)</field>
<field type="uint8_t" name="n">Number of states, max 21</field>
<field type="uint8_t[21]" name="id" enum="MAV_FIELD">An array describing field type (see MAV_FIELD)</field>
<field type="uint8_t[21]" name="sensor" enum="MAV_SENSOR_TYPE">An array describing the sensor associated with the field (see MAV_SENSOR_TYPE)</field>
<field type="float[21]" name="std">The estimator state standard deviation sqrt(diag(P))</field>
</message>
<message id="337" name="ESTIMATOR_STATE_COV">
<description>An estimator agnostic state covariance message. Note: Very large, not meant for use over radio.</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (microseconds since system boot or since UNIX epoch)</field>
<field type="uint8_t" name="n">Number of states, max 21, limited by mavlink protocol</field>
<field type="uint8_t[21]" name="id" enum="MAV_FIELD">An array describing field type (see MAV_FIELD)</field>
<field type="uint8_t[21]" name="sensor" enum="MAV_SENSOR_TYPE">An array describing the sensor associated with the field (see MAV_SENSOR_TYPE)</field>
<field type="float[210]" name="cov">The estimator covariance matrix (upper triangle), horizontally stacked with lengths [n, n-1, n-2, ..., 1]</field>
</message>
<message id="338" name="ESTIMATOR_INNOV">
<description>An estimator agnostic innovation message</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (microseconds since system boot or since UNIX epoch)</field>
<field type="uint8_t" name="n">Number of innovations, max 21</field>
<field type="uint8_t[21]" name="id" enum="MAV_FIELD">An array describing field type (see MAV_FIELD)</field>
<field type="uint8_t[21]" name="sensor" enum="MAV_SENSOR_TYPE">An array describing the sensor associated with the field (see MAV_SENSOR_TYPE)</field>
<field type="float[21]" name="innov">The estimator innovation</field>
</message>
<message id="339" name="ESTIMATOR_INNOV_STD">
<description>An estimator agnostic innovation standard deviation message</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (microseconds since system boot or since UNIX epoch)</field>
<field type="uint8_t" name="n">Number of innovations, max 21</field>
<field type="uint8_t[21]" name="id" enum="MAV_FIELD">An array describing field type (see MAV_FIELD)</field>
<field type="uint8_t[21]" name="sensor" enum="MAV_SENSOR_TYPE">An array describing the sensor associated with the field (see MAV_SENSOR_TYPE)</field>
<field type="float[21]" name="std">The estimator innovation standard deviation sqrt(diag(S))</field>
</message>
<message id="340" name="ESTIMATOR_INNOV_COV">
<description>An estimator agnostic innovation covariance message. Note: Very large, not meant for use over radio.</description>
<field type="uint64_t" name="time_usec" units="us">Timestamp (microseconds since system boot or since UNIX epoch)</field>
<field type="uint8_t" name="n">Number of innovations, max 21, limited by mavlink protocol</field>
<field type="uint8_t[21]" name="id" enum="MAV_FIELD">An array describing field type (see MAV_FIELD)</field>
<field type="uint8_t[21]" name="sensor" enum="MAV_SENSOR_TYPE">An array describing the sensor associated with the field (see MAV_SENSOR_TYPE)</field>
<field type="float[210]" name="cov">The estimator covariance matrix (upper triangle), horizontally stacked with lengths [n, n-1, n-2, ..., 1]</field>
</message>
<message id="331" name="ODOMETRY">
<description>Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (http://www.ros.org/reps/rep-0147.html).</description>
Expand Down

0 comments on commit 02a0364

Please sign in to comment.