From 0026b56f0ad7bb08307c835d7dc460103b0d6544 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 8 Dec 2015 13:34:20 -0800 Subject: [PATCH] GCS_MAVLink: updated adsb mavlink msg - remove floats - convert altitude from float m/s to int32 mm/s - convert velocities from float m/s to uint16 cm/s --- libraries/GCS_MAVLink/message_definitions/common.xml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index 66c5046481..ad2874ddfb 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -1585,8 +1585,8 @@ - - + + @@ -2780,10 +2780,10 @@ Latitude, expressed as degrees * 1E7 Longitude, expressed as degrees * 1E7 Type from ADSB_ALTITUDE_TYPE enum - Altitude(ASL) in meters + Altitude(ASL) in millimeters Course over ground in centidegrees - The horizontal velocity in meters/second - The vertical velocity in meters/second, positive is up + The horizontal velocity in centimeters/second + The vertical velocity in centimeters/second, positive is up The callsign, 8+null Type from ADSB_EMITTER_TYPE enum Time since last communication in seconds