From d5ced15acfa4a2ff344d1b9aa365b5eaa1621edf Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 25 Nov 2014 09:08:51 +1100 Subject: [PATCH] GCS_MAVLink: include units in CONTINUE_AND_CHANGE_ALT --- libraries/GCS_MAVLink/message_definitions/common.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml index b7a5e168c6..f168c8ccd8 100644 --- a/libraries/GCS_MAVLink/message_definitions/common.xml +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -580,14 +580,14 @@ Altitude - Continue on the current course and climb/descend to specified altitude. When the altitude is reached, the intended behavior is to continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. + Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. Empty Empty Empty Empty Empty Empty - Desired altitude. + Desired altitude in meters Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.