aboutsummaryrefslogtreecommitdiff
path: root/concise.xml
diff options
context:
space:
mode:
authorJakob Odersky <jodersky@gmail.com>2014-12-16 00:09:12 +0100
committerJakob Odersky <jodersky@gmail.com>2014-12-16 00:09:12 +0100
commit458971f834a3af0dbf2fffe527352fa11e7d8168 (patch)
tree226675f8402f2c099cb15b21cab28eb8784f1c96 /concise.xml
parent84c641d12187183466df936eaa7c1637d861cf62 (diff)
downloadmavigator-458971f834a3af0dbf2fffe527352fa11e7d8168.tar.gz
mavigator-458971f834a3af0dbf2fffe527352fa11e7d8168.tar.bz2
mavigator-458971f834a3af0dbf2fffe527352fa11e7d8168.zip
generate mavlink files in build
Diffstat (limited to 'concise.xml')
-rw-r--r--concise.xml93
1 files changed, 93 insertions, 0 deletions
diff --git a/concise.xml b/concise.xml
new file mode 100644
index 0000000..9be16f7
--- /dev/null
+++ b/concise.xml
@@ -0,0 +1,93 @@
+<?xml version='1.0'?>
+<mavlink>
+ <version>1</version>
+ <enums>
+ <enum name="MAV_STATE">
+ <entry value="0" name="MAV_STATE_UNINIT">
+ <description>Uninitialized system, state is unknown.</description>
+ </entry>
+ <entry value="1" name="MAV_STATE_BOOT">
+ <description>System is booting up.</description>
+ </entry>
+ <entry value="2" name="MAV_STATE_CALIBRATING">
+ <description>System is calibrating and not flight-ready.</description>
+ </entry>
+ <entry value="3" name="MAV_STATE_STANDBY">
+ <description>System is grounded and on standby. It can be launched any time.</description>
+ </entry>
+ <entry value="4" name="MAV_STATE_ACTIVE">
+ <description>System is active and might be already airborne. Motors are engaged.</description>
+ </entry>
+ <entry value="5" name="MAV_STATE_CRITICAL">
+ <description>System is in a non-normal flight mode. It can however still navigate.</description>
+ </entry>
+ <entry value="6" name="MAV_STATE_EMERGENCY">
+ <description>System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.</description>
+ </entry>
+ <entry value="7" name="MAV_STATE_POWEROFF">
+ <description>System just initialized its power-down sequence, will shut down now.</description>
+ </entry>
+ </enum>
+ </enums>
+ <messages>
+ <message id="0" name="HEARTBEAT">
+ <description>The heartbeat message shows that a system is present and responding.</description>
+ <field type="uint8_t" name="system_state" enum="MAV_STATE">Global state of system.</field>
+ </message>
+ <message id="1" name="POWER">
+ <description>Information about the main power source.</description>
+ <field type="uint16_t" name="voltage">Voltage of the source (mV)</field>
+ </message>
+ <message id="2" name="IMU">
+ <description>The IMU readings in a NED body frame</description>
+ <field type="int32_t" name="xacc">X acceleration (mm/s^2)</field>
+ <field type="int32_t" name="yacc">Y acceleration (mm/s^2)</field>
+ <field type="int32_t" name="zacc">Z acceleration (mm/s^2)</field>
+ <field type="int32_t" name="xgyro">Angular speed around X axis (mrad / sec)</field>
+ <field type="int32_t" name="ygyro">Angular speed around Y axis (mrad / sec)</field>
+ <field type="int32_t" name="zgyro">Angular speed around Z axis (mrad / sec)</field>
+ <field type="int32_t" name="xmag">X Magnetic field (uT)</field>
+ <field type="int32_t" name="ymag">Y Magnetic field (uT)</field>
+ <field type="int32_t" name="zmag">Z Magnetic field (uT)</field>
+ <field type="int32_t" name="alt">Altitude to mean sea level (mm)</field>
+ <field type="uint32_t" name="temperature">Ambient temperature (mK)</field>
+ </message>
+ <message id="3" name="DISTANCE">
+ <description>Information on distance sensors</description>
+ <field type="int16_t" name="relative_alt">Relative altitude to ground (mm)</field>
+ </message>
+ <message name="PING" id="4">
+ <description>Ping a target system, usually used to determine latency.</description>
+ <field type="uint8_t" name="target_system">System ID</field>
+ <field type="uint8_t" name="target_component">Component ID</field>
+ </message>
+ <message name="ACK" id="5">
+ <description>Acknowledgement packet</description>
+ <field type="uint8_t" name="target_system">System ID</field>
+ <field type="uint8_t" name="target_component">Component ID</field>
+ </message>
+ <message id="70" name="RC_CHANNELS_OVERRIDE">
+ <description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
+ <field type="uint8_t" name="target_system">System ID</field>
+ <field type="uint8_t" name="target_component">Component ID</field>
+ <field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
+ <field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
+ <field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
+ <field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
+ <field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
+ <field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
+ <field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
+ <field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
+ </message>
+ <message name="RADIO_STATUS" id="109">
+ <description>Status generated by radio</description>
+ <field type="uint8_t" name="rssi">local signal strength</field>
+ <field type="uint8_t" name="remrssi">remote signal strength</field>
+ <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
+ <field type="uint8_t" name="noise">background noise level</field>
+ <field type="uint8_t" name="remnoise">remote background noise level</field>
+ <field type="uint16_t" name="rxerrors">receive errors</field>
+ <field type="uint16_t" name="fixed">count of error corrected packets</field>
+ </message>
+ </messages>
+</mavlink>