diff --git a/message_definitions/v1.0/ardupilotmega.xml b/message_definitions/v1.0/ardupilotmega.xml index 320a578..e04c0b1 100644 --- a/message_definitions/v1.0/ardupilotmega.xml +++ b/message_definitions/v1.0/ardupilotmega.xml @@ -27,6 +27,28 @@ Empty + + Enable/disable autotune + enable (1: enable, 0:disable) + Empty + Empty + Empty + Empty + Empty + Empty + + + + Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. + altitude (m) + descent speed (m/s) + Wiggle Time (s) + Empty + Empty + Empty + Empty + + A system wide power-off event has been initiated. Empty @@ -78,7 +100,7 @@ Automatically retry on failure (0=no retry, 1=retry). Save without user input (0=require input, 1=autosave). Delay (seconds) - Empty + Autoreboot (0=user reboot, 1=autoreboot) Empty Empty @@ -301,19 +323,23 @@ - + + Shooting photos, not video + + + Shooting video, not stills - + Unable to achieve requested exposure (e.g. shutter speed too low) - + Closed loop feedback from camera, we know for sure it has successfully taken a picture - + Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture @@ -974,6 +1000,14 @@ + + + + + + + + @@ -983,12 +1017,6 @@ - - - - - - Special ACK block numbers control activation of dataflash log streaming @@ -1527,15 +1555,10 @@ - - Accuracy statistics for GPS lock - Which instance of GPS we're reporting on - GPS-reported horizontal accuracy - GPS-reported speed accuracy - GPS-reported, filtered horizontal velocity - GPS-reported, filtered vertical velocity - GPS position drift - Which fields pass EKF checks + + RPM sensor output + RPM Sensor1 + RPM Sensor2