diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
index 036d294f82..e04c0b1443 100644
--- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
+++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
@@ -49,6 +49,51 @@
Empty
+
+ A system wide power-off event has been initiated.
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+
+
+
+
+ FLY button has been clicked.
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+
+
+
+ FLY button has been held for 1.5 seconds.
+ Takeoff altitude
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+
+
+
+ PAUSE button has been clicked.
+ 1 if Solo is in a shot mode, 0 otherwise
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+
+
Initiate a magnetometer calibration
uint8_t bitmask of magnetometers (0 means all)
@@ -92,6 +137,61 @@
Empty
Empty
+
+
+ Causes the gimbal to reset and boot as if it was just powered on
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+
+
+
+ Command autopilot to get into factory test/diagnostic mode
+ 0 means get out of test mode, 1 means get into test mode
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+
+
+
+ Reports progress and success or failure of gimbal axis calibration procedure
+ Gimbal axis we're reporting calibration progress for
+ Current calibration progress for this axis, 0x64=100%
+ Status of the calibration
+ Empty
+ Empty
+ Empty
+ Empty
+
+
+
+ Starts commutation calibration on the gimbal
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+ Empty
+
+
+
+ Erases gimbal application and parameters
+ Magic number
+ Magic number
+ Magic number
+ Magic number
+ Magic number
+ Magic number
+ Magic number
+
@@ -244,6 +344,603 @@
+
+
+
+ Gimbal is powered on but has not started initializing yet
+
+
+
+ Gimbal is currently running calibration on the pitch axis
+
+
+
+ Gimbal is currently running calibration on the roll axis
+
+
+
+ Gimbal is currently running calibration on the yaw axis
+
+
+
+ Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter
+
+
+
+ Gimbal is actively stabilizing
+
+
+
+ Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command
+
+
+
+
+
+ Gimbal yaw axis
+
+
+
+ Gimbal pitch axis
+
+
+
+ Gimbal roll axis
+
+
+
+
+
+ Axis calibration is in progress
+
+
+
+ Axis calibration succeeded
+
+
+
+ Axis calibration failed
+
+
+
+
+
+ Whether or not this axis requires calibration is unknown at this time
+
+
+
+ This axis requires calibration
+
+
+
+ This axis does not require calibration
+
+
+
+
+
+
+ No GoPro connected
+
+
+
+ The detected GoPro is not HeroBus compatible
+
+
+
+ A HeroBus compatible GoPro is connected
+
+
+
+ An unrecoverable error was encountered with the connected GoPro, it may require a power cycle
+
+
+
+
+
+
+ GoPro is currently recording
+
+
+
+
+
+ The write message with ID indicated succeeded
+
+
+
+ The write message with ID indicated failed
+
+
+
+
+
+ (Get/Set)
+
+
+
+ (Get/Set)
+
+
+
+ (___/Set)
+
+
+
+ (Get/___)
+
+
+
+ (Get/___)
+
+
+
+ (Get/Set)
+
+
+
+
+ (Get/Set)
+
+
+
+ (Get/Set)
+
+
+
+ (Get/Set)
+
+
+
+ (Get/Set)
+
+
+
+ (Get/Set) Hero 3+ Only
+
+
+
+ (Get/Set) Hero 3+ Only
+
+
+
+ (Get/Set) Hero 3+ Only
+
+
+
+ (Get/Set) Hero 3+ Only
+
+
+
+ (Get/Set) Hero 3+ Only
+
+
+
+ (Get/Set)
+
+
+
+
+ (Get/Set)
+
+
+
+
+
+ Video mode
+
+
+
+ Photo mode
+
+
+
+ Burst mode, hero 3+ only
+
+
+
+ Time lapse mode, hero 3+ only
+
+
+
+ Multi shot mode, hero 4 only
+
+
+
+ Playback mode, hero 4 only, silver only except when LCD or HDMI is connected to black
+
+
+
+ Playback mode, hero 4 only
+
+
+
+ Mode not yet known
+
+
+
+
+
+ 848 x 480 (480p)
+
+
+
+ 1280 x 720 (720p)
+
+
+
+ 1280 x 960 (960p)
+
+
+
+ 1920 x 1080 (1080p)
+
+
+
+ 1920 x 1440 (1440p)
+
+
+
+ 2704 x 1440 (2.7k-17:9)
+
+
+
+ 2704 x 1524 (2.7k-16:9)
+
+
+
+ 2704 x 2028 (2.7k-4:3)
+
+
+
+ 3840 x 2160 (4k-16:9)
+
+
+
+ 4096 x 2160 (4k-17:9)
+
+
+
+ 1280 x 720 (720p-SuperView)
+
+
+
+ 1920 x 1080 (1080p-SuperView)
+
+
+
+ 2704 x 1520 (2.7k-SuperView)
+
+
+
+ 3840 x 2160 (4k-SuperView)
+
+
+
+
+
+ 12 FPS
+
+
+
+ 15 FPS
+
+
+
+ 24 FPS
+
+
+
+ 25 FPS
+
+
+
+ 30 FPS
+
+
+
+ 48 FPS
+
+
+
+ 50 FPS
+
+
+
+ 60 FPS
+
+
+
+ 80 FPS
+
+
+
+ 90 FPS
+
+
+
+ 100 FPS
+
+
+
+ 120 FPS
+
+
+
+ 240 FPS
+
+
+
+ 12.5 FPS
+
+
+
+
+
+ 0x00: Wide
+
+
+
+ 0x01: Medium
+
+
+
+ 0x02: Narrow
+
+
+
+
+
+ 0=NTSC, 1=PAL
+
+
+
+
+
+ 5MP Medium
+
+
+
+ 7MP Medium
+
+
+
+ 7MP Wide
+
+
+
+ 10MP Wide
+
+
+
+ 12MP Wide
+
+
+
+
+
+ Auto
+
+
+
+ 3000K
+
+
+
+ 5500K
+
+
+
+ 6500K
+
+
+
+ Camera Raw
+
+
+
+
+
+ Auto
+
+
+
+ Neutral
+
+
+
+
+
+ ISO 400
+
+
+
+ ISO 800 (Only Hero 4)
+
+
+
+ ISO 1600
+
+
+
+ ISO 3200 (Only Hero 4)
+
+
+
+ ISO 6400
+
+
+
+
+
+ Low Sharpness
+
+
+
+ Medium Sharpness
+
+
+
+ High Sharpness
+
+
+
+
+
+ -5.0 EV (Hero 3+ Only)
+
+
+
+ -4.5 EV (Hero 3+ Only)
+
+
+
+ -4.0 EV (Hero 3+ Only)
+
+
+
+ -3.5 EV (Hero 3+ Only)
+
+
+
+ -3.0 EV (Hero 3+ Only)
+
+
+
+ -2.5 EV (Hero 3+ Only)
+
+
+
+ -2.0 EV
+
+
+
+ -1.5 EV
+
+
+
+ -1.0 EV
+
+
+
+ -0.5 EV
+
+
+
+ 0.0 EV
+
+
+
+ +0.5 EV
+
+
+
+ +1.0 EV
+
+
+
+ +1.5 EV
+
+
+
+ +2.0 EV
+
+
+
+ +2.5 EV (Hero 3+ Only)
+
+
+
+ +3.0 EV (Hero 3+ Only)
+
+
+
+ +3.5 EV (Hero 3+ Only)
+
+
+
+ +4.0 EV (Hero 3+ Only)
+
+
+
+ +4.5 EV (Hero 3+ Only)
+
+
+
+ +5.0 EV (Hero 3+ Only)
+
+
+
+
+
+ Charging disabled
+
+
+
+ Charging enabled
+
+
+
+
+
+ Unknown gopro model
+
+
+
+ Hero 3+ Silver (HeroBus not supported by GoPro)
+
+
+
+ Hero 3+ Black
+
+
+
+ Hero 4 Silver
+
+
+
+ Hero 4 Black
+
+
+
+
+
+ 3 Shots / 1 Second
+
+
+
+ 5 Shots / 1 Second
+
+
+
+ 10 Shots / 1 Second
+
+
+
+ 10 Shots / 2 Second
+
+
+
+ 10 Shots / 3 Second (Hero 4 Only)
+
+
+
+ 30 Shots / 1 Second
+
+
+
+ 30 Shots / 2 Second
+
+
+
+ 30 Shots / 3 Second
+
+
+
+ 30 Shots / 6 Second
+
+
+
@@ -786,8 +1483,78 @@
D component
-
+
+ 3 axis gimbal mesuraments
+ System ID
+ Component ID
+ Time since last update (seconds)
+ Delta angle X (radians)
+ Delta angle Y (radians)
+ Delta angle X (radians)
+ Delta velocity X (m/s)
+ Delta velocity Y (m/s)
+ Delta velocity Z (m/s)
+ Joint ROLL (radians)
+ Joint EL (radians)
+ Joint AZ (radians)
+
+
+ Control message for rate gimbal
+ System ID
+ Component ID
+ Demanded angular rate X (rad/s)
+ Demanded angular rate Y (rad/s)
+ Demanded angular rate Z (rad/s)
+
+
+
+ 100 Hz gimbal torque command telemetry
+ System ID
+ Component ID
+ Roll Torque Command
+ Elevation Torque Command
+ Azimuth Torque Command
+
+
+
+
+ Heartbeat from a HeroBus attached GoPro
+ Status
+ Current capture mode
+ additional status bits
+
+
+
+
+ Request a GOPRO_COMMAND response from the GoPro
+ System ID
+ Component ID
+ Command ID
+
+
+
+ Response from a GOPRO_COMMAND get request
+ Command ID
+ Status
+ Value
+
+
+
+ Request to set a GOPRO_COMMAND with a desired
+ System ID
+ Component ID
+ Command ID
+ Value
+
+
+
+ Response from a GOPRO_COMMAND set request
+ Command ID
+ Status
+
+
+
RPM sensor output
RPM Sensor1