diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h
index ad72d50f4a..2124571911 100644
--- a/libraries/GCS_MAVLink/GCS.h
+++ b/libraries/GCS_MAVLink/GCS.h
@@ -58,6 +58,7 @@ enum ap_message {
MSG_GIMBAL_REPORT,
MSG_EKF_STATUS_REPORT,
MSG_LOCAL_POSITION,
+ MSG_PID_TUNING,
MSG_RETRY_DEFERRED // this must be last
};
diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
index fef192082f..043a3c7697 100644
--- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
+++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
@@ -258,6 +258,12 @@
set if EKF's predicted horizontal position (absolute) estimate is good
+
+
+
+
+
+
@@ -651,6 +657,18 @@
Terrain Altitude variance
+
+
+ PID tuning information
+ axis
+ desired rate (degrees/s)
+ achieved rate (degrees/s)
+ FF component
+ P component
+ I component
+ D component
+
+
3 axis gimbal mesuraments
System ID