diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml
index 1b7253caa5..b7a5e168c6 100644
--- a/libraries/GCS_MAVLink/message_definitions/common.xml
+++ b/libraries/GCS_MAVLink/message_definitions/common.xml
@@ -578,6 +578,16 @@
Latitude
Longitude
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.
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Desired altitude.
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.