GCS_MAVLink: import latest MAVLink XML

This commit is contained in:
Andrew Tridgell 2014-08-07 12:21:10 +10:00
parent dd93c6e0ca
commit 5ed24557b3
2 changed files with 34 additions and 7 deletions

View File

@ -77,13 +77,13 @@
<!-- Camera event types -->
<enum name="CAMERA_STATUS_TYPES">
<entry name="HEARTBEAT" value="0"><description>Camera heartbeat, announce camera component ID at 1hz</description></entry>
<entry name="TRIGGER" value="1"><description>Camera image triggered</description></entry>
<entry name="DISCONNECT" value="2"><description>Camera connection lost</description></entry>
<entry name="ERROR" value="3"><description>Camera unknown error</description></entry>
<entry name="LOWBATT" value="4"><description>Camera battery low. Parameter p1 shows reported voltage</description></entry>
<entry name="LOWSTORE" value="5"><description>Camera storage low. Parameter p1 shows reported shots remaining</description></entry>
<entry name="LOWSTOREV" value="6"><description>Camera storage low. Parameter p1 shows reported video minutes remaining</description></entry>
<entry name="CAMERA_STATUS_TYPE_HEARTBEAT" value="0"><description>Camera heartbeat, announce camera component ID at 1hz</description></entry>
<entry name="CAMERA_STATUS_TYPE_TRIGGER" value="1"><description>Camera image triggered</description></entry>
<entry name="CAMERA_STATUS_TYPE_DISCONNECT" value="2"><description>Camera connection lost</description></entry>
<entry name="CAMERA_STATUS_TYPE_ERROR" value="3"><description>Camera unknown error</description></entry>
<entry name="CAMERA_STATUS_TYPE_LOWBATT" value="4"><description>Camera battery low. Parameter p1 shows reported voltage</description></entry>
<entry name="CAMERA_STATUS_TYPE_LOWSTORE" value="5"><description>Camera storage low. Parameter p1 shows reported shots remaining</description></entry>
<entry name="CAMERA_STATUS_TYPE_LOWSTOREV" value="6"><description>Camera storage low. Parameter p1 shows reported video minutes remaining</description></entry>
</enum>
<!-- camera feedback flags, a little bit of future-proofing -->

View File

@ -193,5 +193,32 @@
<field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field>
<field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field>
</message>
<message id="205" name="DETECTION_STATS">
<field type="uint16_t" name="detections">Number of detections</field>
<field type="float" name="best_score">Best score</field>
<field type="int32_t" name="best_lat">Latitude of best detection * 1E7</field>
<field type="int32_t" name="best_lon">Longitude of best detection * 1E7</field>
<field type="int16_t" name="best_alt">Altitude of best detection * 1E3</field>
<field type="int32_t" name="best_detection_id">ID of best detection</field>
<field type="uint16_t" name="images_done">Number of images already processed</field>
<field type="uint16_t" name="images_todo">Number of images still to process</field>
<field type="float" name="fps">Average images per seconds processed</field>
</message>
<message id="206" name="ONBOARD_HEALTH">
<field type="uint32_t" name="uptime">Uptime of system</field>
<field type="uint16_t" name="cpu_freq">CPU frequency</field>
<field type="uint8_t" name="cpu_load">CPU load in percent</field>
<field type="uint8_t" name="ram_usage">RAM usage in percent</field>
<field type="float" name="ram_total">RAM size in GiB</field>
<field type="uint8_t" name="swap_usage">Swap usage in percent</field>
<field type="float" name="swap_total">Swap size in GiB</field>
<field type="int8_t" name="disk_health">Disk health (-1: N/A, 0: ERR, 1: RO, 2: RW)</field>
<field type="uint8_t" name="disk_usage">Disk usage in percent</field>
<field type="float" name="disk_total">Disk total in GiB</field>
<field type="float" name="temp">Temperature</field>
<field type="float" name="voltage">Supply voltage V</field>
<field type="float" name="network_load_in">Network load inbound KiB/s</field>
<field type="float" name="network_load_out">Network load outbound in KiB/s </field>
</message>
</messages>
</mavlink>