From 3ef44459c8f26f580742c137b0794e0ed74d9140 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 13 Jun 2015 18:40:15 +1000 Subject: [PATCH] GCS_MAVLink: added ALTITUDE_WAIT message --- .../message_definitions/ardupilotmega.xml | 22 +++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml index 8715c9bfe5..4bb87a5b86 100644 --- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -33,6 +33,28 @@ Empty Empty + + + Enable/disable autotune + enable (1: enable, 0:disable) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. + altitude (m) + descent speed (m/s) + Wiggle Time (s) + Empty + Empty + Empty + Empty +