From 91623322f98adca451c820774749a3e392794cc4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 11 Sep 2015 17:51:06 +1000 Subject: [PATCH] GCS_MAVLink: added SCALED_PRESSURE3 --- libraries/GCS_MAVLink/message_definitions/common.xml | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 6a970592bc..fc6e28ac51 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -2631,6 +2631,13 @@ 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. + + Barometer readings for 3rd barometer + Timestamp (milliseconds since system boot) + Absolute pressure (hectopascal) + Differential pressure 1 (hectopascal) + Temperature measurement (0.01 degrees celsius) + Battery information Battery ID