From 6564fcc8d560dea03daec3463ccb0c87932a912b Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Fri, 24 Nov 2023 08:36:15 +1100 Subject: [PATCH] MAV_CMD_CONDITION_YAW - shortest direction v2 (#2058) * MAV_CMD_CONDITION_YAW - shortest direction v2 * Update message_definitions/v1.0/common.xml * Update message_definitions/v1.0/common.xml --- message_definitions/v1.0/common.xml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml index 464a24d2b6..2e0fefc6f0 100644 --- a/message_definitions/v1.0/common.xml +++ b/message_definitions/v1.0/common.xml @@ -1003,9 +1003,9 @@ Reach a certain target angle. - target angle, 0 is north - angular speed - direction: -1: counter clockwise, 1: clockwise + target angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3. + angular speed + direction: -1: counter clockwise, 0: shortest direction, 1: clockwise 0: absolute angle, 1: relative offset Empty Empty