diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml
index 7f35f074b9..f5e917c99d 100644
--- a/libraries/GCS_MAVLink/message_definitions/common.xml
+++ b/libraries/GCS_MAVLink/message_definitions/common.xml
@@ -599,7 +599,7 @@
Latitude
Longitude
Altitude
-
+
Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached.
Empty
@@ -609,6 +609,16 @@
Empty
Empty
Desired altitude in meters
+
+
+ Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint.
+ Heading Required (0 = False)
+ Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.
+ Empty
+ Empty
+ Latitude
+ Longitude
+ 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.