GCS_MAVLink: merged latest changes from upstream
This commit is contained in:
parent
2c86f5df94
commit
0f24c43b0c
@ -13,16 +13,6 @@
|
||||
|
||||
<!-- ardupilot specific MAV_CMD_* commands -->
|
||||
<enum name="MAV_CMD">
|
||||
<entry name="MAV_CMD_NAV_GUIDED" value="90">
|
||||
<description>Pass control to an external controller.</description>
|
||||
<param index="1">Timeout in seconds. The maximum amount of time that the external controller will be allowed to control the vehicle. 0 means no timeout</param>
|
||||
<param index="2">Altitude min. If vehicle moves below this altitude the command will be aborted and the mission will continue. 0 for no lower alt limit</param>
|
||||
<param index="3">Altitude max. If vehicle moves above this altitude the command will be aborted and the mission will continue. 0 for no upper alt limit</param>
|
||||
<param index="4">Horizontal move limit. If vehicle moves more than this distance from it's location at the moment the command was begun, the command will be aborted and the mission will continue. 0 for no horizontal movement limit</param>
|
||||
<param index="5">Empty</param>
|
||||
<param index="6">Empty</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
<entry name="MAV_CMD_NAV_VELOCITY" value="91">
|
||||
<description>Navigate at the specified velocity</description>
|
||||
<param index="1">coordinate_frame - see MAV_FRAME enum</param>
|
||||
|
@ -396,6 +396,9 @@
|
||||
<entry value="2097152" name="MAV_SYS_STATUS_AHRS">
|
||||
<description>0x200000 AHRS subsystem health</description>
|
||||
</entry>
|
||||
<entry value="4194304" name="MAV_SYS_STATUS_TERRAIN">
|
||||
<description>0x400000 Terrain subsystem health</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_FRAME">
|
||||
<entry value="0" name="MAV_FRAME_GLOBAL">
|
||||
@ -419,6 +422,15 @@
|
||||
<entry value="6" name="MAV_FRAME_GLOBAL_RELATIVE_ALT_INT">
|
||||
<description>Global coordinate frame with some fields as scaled integers, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations.</description>
|
||||
</entry>
|
||||
<entry value="7" name="MAV_FRAME_LOCAL_OFFSET_NED">
|
||||
<description>Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position.</description>
|
||||
</entry>
|
||||
<entry value="8" name="MAV_FRAME_BODY_NED">
|
||||
<description>Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right.</description>
|
||||
</entry>
|
||||
<entry value="9" name="MAV_FRAME_BODY_OFFSET_NED">
|
||||
<description>Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAVLINK_DATA_STREAM_TYPE">
|
||||
<entry name="MAVLINK_DATA_STREAM_IMG_JPEG">
|
||||
@ -581,6 +593,36 @@
|
||||
<param index="6">Longitude/Y of goal</param>
|
||||
<param index="7">Altitude/Z of goal</param>
|
||||
</entry>
|
||||
<entry value="90" name="MAV_CMD_NAV_GUIDED_LIMITS">
|
||||
<description>set limits for external control</description>
|
||||
<param index="1">timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout</param>
|
||||
<param index="2">absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit</param>
|
||||
<param index="3">absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit</param>
|
||||
<param index="4">horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit</param>
|
||||
<param index="5">Empty</param>
|
||||
<param index="6">Empty</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
<entry value="91" name="MAV_CMD_NAV_GUIDED_MASTER">
|
||||
<description>set id of master controller</description>
|
||||
<param index="1">System ID</param>
|
||||
<param index="2">Component ID</param>
|
||||
<param index="3">Empty</param>
|
||||
<param index="4">Empty</param>
|
||||
<param index="5">Empty</param>
|
||||
<param index="6">Empty</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
<entry value="92" name="MAV_CMD_NAV_GUIDED_ENABLE">
|
||||
<description>hand control over to an external controller</description>
|
||||
<param index="1">On / Off (> 0.5f on)</param>
|
||||
<param index="2">Empty</param>
|
||||
<param index="3">Empty</param>
|
||||
<param index="4">Empty</param>
|
||||
<param index="5">Empty</param>
|
||||
<param index="6">Empty</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
<entry value="95" name="MAV_CMD_NAV_LAST">
|
||||
<description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description>
|
||||
<param index="1">Empty</param>
|
||||
@ -731,6 +773,36 @@
|
||||
<param index="6">Empty</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
<entry value="185" name="MAV_CMD_DO_FLIGHTTERMINATION">
|
||||
<description>Terminate flight immediately</description>
|
||||
<param index="1">Flight termination activated if > 0.5</param>
|
||||
<param index="2">Empty</param>
|
||||
<param index="3">Empty</param>
|
||||
<param index="4">Empty</param>
|
||||
<param index="5">Empty</param>
|
||||
<param index="6">Empty</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
<entry value="190" name="MAV_CMD_DO_RALLY_LAND">
|
||||
<description>Mission command to perform a landing from a rally point.</description>
|
||||
<param index="1">Break altitude (meters)</param>
|
||||
<param index="2">Landing speed (m/s)</param>
|
||||
<param index="3">Empty</param>
|
||||
<param index="4">Empty</param>
|
||||
<param index="5">Empty</param>
|
||||
<param index="6">Empty</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
<entry value="191" name="MAV_CMD_DO_GO_AROUND">
|
||||
<description>Mission command to safely abort an autonmous landing.</description>
|
||||
<param index="1">Altitude (meters)</param>
|
||||
<param index="2">Empty</param>
|
||||
<param index="3">Empty</param>
|
||||
<param index="4">Empty</param>
|
||||
<param index="5">Empty</param>
|
||||
<param index="6">Empty</param>
|
||||
<param index="7">Empty</param>
|
||||
</entry>
|
||||
<entry value="200" name="MAV_CMD_DO_CONTROL_VIDEO">
|
||||
<description>Control onboard camera system.</description>
|
||||
<param index="1">Camera ID (-1 for all)</param>
|
||||
@ -1772,6 +1844,51 @@
|
||||
<field type="uint8_t" name="mode_switch">Flight mode switch position, 0.. 255</field>
|
||||
<field type="uint8_t" name="manual_override_switch">Override mode switch position, 0.. 255</field>
|
||||
</message>
|
||||
<message id="82" name="ATTITUDE_SETPOINT_EXTERNAL">
|
||||
<description>Set the vehicle attitude and body angular rates.</description>
|
||||
<field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint8_t" name="type_mask">Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude</field>
|
||||
<field type="float[4]" name="q">Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)</field>
|
||||
<field type="float" name="body_roll_rate">Body roll rate in radians per second</field>
|
||||
<field type="float" name="body_pitch_rate">Body roll rate in radians per second</field>
|
||||
<field type="float" name="body_yaw_rate">Body roll rate in radians per second</field>
|
||||
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)</field>
|
||||
</message>
|
||||
<message id="83" name="LOCAL_NED_POSITION_SETPOINT_EXTERNAL">
|
||||
<description>Set vehicle position, velocity and acceleration setpoint in local frame.</description>
|
||||
<field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7</field>
|
||||
<field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
|
||||
<field type="float" name="x">X Position in NED frame in meters</field>
|
||||
<field type="float" name="y">Y Position in NED frame in meters</field>
|
||||
<field type="float" name="z">Z Position in NED frame in meters (note, altitude is negative in NED)</field>
|
||||
<field type="float" name="vx">X velocity in NED frame in meter / s</field>
|
||||
<field type="float" name="vy">Y velocity in NED frame in meter / s</field>
|
||||
<field type="float" name="vz">Z velocity in NED frame in meter / s</field>
|
||||
<field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
|
||||
<field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
|
||||
<field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
|
||||
</message>
|
||||
<message id="84" name="GLOBAL_POSITION_SETPOINT_EXTERNAL_INT">
|
||||
<description>Set vehicle position, velocity and acceleration setpoint in the WGS84 coordinate system.</description>
|
||||
<field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.</field>
|
||||
<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="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint</field>
|
||||
<field type="int32_t" name="lat_int">X Position in WGS84 frame in 1e7 * meters</field>
|
||||
<field type="int32_t" name="lon_int">Y Position in WGS84 frame in 1e7 * meters</field>
|
||||
<field type="float" name="alt">Altitude in WGS84, not AMSL</field>
|
||||
<field type="float" name="vx">X velocity in NED frame in meter / s</field>
|
||||
<field type="float" name="vy">Y velocity in NED frame in meter / s</field>
|
||||
<field type="float" name="vz">Z velocity in NED frame in meter / s</field>
|
||||
<field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
|
||||
<field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
|
||||
<field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
|
||||
</message>
|
||||
<message id="89" name="LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET">
|
||||
<description>The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description>
|
||||
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
|
||||
@ -2169,6 +2286,35 @@
|
||||
<field type="uint8_t" name="orientation">Direction the sensor faces from FIXME enum.</field>
|
||||
<field type="uint8_t" name="covariance">Measurement covariance in centimeters, 0 for unknown / invalid readings</field>
|
||||
</message>
|
||||
<message id="133" name="TERRAIN_REQUEST">
|
||||
<description>Request for terrain data and terrain status</description>
|
||||
<field type="int32_t" name="lat">Latitude of SW corner of first grid (degrees *10^7)</field>
|
||||
<field type="int32_t" name="lon">Longitude of SW corner of first grid (in degrees *10^7)</field>
|
||||
<field type="uint16_t" name="grid_spacing">Grid spacing in meters</field>
|
||||
<field type="uint64_t" name="mask" print_format="0x%07x">Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)</field>
|
||||
</message>
|
||||
<message id="134" name="TERRAIN_DATA">
|
||||
<description>Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST</description>
|
||||
<field type="int32_t" name="lat">Latitude of SW corner of first grid (degrees *10^7)</field>
|
||||
<field type="int32_t" name="lon">Longitude of SW corner of first grid (in degrees *10^7)</field>
|
||||
<field type="uint16_t" name="grid_spacing">Grid spacing in meters</field>
|
||||
<field type="uint8_t" name="gridbit">bit within the terrain request mask</field>
|
||||
<field type="int16_t[16]" name="data">Terrain data in meters AMSL</field>
|
||||
</message>
|
||||
<message id="135" name="TERRAIN_CHECK">
|
||||
<description>Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission.</description>
|
||||
<field type="int32_t" name="lat">Latitude (degrees *10^7)</field>
|
||||
<field type="int32_t" name="lon">Longitude (degrees *10^7)</field>
|
||||
</message>
|
||||
<message id="136" name="TERRAIN_REPORT">
|
||||
<description>Response from a TERRAIN_CHECK request</description>
|
||||
<field type="int32_t" name="lat">Latitude (degrees *10^7)</field>
|
||||
<field type="int32_t" name="lon">Longitude (degrees *10^7)</field>
|
||||
<field type="uint16_t" name="spacing">grid spacing (zero if terrain at this location unavailable)</field>
|
||||
<field type="float" name="height">Terrain height in meters AMSL (-32767 if unavailable)</field>
|
||||
<field type="uint16_t" name="pending">Number of 4x4 terrain blocks waiting to be received or read from disk</field>
|
||||
<field type="uint16_t" name="loaded">Number of 4x4 terrain blocks in memory</field>
|
||||
</message>
|
||||
<message id="147" name="BATTERY_STATUS">
|
||||
<description>Transmitte battery informations for a accu pack.</description>
|
||||
<field type="uint8_t" name="accu_id">Accupack ID</field>
|
||||
|
445
libraries/GCS_MAVLink/message_definitions/slugs.xml
Normal file → Executable file
445
libraries/GCS_MAVLink/message_definitions/slugs.xml
Normal file → Executable file
@ -1,26 +1,125 @@
|
||||
<?xml version="1.0"?>
|
||||
<mavlink>
|
||||
<include>common.xml</include>
|
||||
|
||||
<!-- <enums>
|
||||
<enum name="SLUGS_ACTION" >
|
||||
<description> Slugs Actions </description>
|
||||
<entry name = "SLUGS_ACTION_NONE">
|
||||
<entry name = "SLUGS_ACTION_SUCCESS">
|
||||
<entry name = "SLUGS_ACTION_FAIL">
|
||||
<entry name = "SLUGS_ACTION_EEPROM">
|
||||
<entry name = "SLUGS_ACTION_MODE_CHANGE">
|
||||
<entry name = "SLUGS_ACTION_MODE_REPORT">
|
||||
<entry name = "SLUGS_ACTION_PT_CHANGE">
|
||||
<entry name = "SLUGS_ACTION_PT_REPORT">
|
||||
<entry name = "SLUGS_ACTION_PID_CHANGE">
|
||||
<entry name = "SLUGS_ACTION_PID_REPORT">
|
||||
<entry name = "SLUGS_ACTION_WP_CHANGE">
|
||||
<entry name = "SLUGS_ACTION_WP_REPORT">
|
||||
<entry name = "SLUGS_ACTION_MLC_CHANGE">
|
||||
<entry name = "SLUGS_ACTION_MLC_REPORT">
|
||||
</enum>
|
||||
|
||||
<enums>
|
||||
<enum name="MAV_CMD">
|
||||
<!-- 1-10000 reserved for common commands -->
|
||||
<entry value="10001" name="MAV_CMD_DO_NOTHING">
|
||||
<description>Does nothing.</description>
|
||||
<param index="1">1 to arm, 0 to disarm</param>
|
||||
</entry>
|
||||
<!-- Unused Commands -->
|
||||
<!--
|
||||
<entry value="10002" name="MAV_CMD_CALIBRATE_RC">
|
||||
<description>Initiate radio control calibration.</description>
|
||||
</entry>
|
||||
<entry value="10003" name="MAV_CMD_CALIBRATE_MAGNETOMETER">
|
||||
<description>Stops recording data.</description>
|
||||
</entry>
|
||||
<entry value="10004" name="MAV_CMD_START_RECORDING">
|
||||
<description>Start recording data.</description>
|
||||
</entry>
|
||||
<entry value="10005" name="MAV_CMD_PAUSE_RECORDING">
|
||||
<description>Pauses recording data.</description>
|
||||
</entry>
|
||||
<entry value="10006" name="MAV_CMD_STOP_RECORDING">
|
||||
<description>Stops recording data.</description>
|
||||
</entry>
|
||||
-->
|
||||
<!-- Old MAVlink Common Actions -->
|
||||
<entry value="10011" name="MAV_CMD_RETURN_TO_BASE">
|
||||
<description>Return vehicle to base.</description>
|
||||
<param index="1">0: return to base, 1: track mobile base</param>
|
||||
</entry>
|
||||
<entry value="10012" name="MAV_CMD_STOP_RETURN_TO_BASE">
|
||||
<description>Stops the vehicle from returning to base and resumes flight. </description>
|
||||
</entry>
|
||||
<entry value="10013" name="MAV_CMD_TURN_LIGHT">
|
||||
<description>Turns the vehicle's visible or infrared lights on or off.</description>
|
||||
<param index="1">0: visible lights, 1: infrared lights</param>
|
||||
<param index="2">0: turn on, 1: turn off</param>
|
||||
</entry>
|
||||
<entry value="10014" name="MAV_CMD_GET_MID_LEVEL_COMMANDS">
|
||||
<description>Requests vehicle to send current mid-level commands to ground station.</description>
|
||||
</entry>
|
||||
<entry value="10015" name="MAV_CMD_MIDLEVEL_STORAGE">
|
||||
<description>Requests storage of mid-level commands.</description>
|
||||
<param index="1">Mid-level command storage: 0: read from flash/EEPROM, 1: write to flash/EEPROM</param>
|
||||
</entry>
|
||||
<!-- From SLUGS_ACTION Enum -->
|
||||
</enum>
|
||||
|
||||
<enum name="SLUGS_MODE">
|
||||
<description>Slugs-specific navigation modes.</description>
|
||||
<entry value="0" name="SLUGS_MODE_NONE">
|
||||
<description>No change to SLUGS mode.</description>
|
||||
</entry>
|
||||
<entry value="1" name="SLUGS_MODE_LIFTOFF">
|
||||
<description>Vehicle is in liftoff mode.</description>
|
||||
</entry>
|
||||
<entry value="2" name="SLUGS_MODE_PASSTHROUGH">
|
||||
<description>Vehicle is in passthrough mode, being controlled by a pilot.</description>
|
||||
</entry>
|
||||
<entry value="3" name="SLUGS_MODE_WAYPOINT">
|
||||
<description>Vehicle is in waypoint mode, navigating to waypoints.</description>
|
||||
</entry>
|
||||
<entry value="4" name="SLUGS_MODE_MID_LEVEL">
|
||||
<description>Vehicle is executing mid-level commands.</description>
|
||||
</entry>
|
||||
<entry value="5" name="SLUGS_MODE_RETURNING">
|
||||
<description>Vehicle is returning to the home location.</description>
|
||||
</entry>
|
||||
<entry value="6" name="SLUGS_MODE_LANDING">
|
||||
<description>Vehicle is landing.</description>
|
||||
</entry>
|
||||
<entry value="7" name="SLUGS_MODE_LOST">
|
||||
<description>Lost connection with vehicle.</description>
|
||||
</entry>
|
||||
<entry value="8" name="SLUGS_MODE_SELECTIVE_PASSTHROUGH">
|
||||
<description>Vehicle is in selective passthrough mode, where selected surfaces are being manually controlled.</description>
|
||||
</entry>
|
||||
<entry value="9" name="SLUGS_MODE_ISR">
|
||||
<description>Vehicle is in ISR mode, performing reconaissance at a point specified by ISR_LOCATION message.</description>
|
||||
</entry>
|
||||
<entry value="10" name="SLUGS_MODE_LINE_PATROL">
|
||||
<description>Vehicle is patrolling along lines between waypoints.</description>
|
||||
</entry>
|
||||
<entry value="11" name="SLUGS_MODE_GROUNDED">
|
||||
<description>Vehicle is grounded or an error has occurred.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
|
||||
<enum name="CONTROL_SURFACE_FLAG">
|
||||
<description>These flags encode the control surfaces for selective passthrough mode. If a bit is set then the pilot console
|
||||
has control of the surface, and if not then the autopilot has control of the surface.</description>
|
||||
<entry value="128" name="CONTROL_SURFACE_FLAG_THROTTLE">
|
||||
<description>0b10000000 Throttle control passes through to pilot console.</description>
|
||||
</entry>
|
||||
<entry value="64" name="CONTROL_SURFACE_FLAG_LEFT_AILERON">
|
||||
<description>0b01000000 Left aileron control passes through to pilot console.</description>
|
||||
</entry>
|
||||
<entry value="32" name="CONTROL_SURFACE_FLAG_RIGHT_AILERON">
|
||||
<description>0b00100000 Right aileron control passes through to pilot console.</description>
|
||||
</entry>
|
||||
<entry value="16" name="CONTROL_SURFACE_FLAG_RUDDER">
|
||||
<description>0b00010000 Rudder control passes through to pilot console.</description>
|
||||
</entry>
|
||||
<entry value="8" name="CONTROL_SURFACE_FLAG_LEFT_ELEVATOR">
|
||||
<description>0b00001000 Left elevator control passes through to pilot console.</description>
|
||||
</entry>
|
||||
<entry value="4" name="CONTROL_SURFACE_FLAG_RIGHT_ELEVATOR">
|
||||
<description>0b00000100 Right elevator control passes through to pilot console.</description>
|
||||
</entry>
|
||||
<entry value="2" name="CONTROL_SURFACE_FLAG_LEFT_FLAP">
|
||||
<description>0b00000010 Left flap control passes through to pilot console.</description>
|
||||
</entry>
|
||||
<entry value="1" name="CONTROL_SURFACE_FLAG_RIGHT_FLAP">
|
||||
<description>0b00000001 Right flap control passes through to pilot console.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
</enums>
|
||||
<!--
|
||||
<enum name="WP_PROTOCOL_STATE" >
|
||||
<description> Waypoint Protocol States </description>
|
||||
<entry name = "WP_PROT_IDLE">
|
||||
@ -31,114 +130,210 @@
|
||||
<entry name = "WP_PROT_SENDING_WP_IDLE">
|
||||
<entry name = "WP_PROT_GETTING_WP_IDLE">
|
||||
</enum>
|
||||
-->
|
||||
|
||||
</enums> -->
|
||||
|
||||
<messages>
|
||||
|
||||
<message name="CPU_LOAD" id="170">
|
||||
<description>Sensor and DSC control loads.</description>
|
||||
<field name="sensLoad" type="uint8_t">Sensor DSC Load</field>
|
||||
<field name="ctrlLoad" type="uint8_t">Control DSC Load</field>
|
||||
<field name="batVolt" type="uint16_t">Battery Voltage in millivolts</field>
|
||||
<message name="CPU_LOAD" id="170">
|
||||
<description>Sensor and DSC control loads.</description>
|
||||
<field name="sensLoad" type="uint8_t">Sensor DSC Load</field>
|
||||
<field name="ctrlLoad" type="uint8_t">Control DSC Load</field>
|
||||
<field name="batVolt" type="uint16_t">Battery Voltage in millivolts</field>
|
||||
</message>
|
||||
|
||||
<message name="SENSOR_BIAS" id="172">
|
||||
<description>Accelerometer and gyro biases.</description>
|
||||
<field name="axBias" type="float">Accelerometer X bias (m/s)</field>
|
||||
<field name="ayBias" type="float">Accelerometer Y bias (m/s)</field>
|
||||
<field name="azBias" type="float">Accelerometer Z bias (m/s)</field>
|
||||
<field name="gxBias" type="float">Gyro X bias (rad/s)</field>
|
||||
<field name="gyBias" type="float">Gyro Y bias (rad/s)</field>
|
||||
<field name="gzBias" type="float">Gyro Z bias (rad/s)</field>
|
||||
</message>
|
||||
|
||||
<message name="DIAGNOSTIC" id="173">
|
||||
<description>Configurable diagnostic messages.</description>
|
||||
<field name="diagFl1" type="float">Diagnostic float 1</field>
|
||||
<field name="diagFl2" type="float">Diagnostic float 2</field>
|
||||
<field name="diagFl3" type="float">Diagnostic float 3</field>
|
||||
<field name="diagSh1" type="int16_t">Diagnostic short 1</field>
|
||||
<field name="diagSh2" type="int16_t">Diagnostic short 2</field>
|
||||
<field name="diagSh3" type="int16_t">Diagnostic short 3</field>
|
||||
</message>
|
||||
|
||||
<message name="SLUGS_NAVIGATION" id="176">
|
||||
<description>Data used in the navigation algorithm.</description>
|
||||
<field name="u_m" type="float">Measured Airspeed prior to the nav filter in m/s</field>
|
||||
<field name="phi_c" type="float">Commanded Roll</field>
|
||||
<field name="theta_c" type="float">Commanded Pitch</field>
|
||||
<field name="psiDot_c" type="float">Commanded Turn rate</field>
|
||||
<field name="ay_body" type="float">Y component of the body acceleration</field>
|
||||
<field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field>
|
||||
<field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field>
|
||||
<field name="fromWP" type="uint8_t">Origin WP</field>
|
||||
<field name="toWP" type="uint8_t">Destination WP</field>
|
||||
<field name="h_c" type="uint16_t">Commanded altitude in 0.1 m</field>
|
||||
</message>
|
||||
|
||||
<message name="DATA_LOG" id="177">
|
||||
<description>Configurable data log probes to be used inside Simulink</description>
|
||||
<field name="fl_1" type="float">Log value 1 </field>
|
||||
<field name="fl_2" type="float">Log value 2 </field>
|
||||
<field name="fl_3" type="float">Log value 3 </field>
|
||||
<field name="fl_4" type="float">Log value 4 </field>
|
||||
<field name="fl_5" type="float">Log value 5 </field>
|
||||
<field name="fl_6" type="float">Log value 6 </field>
|
||||
</message>
|
||||
|
||||
<message name="GPS_DATE_TIME" id="179">
|
||||
<description>Pilot console PWM messges.</description>
|
||||
<field name="year" type="uint8_t">Year reported by Gps </field>
|
||||
<field name="month" type="uint8_t">Month reported by Gps </field>
|
||||
<field name="day" type="uint8_t">Day reported by Gps </field>
|
||||
<field name="hour" type="uint8_t">Hour reported by Gps </field>
|
||||
<field name="min" type="uint8_t">Min reported by Gps </field>
|
||||
<field name="sec" type="uint8_t">Sec reported by Gps </field>
|
||||
<field name="clockStat" type="uint8_t">Clock Status. See table 47 page 211 OEMStar Manual </field>
|
||||
<field name="visSat" type="uint8_t">Visible satellites reported by Gps </field>
|
||||
<field name="useSat" type="uint8_t">Used satellites in Solution </field>
|
||||
<field name="GppGl" type="uint8_t">GPS+GLONASS satellites in Solution </field>
|
||||
<field name="sigUsedMask" type="uint8_t">GPS and GLONASS usage mask (bit 0 GPS_used? bit_4 GLONASS_used?)</field>
|
||||
<field name="percentUsed" type="uint8_t">Percent used GPS</field>
|
||||
</message>
|
||||
|
||||
<message name="AIR_DATA" id="171">
|
||||
<description>Air data for altitude and airspeed computation.</description>
|
||||
<field name="dynamicPressure" type="float">Dynamic pressure (Pa)</field>
|
||||
<field name="staticPressure" type="float">Static pressure (Pa)</field>
|
||||
<field name="temperature" type="uint16_t">Board temperature</field>
|
||||
</message>
|
||||
|
||||
<message name="SENSOR_BIAS" id="172">
|
||||
<description>Accelerometer and gyro biases.</description>
|
||||
<field name="axBias" type="float">Accelerometer X bias (m/s)</field>
|
||||
<field name="ayBias" type="float">Accelerometer Y bias (m/s)</field>
|
||||
<field name="azBias" type="float">Accelerometer Z bias (m/s)</field>
|
||||
<field name="gxBias" type="float">Gyro X bias (rad/s)</field>
|
||||
<field name="gyBias" type="float">Gyro Y bias (rad/s)</field>
|
||||
<field name="gzBias" type="float">Gyro Z bias (rad/s)</field>
|
||||
</message>
|
||||
|
||||
<message name="DIAGNOSTIC" id="173">
|
||||
<description>Configurable diagnostic messages.</description>
|
||||
<field name="diagFl1" type="float">Diagnostic float 1</field>
|
||||
<field name="diagFl2" type="float">Diagnostic float 2</field>
|
||||
<field name="diagFl3" type="float">Diagnostic float 3</field>
|
||||
<field name="diagSh1" type="int16_t">Diagnostic short 1</field>
|
||||
<field name="diagSh2" type="int16_t">Diagnostic short 2</field>
|
||||
<field name="diagSh3" type="int16_t">Diagnostic short 3</field>
|
||||
</message>
|
||||
|
||||
<message name="SLUGS_NAVIGATION" id="176">
|
||||
<description>Data used in the navigation algorithm.</description>
|
||||
<field name="u_m" type="float">Measured Airspeed prior to the Nav Filter</field>
|
||||
<field name="phi_c" type="float">Commanded Roll</field>
|
||||
<field name="theta_c" type="float">Commanded Pitch</field>
|
||||
<field name="psiDot_c" type="float">Commanded Turn rate</field>
|
||||
<field name="ay_body" type="float">Y component of the body acceleration</field>
|
||||
<field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field>
|
||||
<field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field>
|
||||
<field name="fromWP" type="uint8_t">Origin WP</field>
|
||||
<field name="toWP" type="uint8_t">Destination WP</field>
|
||||
</message>
|
||||
|
||||
<message name="DATA_LOG" id="177">
|
||||
<description>Configurable data log probes to be used inside Simulink.</description>
|
||||
<field name="fl_1" type="float">Log value 1 </field>
|
||||
<field name="fl_2" type="float">Log value 2 </field>
|
||||
<field name="fl_3" type="float">Log value 3 </field>
|
||||
<field name="fl_4" type="float">Log value 4 </field>
|
||||
<field name="fl_5" type="float">Log value 5 </field>
|
||||
<field name="fl_6" type="float">Log value 6 </field>
|
||||
</message>
|
||||
|
||||
<message name="GPS_DATE_TIME" id="179">
|
||||
<description>Pilot console PWM messges.</description>
|
||||
<field name="year" type="uint8_t">Year reported by Gps </field>
|
||||
<field name="month" type="uint8_t">Month reported by Gps </field>
|
||||
<field name="day" type="uint8_t">Day reported by Gps </field>
|
||||
<field name="hour" type="uint8_t">Hour reported by Gps </field>
|
||||
<field name="min" type="uint8_t">Min reported by Gps </field>
|
||||
<field name="sec" type="uint8_t">Sec reported by Gps </field>
|
||||
<field name="visSat" type="uint8_t">Visible sattelites reported by Gps </field>
|
||||
</message>
|
||||
|
||||
<message name="MID_LVL_CMDS" id="180">
|
||||
<description>Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX.</description>
|
||||
<field name="target" type="uint8_t">The system setting the commands</field>
|
||||
<field name="hCommand" type="float">Commanded Airspeed</field>
|
||||
<field name="uCommand" type="float">Log value 2 </field>
|
||||
<field name="rCommand" type="float">Log value 3 </field>
|
||||
</message>
|
||||
|
||||
|
||||
<message name="CTRL_SRFC_PT" id="181">
|
||||
<description>This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows:
|
||||
Position Bit Code
|
||||
=================================
|
||||
15-8 Reserved
|
||||
7 dt_pass 128
|
||||
6 dla_pass 64
|
||||
5 dra_pass 32
|
||||
4 dr_pass 16
|
||||
3 dle_pass 8
|
||||
2 dre_pass 4
|
||||
1 dlf_pass 2
|
||||
0 drf_pass 1
|
||||
Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface.</description>
|
||||
<field name="target" type="uint8_t">The system setting the commands</field>
|
||||
<field name="bitfieldPt" type="uint16_t">Bitfield containing the PT configuration</field>
|
||||
</message>
|
||||
|
||||
|
||||
|
||||
<message name="SLUGS_ACTION" id="183">
|
||||
<description>Action messages focused on the SLUGS AP. </description>
|
||||
<field name="target" type="uint8_t">The system reporting the action</field>
|
||||
<field name="actionId" type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field>
|
||||
<field name="actionVal" type="uint16_t">Value associated with the action</field>
|
||||
</message>
|
||||
|
||||
</messages>
|
||||
<message name="MID_LVL_CMDS" id="180">
|
||||
<description>Mid Level commands sent from the GS to the autopilot. These are only sent when being operated in mid-level commands mode from the ground.</description>
|
||||
<field name="target" type="uint8_t">The system setting the commands</field>
|
||||
<field name="hCommand" type="float">Commanded Altitude in meters</field>
|
||||
<field name="uCommand" type="float">Commanded Airspeed in m/s</field>
|
||||
<field name="rCommand" type="float">Commanded Turnrate in rad/s</field>
|
||||
</message>
|
||||
|
||||
<message name="CTRL_SRFC_PT" id="181">
|
||||
<description>This message sets the control surfaces for selective passthrough mode.</description>
|
||||
<field name="target" type="uint8_t">The system setting the commands</field>
|
||||
<field name="bitfieldPt" type="uint16_t">Bitfield containing the passthrough configuration, see CONTROL_SURFACE_FLAG ENUM.</field>
|
||||
</message>
|
||||
|
||||
<message name="SLUGS_CAMERA_ORDER" id="184">
|
||||
<description>Orders generated to the SLUGS camera mount. </description>
|
||||
<field name="target" type="uint8_t">The system reporting the action</field>
|
||||
<field name="pan" type="int8_t">Order the mount to pan: -1 left, 0 No pan motion, +1 right</field>
|
||||
<field name="tilt" type="int8_t">Order the mount to tilt: -1 down, 0 No tilt motion, +1 up</field>
|
||||
<field name="zoom" type="int8_t">Order the zoom values 0 to 10</field>
|
||||
<field name="moveHome" type="int8_t">Orders the camera mount to move home. The other fields are ignored when this field is set. 1: move home, 0 ignored</field>
|
||||
</message>
|
||||
|
||||
<message name="CONTROL_SURFACE" id="185">
|
||||
<description>Control for surface; pending and order to origin.</description>
|
||||
<field name="target" type="uint8_t">The system setting the commands</field>
|
||||
<field name="idSurface" type="uint8_t">ID control surface send 0: throttle 1: aileron 2: elevator 3: rudder</field>
|
||||
<field name="mControl" type="float">Pending</field>
|
||||
<field name="bControl" type="float">Order to origin</field>
|
||||
</message>
|
||||
|
||||
<!-- Moved into MAV_CMD_RETURN_TO_BASE -->
|
||||
<!--
|
||||
<message name="SLUGS_RTB" id="187">
|
||||
<description>Orders SLUGS to RTB. It also decides to either track a mobile or RTB </description>
|
||||
<field name="target" type="uint8_t">The system ordered to RTB</field>
|
||||
<field name="rtb" type="uint8_t">Order SLUGS to: 0: Stop RTB and resume flight; 1: RTB</field>
|
||||
<field name="track_mobile" type="uint8_t">Order SLUGS to: 0: RTB to GS Location; 1: Track mobile </field>
|
||||
</message>
|
||||
-->
|
||||
|
||||
<message name="SLUGS_MOBILE_LOCATION" id="186">
|
||||
<description>Transmits the last known position of the mobile GS to the UAV. Very relevant when Track Mobile is enabled</description>
|
||||
<field name="target" type="uint8_t">The system reporting the action</field>
|
||||
<field name="latitude" type="float">Mobile Latitude</field>
|
||||
<field name="longitude" type="float">Mobile Longitude</field>
|
||||
</message>
|
||||
|
||||
<message name="SLUGS_CONFIGURATION_CAMERA" id="188">
|
||||
<description>Control for camara.</description>
|
||||
<field name="target" type="uint8_t">The system setting the commands</field>
|
||||
<field name="idOrder" type="uint8_t">ID 0: brightness 1: aperture 2: iris 3: ICR 4: backlight</field>
|
||||
<field name="order" type="uint8_t"> 1: up/on 2: down/off 3: auto/reset/no action</field>
|
||||
</message>
|
||||
|
||||
<message name="ISR_LOCATION" id="189">
|
||||
<description>Transmits the position of watch</description>
|
||||
<field name="target" type="uint8_t">The system reporting the action</field>
|
||||
<field name="latitude" type="float">ISR Latitude</field>
|
||||
<field name="longitude" type="float">ISR Longitude</field>
|
||||
<field name="height" type="float">ISR Height</field>
|
||||
<field name="option1" type="uint8_t">Option 1</field>
|
||||
<field name="option2" type="uint8_t">Option 2</field>
|
||||
<field name="option3" type="uint8_t">Option 3</field>
|
||||
</message>
|
||||
|
||||
<!-- Removed to MAV_CMD_TURN_LIGHT -->
|
||||
<!--
|
||||
<message name="TURN_LIGHT" id="190">
|
||||
<description>Transmits the order to turn on lights</description>
|
||||
<field name="target" type="uint8_t">The system ordered to turn on lights</field>
|
||||
<field name="type" type="uint8_t">Type lights 0: Visible; 1: Infrared</field>
|
||||
<field name="turn" type="uint8_t">Order turn on lights 1: Turn on; 0: Turn off</field>
|
||||
</message>
|
||||
-->
|
||||
|
||||
<message name="VOLT_SENSOR" id="191">
|
||||
<description>Transmits the readings from the voltage and current sensors</description>
|
||||
<field name="r2Type" type="uint8_t">It is the value of reading 2: 0 - Current, 1 - Foreward Sonar, 2 - Back Sonar, 3 - RPM</field>
|
||||
<field name="voltage" type="uint16_t">Voltage in uS of PWM. 0 uS = 0V, 20 uS = 21.5V </field>
|
||||
<field name="reading2" type="uint16_t">Depends on the value of r2Type (0) Current consumption in uS of PWM, 20 uS = 90Amp (1) Distance in cm (2) Distance in cm (3) Absolute value</field>
|
||||
</message>
|
||||
|
||||
<message name="PTZ_STATUS" id="192">
|
||||
<description>Transmits the actual Pan, Tilt and Zoom values of the camera unit</description>
|
||||
<field name="zoom" type="uint8_t">The actual Zoom Value</field>
|
||||
<field name="pan" type="int16_t">The Pan value in 10ths of degree</field>
|
||||
<field name="tilt" type="int16_t">The Tilt value in 10ths of degree</field>
|
||||
</message>
|
||||
|
||||
<message name="UAV_STATUS" id="193">
|
||||
<description>Transmits the actual status values UAV in flight</description>
|
||||
<field name="target" type="uint8_t">The ID system reporting the action</field>
|
||||
<field name="latitude" type="float">Latitude UAV</field>
|
||||
<field name="longitude" type="float">Longitude UAV</field>
|
||||
<field name="altitude" type="float">Altitude UAV</field>
|
||||
<field name="speed" type="float">Speed UAV</field>
|
||||
<field name="course" type="float">Course UAV</field>
|
||||
</message>
|
||||
|
||||
<message name="STATUS_GPS" id="194">
|
||||
<description>This contains the status of the GPS readings</description>
|
||||
<field name="csFails" type="uint16_t">Number of times checksum has failed</field>
|
||||
<field name="gpsQuality" type="uint8_t">The quality indicator, 0=fix not available or invalid, 1=GPS fix, 2=C/A differential GPS, 6=Dead reckoning mode, 7=Manual input mode (fixed position), 8=Simulator mode, 9= WAAS a</field>
|
||||
<field name="msgsType" type="uint8_t"> Indicates if GN, GL or GP messages are being received</field>
|
||||
<field name="posStatus" type="uint8_t"> A = data valid, V = data invalid</field>
|
||||
<field name="magVar" type="float">Magnetic variation, degrees </field>
|
||||
<field name="magDir" type="int8_t"> Magnetic variation direction E/W. Easterly variation (E) subtracts from True course and Westerly variation (W) adds to True course</field>
|
||||
<field name="modeInd" type="uint8_t"> Positioning system mode indicator. A - Autonomous;D-Differential; E-Estimated (dead reckoning) mode;M-Manual input; N-Data not valid</field>
|
||||
</message>
|
||||
|
||||
<message name="NOVATEL_DIAG" id="195">
|
||||
<description>Transmits the diagnostics data from the Novatel OEMStar GPS</description>
|
||||
<field name="timeStatus" type="uint8_t">The Time Status. See Table 8 page 27 Novatel OEMStar Manual</field>
|
||||
<field name="receiverStatus" type="uint32_t">Status Bitfield. See table 69 page 350 Novatel OEMstar Manual</field>
|
||||
<field name="solStatus" type="uint8_t">solution Status. See table 44 page 197</field>
|
||||
<field name="posType" type="uint8_t">position type. See table 43 page 196</field>
|
||||
<field name="velType" type="uint8_t">velocity type. See table 43 page 196</field>
|
||||
<field name="posSolAge" type="float">Age of the position solution in seconds</field>
|
||||
<field name="csFails" type="uint16_t">Times the CRC has failed since boot</field>
|
||||
</message>
|
||||
|
||||
<message name="SENSOR_DIAG" id="196">
|
||||
<description>Diagnostic data Sensor MCU</description>
|
||||
<field name="float1" type="float">Float field 1</field>
|
||||
<field name="float2" type="float">Float field 2</field>
|
||||
<field name="int1" type="int16_t">Int 16 field 1</field>
|
||||
<field name="char1" type="int8_t">Int 8 field 1</field>
|
||||
</message>
|
||||
|
||||
|
||||
<message id="197" name="BOOT">
|
||||
<description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions. This message allows the sensor and control MCUs to communicate version numbers on startup.</description>
|
||||
<field type="uint32_t" name="version">The onboard software version</field>
|
||||
</message>
|
||||
</messages>
|
||||
</mavlink>
|
||||
|
Loading…
Reference in New Issue
Block a user