From b227f8463f54ad279dbd88d93f036678ad4c3308 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 11 Feb 2015 20:13:27 +1100 Subject: [PATCH] GCS_MAVLink: merge upstream mavlink changes --- .../message_definitions/ASLUAV.xml | 26 +++++++++++ .../message_definitions/ardupilotmega.xml | 6 +-- .../message_definitions/common.xml | 46 ++++++++++++++----- 3 files changed, 64 insertions(+), 14 deletions(-) diff --git a/libraries/GCS_MAVLink/message_definitions/ASLUAV.xml b/libraries/GCS_MAVLink/message_definitions/ASLUAV.xml index 012385fd4d..5cf9450269 100644 --- a/libraries/GCS_MAVLink/message_definitions/ASLUAV.xml +++ b/libraries/GCS_MAVLink/message_definitions/ASLUAV.xml @@ -77,5 +77,31 @@ Motor RPM + + Extended EKF state estimates for ASLUAVs + Time since system start [us] + Magnitude of wind velocity (in lateral inertial plane) [m/s] + Wind heading angle from North [rad] + Z (Down) component of inertial wind velocity [m/s] + Magnitude of air velocity [m/s] + Sideslip angle [rad] + Angle of attack [rad] + + + Off-board controls/commands for ASLUAVs + Time since system start [us] + Elevator command [~] + Throttle command [~] + Throttle 2 command [~] + Left aileron command [~] + Right aileron command [~] + Rudder command [~] + Off-board computer status + + + Atmospheric sensors (temperature, humidity, ...) + Ambient temperature [degrees Celsius] + Relative humidity [%] + diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml index 46e307c67a..b31061c74d 100644 --- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -478,7 +478,7 @@ test variable3 test variable4 - + Request the autopilot version from the system/component. System ID @@ -486,7 +486,7 @@ - Report from MAVLink enabled gimbal to vehicle + Report from MAVLink enabled gimbal to vehicle. The deltas are in gimbal sensor frame. Joint measurements assume a 312 ordering (azimuth, roll, pitch). System ID Component ID Time since last update (seconds) @@ -502,7 +502,7 @@ - Control packet from vehicle to MAVLink enabled gimbal + Control packet from vehicle to MAVLink enabled gimbal. All values in gimbal sensor frame System ID Component ID Demanded angular rate X, radians/s diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 4647268906..ef6e25ab19 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -1411,6 +1411,9 @@ Autopilot supports terrain protocol / data handling. + + Autopilot supports direct actuator control. + Enumeration of estimator types @@ -2280,17 +2283,16 @@ True velocity in m/s in DOWN direction in earth-fixed NED frame - - Status generated by radio - local signal strength - remote signal strength - how full the tx buffer is as a percentage - background noise level - remote background noise level - receive errors - count of error corrected packets - - + + Status generated by radio and injected into MAVLink stream. + Local signal strength + Remote signal strength + Remaining free buffer space in percent. + Background noise level + Remote background noise level + Receive errors + Count of error corrected packets + File transfer message Network ID (0 for broadcast) @@ -2536,6 +2538,28 @@ Differential pressure 1 (hectopascal) Temperature measurement (0.01 degrees celsius) + + Motion capture attitude and position + Timestamp (micros since boot or Unix epoch) + Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) + X position in meters (NED) + Y position in meters (NED) + Z position in meters (NED) + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + System ID + Component ID + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + + + Set the vehicle attitude and body angular rates. + Timestamp (micros since boot or Unix epoch) + Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances. + Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs. + Battery information Battery ID