diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml index 04aae0a7d0..2f4cd6ca5a 100644 --- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -13,6 +13,16 @@ + + Pass control to an external controller. + Timeout in seconds. The maximum amount of time that the external controller will be allowed to control the vehicle. 0 means no timeout + Altitude min. If vehicle moves below this altitude the command will be aborted and the mission will continue. 0 for no lower alt limit + Altitude max. If vehicle moves above this altitude the command will be aborted and the mission will continue. 0 for no upper alt limit + Horizontal move limit. If vehicle moves more than this distance from it's location at the moment the command was begun, the command will be aborted and the mission will continue. 0 for no horizontal movement limit + Empty + Empty + Empty + Mission command to perform motor test motor sequence number (a number from 1 to max number of motors on the vehicle)