From af93c8da4eeb15a2b9498c95c2c2456c0c9a6ad5 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 18 Nov 2015 16:57:50 -0800 Subject: [PATCH] GCS_MAVLink: new mavlink msg ADSB_VEHICLE --- .../message_definitions/common.xml | 62 +++++++++++++++++++ 1 file changed, 62 insertions(+) diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index a31ac1251b..c2106f69a0 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -142,6 +142,9 @@ Onboard gimbal + + Onboard ADSB peripheral + These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65. @@ -376,6 +379,9 @@ + + + These encode the sensors whose status is sent as part of the SYS_STATUS message. @@ -1537,6 +1543,47 @@ Payload battery + + Enumeration of the ADSB altimeter types + + Altitude reported from a Baro source using QNH reference + + + Altitude reported from a GNSS source + + + + ADSB classification for the type of vehicle emitting the transponder signal + + + + + + + + + + + + + + + + + + + + + + + These flags indicate status such as data validity of each data source. Set = data valid + + + + + + + @@ -2723,6 +2770,21 @@ Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone. + + The location and information of an ADSB vehicle + ICAO address + The reported latitude in degrees + The reported longitude in degrees + Type from ADSB_ALTITUDE_TYPE enum. + Altitude(ASL) in meters + Course over ground in degrees * 10^2 + The horizontal velocity in meters/second + The vertical velocity in meters/second, positive is up + The callsign(squawk) + Type from ADSB_EMITTER_TYPE enum + Time since last communication in seconds + Flags to indicate various statuses including valid data fields + Message implementing parts of the V2 payload specs in V1 frames for transitional support. Network ID (0 for broadcast)