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