199 lines
10 KiB
XML
199 lines
10 KiB
XML
<?xml version="1.0"?>
|
|
<!-- AVSS is a Canadian aerospace company commercializing safety technologies for Urban Air Mobility. -->
|
|
<!-- AVSS is first commercially available products are parachute recovery systems for commercial drones. -->
|
|
<!-- AVSS contact info: -->
|
|
<!-- company URL: https://www.avss.co -->
|
|
<!-- email contact: josh.boudreau@avss.co thomas.li@avss.co llxxgg@gmail.com-->
|
|
<!-- mavlink messenger ID range: 60050 - 60099, mavlink command ID range: 60050 - 60099-->
|
|
<mavlink>
|
|
<include>common.xml</include>
|
|
<version>2</version>
|
|
<dialect>1</dialect>
|
|
<enums>
|
|
<enum name="MAV_CMD">
|
|
<!-- AVSS specific MAV_CMD_PRS* commands -->
|
|
<entry name="MAV_CMD_PRS_SET_ARM" value="60050" isDestination="false" hasLocation="false">
|
|
<description>AVSS defined command. Set PRS arm statuses.</description>
|
|
<param index="1" label="ARM status">PRS arm statuses</param>
|
|
<param index="2">User defined</param>
|
|
<param index="3">User defined</param>
|
|
<param index="4">User defined</param>
|
|
<param index="5">User defined</param>
|
|
<param index="6">User defined</param>
|
|
<param index="7">User defined</param>
|
|
</entry>
|
|
<entry name="MAV_CMD_PRS_GET_ARM" value="60051" isDestination="false" hasLocation="false">
|
|
<description>AVSS defined command. Gets PRS arm statuses</description>
|
|
<param index="1">User defined</param>
|
|
<param index="2">User defined</param>
|
|
<param index="3">User defined</param>
|
|
<param index="4">User defined</param>
|
|
<param index="5">User defined</param>
|
|
<param index="6">User defined</param>
|
|
<param index="7">User defined</param>
|
|
</entry>
|
|
<entry name="MAV_CMD_PRS_GET_BATTERY" value="60052" isDestination="false" hasLocation="false">
|
|
<description>AVSS defined command. Get the PRS battery voltage in millivolts</description>
|
|
<param index="1">User defined</param>
|
|
<param index="2">User defined</param>
|
|
<param index="3">User defined</param>
|
|
<param index="4">User defined</param>
|
|
<param index="5">User defined</param>
|
|
<param index="6">User defined</param>
|
|
<param index="7">User defined</param>
|
|
</entry>
|
|
<entry name="MAV_CMD_PRS_GET_ERR" value="60053" isDestination="false" hasLocation="false">
|
|
<description>AVSS defined command. Get the PRS error statuses.</description>
|
|
<param index="1">User defined</param>
|
|
<param index="2">User defined</param>
|
|
<param index="3">User defined</param>
|
|
<param index="4">User defined</param>
|
|
<param index="5">User defined</param>
|
|
<param index="6">User defined</param>
|
|
<param index="7">User defined</param>
|
|
</entry>
|
|
<entry name="MAV_CMD_PRS_SET_ARM_ALTI" value="60070" isDestination="false" hasLocation="false">
|
|
<description>AVSS defined command. Set the ATS arming altitude in meters.</description>
|
|
<param index="1" label="Altitude" units="m">ATS arming altitude</param>
|
|
<param index="2">User defined</param>
|
|
<param index="3">User defined</param>
|
|
<param index="4">User defined</param>
|
|
<param index="5">User defined</param>
|
|
<param index="6">User defined</param>
|
|
<param index="7">User defined</param>
|
|
</entry>
|
|
<entry name="MAV_CMD_PRS_GET_ARM_ALTI" value="60071" isDestination="false" hasLocation="false">
|
|
<description>AVSS defined command. Get the ATS arming altitude in meters.</description>
|
|
<param index="1">User defined</param>
|
|
<param index="2">User defined</param>
|
|
<param index="3">User defined</param>
|
|
<param index="4">User defined</param>
|
|
<param index="5">User defined</param>
|
|
<param index="6">User defined</param>
|
|
<param index="7">User defined</param>
|
|
</entry>
|
|
<entry name="MAV_CMD_PRS_SHUTDOWN" value="60072" isDestination="false" hasLocation="false">
|
|
<description>AVSS defined command. Shuts down the PRS system.</description>
|
|
<param index="1">User defined</param>
|
|
<param index="2">User defined</param>
|
|
<param index="3">User defined</param>
|
|
<param index="4">User defined</param>
|
|
<param index="5">User defined</param>
|
|
<param index="6">User defined</param>
|
|
<param index="7">User defined</param>
|
|
</entry>
|
|
</enum>
|
|
<enum name="MAV_AVSS_COMMAND_FAILURE_REASON">
|
|
<entry name="PRS_NOT_STEADY" value="1">
|
|
<description>AVSS defined command failure reason. PRS not steady.</description>
|
|
</entry>
|
|
<entry name="PRS_DTM_NOT_ARMED" value="2">
|
|
<description>AVSS defined command failure reason. PRS DTM not armed.</description>
|
|
</entry>
|
|
<entry name="PRS_OTM_NOT_ARMED" value="3">
|
|
<description>AVSS defined command failure reason. PRS OTM not armed.</description>
|
|
</entry>
|
|
</enum>
|
|
<enum name="AVSS_M300_OPERATION_MODE">
|
|
<entry name="MODE_M300_MANUAL_CTRL" value="0">
|
|
<description>In manual control mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_ATTITUDE" value="1">
|
|
<description>In attitude mode </description>
|
|
</entry>
|
|
<entry name="MODE_M300_P_GPS" value="6">
|
|
<description>In GPS mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_HOTPOINT_MODE" value="9">
|
|
<description>In hotpoint mode </description>
|
|
</entry>
|
|
<entry name="MODE_M300_ASSISTED_TAKEOFF" value="10">
|
|
<description>In assisted takeoff mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_AUTO_TAKEOFF" value="11">
|
|
<description>In auto takeoff mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_AUTO_LANDING" value="12">
|
|
<description>In auto landing mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_NAVI_GO_HOME" value="15">
|
|
<description>In go home mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_NAVI_SDK_CTRL" value="17">
|
|
<description>In sdk control mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_S_SPORT" value="31">
|
|
<description>In sport mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_FORCE_AUTO_LANDING" value="33">
|
|
<description>In force auto landing mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_T_TRIPOD" value="38">
|
|
<description>In tripod mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_SEARCH_MODE" value="40">
|
|
<description>In search mode</description>
|
|
</entry>
|
|
<entry name="MODE_M300_ENGINE_START" value="41">
|
|
<description>In engine mode</description>
|
|
</entry>
|
|
</enum>
|
|
<enum name="AVSS_HORSEFLY_OPERATION_MODE">
|
|
<entry name="MODE_HORSEFLY_MANUAL_CTRL" value="0">
|
|
<description>In manual control mode</description>
|
|
</entry>
|
|
<entry name="MODE_HORSEFLY_AUTO_TAKEOFF" value="1">
|
|
<description>In auto takeoff mode</description>
|
|
</entry>
|
|
<entry name="MODE_HORSEFLY_AUTO_LANDING" value="2">
|
|
<description>In auto landing mode</description>
|
|
</entry>
|
|
<entry name="MODE_HORSEFLY_NAVI_GO_HOME" value="3">
|
|
<description>In go home mode</description>
|
|
</entry>
|
|
<entry name="MODE_HORSEFLY_DROP" value="4">
|
|
<description>In drop mode</description>
|
|
</entry>
|
|
</enum>
|
|
</enums>
|
|
<messages>
|
|
<message name="AVSS_PRS_SYS_STATUS" id="60050">
|
|
<description> AVSS PRS system status.</description>
|
|
<field name="time_boot_ms" units="ms" type="uint32_t">Timestamp (time since PRS boot).</field>
|
|
<field name="error_status" type="uint32_t">PRS error statuses</field>
|
|
<field name="battery_status" type="uint32_t">Estimated battery run-time without a remote connection and PRS battery voltage</field>
|
|
<field name="arm_status" type="uint8_t">PRS arm statuses</field>
|
|
<field name="charge_status" type="uint8_t">PRS battery charge statuses</field>
|
|
</message>
|
|
<message name="AVSS_DRONE_POSITION" id="60051">
|
|
<description> Drone position.</description>
|
|
<field name="time_boot_ms" units="ms" type="uint32_t">Timestamp (time since FC boot).</field>
|
|
<field name="lat" units="degE7" type="int32_t">Latitude, expressed</field>
|
|
<field name="lon" units="degE7" type="int32_t">Longitude, expressed</field>
|
|
<field name="alt" units="mm" type="int32_t">Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.</field>
|
|
<field name="ground_alt" units="m" type="float">Altitude above ground, This altitude is measured by a ultrasound, Laser rangefinder or millimeter-wave radar</field>
|
|
<field name="barometer_alt" units="m" type="float">This altitude is measured by a barometer</field>
|
|
</message>
|
|
<message name="AVSS_DRONE_IMU" id="60052">
|
|
<description> Drone IMU data. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).</description>
|
|
<field name="time_boot_ms" units="ms" type="uint32_t">Timestamp (time since FC boot).</field>
|
|
<field name="q1" type="float">Quaternion component 1, w (1 in null-rotation)</field>
|
|
<field name="q2" type="float">Quaternion component 2, x (0 in null-rotation)</field>
|
|
<field name="q3" type="float">Quaternion component 3, y (0 in null-rotation)</field>
|
|
<field name="q4" type="float">Quaternion component 4, z (0 in null-rotation)</field>
|
|
<field name="xacc" units="m/s/s" type="float">X acceleration</field>
|
|
<field name="yacc" units="m/s/s" type="float">Y acceleration</field>
|
|
<field name="zacc" units="m/s/s" type="float">Z acceleration</field>
|
|
<field name="xgyro" units="rad/s" type="float">Angular speed around X axis</field>
|
|
<field name="ygyro" units="rad/s" type="float">Angular speed around Y axis</field>
|
|
<field name="zgyro" units="rad/s" type="float">Angular speed around Z axis</field>
|
|
</message>
|
|
<message name="AVSS_DRONE_OPERATION_MODE" id="60053">
|
|
<description> Drone operation mode.</description>
|
|
<field name="time_boot_ms" units="ms" type="uint32_t">Timestamp (time since FC boot).</field>
|
|
<field name="M300_operation_mode" type="uint8_t">DJI M300 operation mode</field>
|
|
<field name="horsefly_operation_mode" type="uint8_t">horsefly operation mode</field>
|
|
</message>
|
|
</messages>
|
|
</mavlink>
|