GCS_MAVLink: update from upstream XML

This commit is contained in:
Andrew Tridgell 2015-03-04 19:21:24 +11:00
parent e0f828f4d2
commit eeacbe518b
2 changed files with 58 additions and 1 deletions

View File

@ -56,7 +56,7 @@
<description>Start/stop AutoQuad telemetry values stream.</description>
<param index="1">Start or stop (1 or 0)</param>
<param index="2">Stream frequency in us</param>
<param index="3">Empty</param>
<param index="3">Dataset ID (refer to aq_mavlink.h::mavlinkCustomDataSets enum in AQ flight controller code)</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
@ -83,6 +83,12 @@
<param index="7">Empty</param>
</entry>
</enum>
<!-- extend MAV_DATA_STREAM -->
<enum name="MAV_DATA_STREAM">
<entry value="13" name="MAV_DATA_STREAM_PROPULSION">
<description>Motor/ESC telemetry data.</description>
</entry>
</enum>
</enums>
<messages>
<message id="150" name="AQ_TELEMETRY_F">
@ -109,5 +115,28 @@
<field type="float" name="value19">value19</field>
<field type="float" name="value20">value20</field>
</message>
<message id="152" name="AQ_ESC_TELEMETRY">
<description>Sends ESC32 telemetry data for up to 4 motors. Multiple messages may be sent in sequence when system has > 4 motors. Data is described as follows:
// unsigned int state : 3;
// unsigned int vin : 12; // x 100
// unsigned int amps : 14; // x 100
// unsigned int rpm : 15;
// unsigned int duty : 8; // x (255/100)
// - Data Version 2 -
// unsigned int errors : 9; // Bad detects error count
// - Data Version 3 -
// unsigned int temp : 9; // (Deg C + 32) * 4
// unsigned int errCode : 3;
</description>
<field type="uint32_t" name="time_boot_ms">Timestamp of the component clock since boot time in ms.</field>
<field type="uint8_t" name="seq">Sequence number of message (first set of 4 motors is #1, next 4 is #2, etc).</field>
<field type="uint8_t" name="num_motors">Total number of active ESCs/motors on the system.</field>
<field type="uint8_t" name="num_in_seq">Number of active ESCs in this sequence (1 through this many array members will be populated with data)</field>
<field type="uint8_t[4]" name="escid">ESC/Motor ID</field>
<field type="uint16_t[4]" name="status_age">Age of each ESC telemetry reading in ms compared to boot time. A value of 0xFFFF means timeout/no data.</field>
<field type="uint8_t[4]" name="data_version">Version of data structure (determines contents).</field>
<field type="uint32_t[4]" name="data0">Data bits 1-32 for each ESC.</field>
<field type="uint32_t[4]" name="data1">Data bits 33-64 for each ESC.</field>
</message>
</messages>
</mavlink>

View File

@ -124,6 +124,21 @@
<description>Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.</description>
</entry>
<!-- Entries up to 25 reserved for other VTOL airframes -->
<entry value="21" name="MAV_TYPE_VTOL_RESERVED1">
<description>VTOL reserved 1</description>
</entry>
<entry value="22" name="MAV_TYPE_VTOL_RESERVED2">
<description>VTOL reserved 2</description>
</entry>
<entry value="23" name="MAV_TYPE_VTOL_RESERVED3">
<description>VTOL reserved 3</description>
</entry>
<entry value="24" name="MAV_TYPE_VTOL_RESERVED4">
<description>VTOL reserved 4</description>
</entry>
<entry value="25" name="MAV_TYPE_VTOL_RESERVED5">
<description>VTOL reserved 5</description>
</entry>
<entry value="26" name="MAV_TYPE_GIMBAL">
<description>Onboard gimbal</description>
</entry>
@ -2483,6 +2498,19 @@
<field type="uint32_t" name="accuracy">Current estimate of baseline accuracy.</field>
<field type="int32_t" name="iar_num_hypotheses">Current number of integer ambiguity hypotheses.</field>
</message>
<message id="129" name="SCALED_IMU3">
<description>The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="int16_t" name="xacc">X acceleration (mg)</field>
<field type="int16_t" name="yacc">Y acceleration (mg)</field>
<field type="int16_t" name="zacc">Z acceleration (mg)</field>
<field type="int16_t" name="xgyro">Angular speed around X axis (millirad /sec)</field>
<field type="int16_t" name="ygyro">Angular speed around Y axis (millirad /sec)</field>
<field type="int16_t" name="zgyro">Angular speed around Z axis (millirad /sec)</field>
<field type="int16_t" name="xmag">X Magnetic field (milli tesla)</field>
<field type="int16_t" name="ymag">Y Magnetic field (milli tesla)</field>
<field type="int16_t" name="zmag">Z Magnetic field (milli tesla)</field>
</message>
<message id="130" name="DATA_TRANSMISSION_HANDSHAKE">
<field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
<field type="uint32_t" name="size">total data size in bytes (set on ACK only)</field>