From 5e496e27fa8108b669cb435d4472823cd7b7a711 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 26 Jul 2025 08:52:11 +1000 Subject: [PATCH] common: added options for hover vs loiter for DO_REPOSITION this gives the GCS operator the choice of asking the aircraft to either enter a hover or a fixed wing loiter at the target location. In ArduPilot this is controlled at the moment using the Q_GUIDED_MODE parameter, but it will be much better to be able to control this using a UI element in the FlyTo dialog. Note: this also brings in the yaw option from upstream --- message_definitions/v1.0/common.xml | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 8037468c9a0..c200a2d0b42 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -3047,6 +3047,15 @@ The aircraft should immediately transition into guided. This should not be set for follow me applications + + Yaw relative to the vehicle current heading (if not set, relative to North). + + + If capable, the aircraft should enter a VTOL hover at the target position + + + If capable, the aircraft should enter a fixed wing loiter at the target position + Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED