Dialect: ArduPilotMega
These messages define the ArduPilot specific message set, which is custom to http://ardupilot.org.
This topic is a human-readable form of the XML definition file: ardupilotmega.xml.
The ArduPilot MAVLink fork of ardupilotmega.xml may contain messages that have not yet been merged into this documentation.
MAVLink 2 messages have an ID > 255 and are marked up using (MAVLink 2) in their description.
MAVLink 2 extension fields that have been added to MAVLink 1 messages are displayed in blue.
MAVLink Include Files: common.xml
MAVLink Include Files: uAvionix.xml
MAVLink Include Files: icarous.xml
This file has protocol dialect: 2.
MAVLink Type Enumerations
[Enum]
[Enum]
[Enum]
[Enum] Flags in RALLY_POINT message.
Value | Field Name | Description |
---|
1 | FAVORABLE_WIND | Flag set when requiring favorable winds for landing. |
2 | LAND_IMMEDIATELY | Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. |
[Enum] Gripper actions.
[Enum] Winch actions.
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum]
[Enum] Flags in EKF_STATUS message.
[Enum]
[Enum]
[Enum] Special ACK block numbers control activation of dataflash log streaming.
[Enum] Possible remote log data block statuses.
[Enum] Bus types for device operations.
[Enum] Deepstall flight stage.
[Enum] A mapping of plane flight modes for custom_mode field of heartbeat.
[Enum] A mapping of copter flight modes for custom_mode field of heartbeat.
[Enum] A mapping of sub flight modes for custom_mode field of heartbeat.
[Enum] A mapping of rover flight modes for custom_mode field of heartbeat.
[Enum] A mapping of antenna tracker flight modes for custom_mode field of heartbeat.
MAVLink Commands (MAV_CMD)
MAVLink commands (MAV_CMD) and messages are different! These commands define the values of up to 7 parameters that are packaged INSIDE specific messages used in the Mission Protocol and Command Protocol. Use commands for actions in missions or if you need acknowledgment and/or retry logic from a request. Otherwise use messages.
MAV_CMD_DO_GRIPPER (211 )
[Command] Mission command to operate EPM gripper.
Param (:Label) | Description |
---|
1 | Gripper number (a number from 1 to max number of grippers on the vehicle). |
2 | Gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum). |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_DO_AUTOTUNE_ENABLE (212 )
[Command] Enable/disable autotune.
Param (:Label) | Description |
---|
1 | Enable (1: enable, 0:disable). |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_NAV_ALTITUDE_WAIT (83 )
[Command] 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.
Param (:Label) | Description |
---|
1 | Altitude (m). |
2 | Descent speed (m/s). |
3 | Wiggle Time (s). |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_POWER_OFF_INITIATED (42000 )
[Command] A system wide power-off event has been initiated.
Param (:Label) | Description |
---|
1 | Empty. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_SOLO_BTN_FLY_CLICK (42001 )
[Command] FLY button has been clicked.
Param (:Label) | Description |
---|
1 | Empty. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_SOLO_BTN_FLY_HOLD (42002 )
[Command] FLY button has been held for 1.5 seconds.
Param (:Label) | Description |
---|
1 | Takeoff altitude. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_SOLO_BTN_PAUSE_CLICK (42003 )
[Command] PAUSE button has been clicked.
Param (:Label) | Description |
---|
1 | 1 if Solo is in a shot mode, 0 otherwise. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_FIXED_MAG_CAL (42004 )
[Command] Magnetometer calibration based on fixed position in earth field given by inclination, declination and intensity.
Param (:Label) | Description |
---|
1 | MagDeclinationDegrees. |
2 | MagInclinationDegrees. |
3 | MagIntensityMilliGauss. |
4 | YawDegrees. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_FIXED_MAG_CAL_FIELD (42005 )
[Command] Magnetometer calibration based on fixed expected field values in milliGauss.
Param (:Label) | Description |
---|
1 | FieldX. |
2 | FieldY. |
3 | FieldZ. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_DO_START_MAG_CAL (42424 )
[Command] Initiate a magnetometer calibration.
Param (:Label) | Description |
---|
1 | uint8_t bitmask of magnetometers (0 means all). |
2 | Automatically retry on failure (0=no retry, 1=retry). |
3 | Save without user input (0=require input, 1=autosave). |
4 | Delay (seconds). |
5 | Autoreboot (0=user reboot, 1=autoreboot). |
6 | Empty. |
7 | Empty. |
MAV_CMD_DO_ACCEPT_MAG_CAL (42425 )
[Command] Initiate a magnetometer calibration.
Param (:Label) | Description |
---|
1 | uint8_t bitmask of magnetometers (0 means all). |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_DO_CANCEL_MAG_CAL (42426 )
[Command] Cancel a running magnetometer calibration.
Param (:Label) | Description |
---|
1 | uint8_t bitmask of magnetometers (0 means all). |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_ACCELCAL_VEHICLE_POS (42429 )
[Command] Used when doing accelerometer calibration. When sent to the GCS tells it what position to put the vehicle in. When sent to the vehicle says what position the vehicle is in.
Param (:Label) | Description |
---|
1 | Position, one of the ACCELCAL_VEHICLE_POS enum values. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_DO_SEND_BANNER (42428 )
[Command] Reply with the version banner.
Param (:Label) | Description |
---|
1 | Empty. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_SET_FACTORY_TEST_MODE (42427 )
[Command] Command autopilot to get into factory test/diagnostic mode.
Param (:Label) | Description |
---|
1 | 0 means get out of test mode, 1 means get into test mode. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_GIMBAL_RESET (42501 )
[Command] Causes the gimbal to reset and boot as if it was just powered on.
Param (:Label) | Description |
---|
1 | Empty. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS (42502 )
[Command] Reports progress and success or failure of gimbal axis calibration procedure.
Param (:Label) | Description |
---|
1 | Gimbal axis we're reporting calibration progress for. |
2 | Current calibration progress for this axis, 0x64=100%. |
3 | Status of the calibration. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION (42503 )
[Command] Starts commutation calibration on the gimbal.
Param (:Label) | Description |
---|
1 | Empty. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_GIMBAL_FULL_RESET (42505 )
[Command] Erases gimbal application and parameters.
Param (:Label) | Description |
---|
1 | Magic number. |
2 | Magic number. |
3 | Magic number. |
4 | Magic number. |
5 | Magic number. |
6 | Magic number. |
7 | Magic number. |
MAV_CMD_DO_WINCH (42600 )
[Command] Command to operate winch.
Param (:Label) | Description |
---|
1 | Winch number (0 for the default winch, otherwise a number from 1 to max number of winches on the vehicle). |
2 | Action (0=relax, 1=relative length control, 2=rate control. See WINCH_ACTIONS enum.). |
3 | Release length (cable distance to unwind in meters, negative numbers to wind in cable). |
4 | Release rate (meters/second). |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_FLASH_BOOTLOADER (42650 )
[Command] Update the bootloader
Param (:Label) | Description |
---|
1 | Empty |
2 | Empty |
3 | Empty |
4 | Empty |
5 | Magic number - set to 290876 to actually flash |
6 | Empty |
7 | Empty |
MAVLink Messages
SENSOR_OFFSETS ( #150 )
[Message] Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.
Field Name | Type | Units | Description |
---|
mag_ofs_x | int16_t | | Magnetometer X offset. |
mag_ofs_y | int16_t | | Magnetometer Y offset. |
mag_ofs_z | int16_t | | Magnetometer Z offset. |
mag_declination | float | rad | Magnetic declination. |
raw_press | int32_t | | Raw pressure from barometer. |
raw_temp | int32_t | | Raw temperature from barometer. |
gyro_cal_x | float | | Gyro X calibration. |
gyro_cal_y | float | | Gyro Y calibration. |
gyro_cal_z | float | | Gyro Z calibration. |
accel_cal_x | float | | Accel X calibration. |
accel_cal_y | float | | Accel Y calibration. |
accel_cal_z | float | | Accel Z calibration. |
SET_MAG_OFFSETS ( #151 )
DEPRECATED: Replaced by MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS (2014-07).
[Message] Set the magnetometer offsets
Field Name | Type | Description |
---|
target_system | uint8_t | System ID. |
target_component | uint8_t | Component ID. |
mag_ofs_x | int16_t | Magnetometer X offset. |
mag_ofs_y | int16_t | Magnetometer Y offset. |
mag_ofs_z | int16_t | Magnetometer Z offset. |
MEMINFO ( #152 )
[Message] State of APM memory.
Field Name | Type | Units | Description |
---|
brkval | uint16_t | | Heap top. |
freemem | uint16_t | bytes | Free memory. |
freemem32 ** | uint32_t | bytes | Free memory (32 bit). |
AP_ADC ( #153 )
[Message] Raw ADC output.
Field Name | Type | Description |
---|
adc1 | uint16_t | ADC output 1. |
adc2 | uint16_t | ADC output 2. |
adc3 | uint16_t | ADC output 3. |
adc4 | uint16_t | ADC output 4. |
adc5 | uint16_t | ADC output 5. |
adc6 | uint16_t | ADC output 6. |
[Message] Configure on-board Camera Control System.
Field Name | Type | Units | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
mode | uint8_t | | Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore). |
shutter_speed | uint16_t | | Divisor number //e.g. 1000 means 1/1000 (0 means ignore). |
aperture | uint8_t | | F stop number x 10 //e.g. 28 means 2.8 (0 means ignore). |
iso | uint8_t | | ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore). |
exposure_type | uint8_t | | Exposure type enumeration from 1 to N (0 means ignore). |
command_id | uint8_t | | Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once. |
engine_cut_off | uint8_t | ds | Main engine cut-off time before camera trigger (0 means no cut-off). |
extra_param | uint8_t | | Extra parameters enumeration (0 means ignore). |
extra_value | float | | Correspondent value to given extra_param. |
DIGICAM_CONTROL ( #155 )
[Message] Control on-board Camera Control System to take shots.
Field Name | Type | Description |
---|
target_system | uint8_t | System ID. |
target_component | uint8_t | Component ID. |
session | uint8_t | 0: stop, 1: start or keep it up //Session control e.g. show/hide lens. |
zoom_pos | uint8_t | 1 to N //Zoom's absolute position (0 means ignore). |
zoom_step | int8_t | -100 to 100 //Zooming step value to offset zoom from the current position. |
focus_lock | uint8_t | 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus. |
shot | uint8_t | 0: ignore, 1: shot or start filming. |
command_id | uint8_t | Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once. |
extra_param | uint8_t | Extra parameters enumeration (0 means ignore). |
extra_value | float | Correspondent value to given extra_param. |
[Message] Message to configure a camera mount, directional antenna, etc.
Field Name | Type | Values | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
mount_mode | uint8_t | MAV_MOUNT_MODE | Mount operating mode. |
stab_roll | uint8_t | | (1 = yes, 0 = no). |
stab_pitch | uint8_t | | (1 = yes, 0 = no). |
stab_yaw | uint8_t | | (1 = yes, 0 = no). |
MOUNT_CONTROL ( #157 )
[Message] Message to control a camera mount, directional antenna, etc.
Field Name | Type | Description |
---|
target_system | uint8_t | System ID. |
target_component | uint8_t | Component ID. |
input_a | int32_t | Pitch (centi-degrees) or lat (degE7), depending on mount mode. |
input_b | int32_t | Roll (centi-degrees) or lon (degE7) depending on mount mode. |
input_c | int32_t | Yaw (centi-degrees) or alt (cm) depending on mount mode. |
save_position | uint8_t | If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING). |
MOUNT_STATUS ( #158 )
[Message] Message with some status from APM to GCS about camera or antenna mount.
Field Name | Type | Units | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
pointing_a | int32_t | cdeg | Pitch. |
pointing_b | int32_t | cdeg | Roll. |
pointing_c | int32_t | cdeg | Yaw. |
FENCE_POINT ( #160 )
[Message] A fence point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS.
Field Name | Type | Units | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
idx | uint8_t | | Point index (first point is 1, 0 is for return point). |
count | uint8_t | | Total number of points (for sanity checking). |
lat | float | deg | Latitude of point. |
lng | float | deg | Longitude of point. |
FENCE_FETCH_POINT ( #161 )
[Message] Request a current fence point from MAV.
Field Name | Type | Description |
---|
target_system | uint8_t | System ID. |
target_component | uint8_t | Component ID. |
idx | uint8_t | Point index (first point is 1, 0 is for return point). |
AHRS ( #163 )
[Message] Status of DCM attitude estimator.
Field Name | Type | Units | Description |
---|
omegaIx | float | rad/s | X gyro drift estimate. |
omegaIy | float | rad/s | Y gyro drift estimate. |
omegaIz | float | rad/s | Z gyro drift estimate. |
accel_weight | float | | Average accel_weight. |
renorm_val | float | | Average renormalisation value. |
error_rp | float | | Average error_roll_pitch value. |
error_yaw | float | | Average error_yaw value. |
SIMSTATE ( #164 )
[Message] Status of simulation environment, if used.
Field Name | Type | Units | Description |
---|
roll | float | rad | Roll angle. |
pitch | float | rad | Pitch angle. |
yaw | float | rad | Yaw angle. |
xacc | float | m/s/s | X acceleration. |
yacc | float | m/s/s | Y acceleration. |
zacc | float | m/s/s | Z acceleration. |
xgyro | float | rad/s | Angular speed around X axis. |
ygyro | float | rad/s | Angular speed around Y axis. |
zgyro | float | rad/s | Angular speed around Z axis. |
lat | int32_t | degE7 | Latitude. |
lng | int32_t | degE7 | Longitude. |
HWSTATUS ( #165 )
[Message] Status of key hardware.
Field Name | Type | Units | Description |
---|
Vcc | uint16_t | mV | Board voltage. |
I2Cerr | uint8_t | | I2C error count. |
RADIO ( #166 )
[Message] Status generated by radio.
Field Name | Type | Units | Description |
---|
rssi | uint8_t | | Local signal strength. |
remrssi | uint8_t | | Remote signal strength. |
txbuf | uint8_t | % | How full the tx buffer is. |
noise | uint8_t | | Background noise level. |
remnoise | uint8_t | | Remote background noise level. |
rxerrors | uint16_t | | Receive errors. |
fixed | uint16_t | | Count of error corrected packets. |
LIMITS_STATUS ( #167 )
[Message] Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled.
Field Name | Type | Units | Values | Description |
---|
limits_state | uint8_t | | LIMITS_STATE | State of AP_Limits. |
last_trigger | uint32_t | ms | | Time (since boot) of last breach. |
last_action | uint32_t | ms | | Time (since boot) of last recovery action. |
last_recovery | uint32_t | ms | | Time (since boot) of last successful recovery. |
last_clear | uint32_t | ms | | Time (since boot) of last all-clear. |
breach_count | uint16_t | | | Number of fence breaches. |
mods_enabled | uint8_t | | LIMIT_MODULE | AP_Limit_Module bitfield of enabled modules. |
mods_required | uint8_t | | LIMIT_MODULE | AP_Limit_Module bitfield of required modules. |
mods_triggered | uint8_t | | LIMIT_MODULE | AP_Limit_Module bitfield of triggered modules. |
WIND ( #168 )
[Message] Wind estimation.
Field Name | Type | Units | Description |
---|
direction | float | deg | Wind direction (that wind is coming from). |
speed | float | m/s | Wind speed in ground plane. |
speed_z | float | m/s | Vertical wind speed. |
DATA16 ( #169 )
[Message] Data packet, size 16.
Field Name | Type | Units | Description |
---|
type | uint8_t | | Data type. |
len | uint8_t | bytes | Data length. |
data | uint8_t[16] | | Raw data. |
DATA32 ( #170 )
[Message] Data packet, size 32.
Field Name | Type | Units | Description |
---|
type | uint8_t | | Data type. |
len | uint8_t | bytes | Data length. |
data | uint8_t[32] | | Raw data. |
DATA64 ( #171 )
[Message] Data packet, size 64.
Field Name | Type | Units | Description |
---|
type | uint8_t | | Data type. |
len | uint8_t | bytes | Data length. |
data | uint8_t[64] | | Raw data. |
DATA96 ( #172 )
[Message] Data packet, size 96.
Field Name | Type | Units | Description |
---|
type | uint8_t | | Data type. |
len | uint8_t | bytes | Data length. |
data | uint8_t[96] | | Raw data. |
RANGEFINDER ( #173 )
[Message] Rangefinder reporting.
Field Name | Type | Units | Description |
---|
distance | float | m | Distance. |
voltage | float | V | Raw voltage if available, zero otherwise. |
AIRSPEED_AUTOCAL ( #174 )
[Message] Airspeed auto-calibration.
Field Name | Type | Units | Description |
---|
vx | float | m/s | GPS velocity north. |
vy | float | m/s | GPS velocity east. |
vz | float | m/s | GPS velocity down. |
diff_pressure | float | Pa | Differential pressure. |
EAS2TAS | float | | Estimated to true airspeed ratio. |
ratio | float | | Airspeed ratio. |
state_x | float | | EKF state x. |
state_y | float | | EKF state y. |
state_z | float | | EKF state z. |
Pax | float | | EKF Pax. |
Pby | float | | EKF Pby. |
Pcz | float | | EKF Pcz. |
RALLY_POINT ( #175 )
[Message] A rally point. Used to set a point when from GCS -> MAV. Also used to return a point from MAV -> GCS.
Field Name | Type | Units | Values | Description |
---|
target_system | uint8_t | | | System ID. |
target_component | uint8_t | | | Component ID. |
idx | uint8_t | | | Point index (first point is 0). |
count | uint8_t | | | Total number of points (for sanity checking). |
lat | int32_t | degE7 | | Latitude of point. |
lng | int32_t | degE7 | | Longitude of point. |
alt | int16_t | m | | Transit / loiter altitude relative to home. |
break_alt | int16_t | m | | Break altitude relative to home. |
land_dir | uint16_t | cdeg | | Heading to aim for when landing. |
flags | uint8_t | | RALLY_FLAGS | Configuration flags. |
RALLY_FETCH_POINT ( #176 )
[Message] Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid.
Field Name | Type | Description |
---|
target_system | uint8_t | System ID. |
target_component | uint8_t | Component ID. |
idx | uint8_t | Point index (first point is 0). |
COMPASSMOT_STATUS ( #177 )
[Message] Status of compassmot calibration.
Field Name | Type | Units | Description |
---|
throttle | uint16_t | d% | Throttle. |
current | float | A | Current. |
interference | uint16_t | % | Interference. |
CompensationX | float | | Motor Compensation X. |
CompensationY | float | | Motor Compensation Y. |
CompensationZ | float | | Motor Compensation Z. |
AHRS2 ( #178 )
[Message] Status of secondary AHRS filter if available.
Field Name | Type | Units | Description |
---|
roll | float | rad | Roll angle. |
pitch | float | rad | Pitch angle. |
yaw | float | rad | Yaw angle. |
altitude | float | m | Altitude (MSL). |
lat | int32_t | degE7 | Latitude. |
lng | int32_t | degE7 | Longitude. |
CAMERA_STATUS ( #179 )
[Message] Camera Event.
Field Name | Type | Units | Values | Description |
---|
time_usec | uint64_t | us | | Image timestamp (since UNIX epoch, according to camera clock). |
target_system | uint8_t | | | System ID. |
cam_idx | uint8_t | | | Camera ID. |
img_idx | uint16_t | | | Image index. |
event_id | uint8_t | | CAMERA_STATUS_TYPES | Event type. |
p1 | float | | | Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). |
p2 | float | | | Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). |
p3 | float | | | Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). |
p4 | float | | | Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum). |
CAMERA_FEEDBACK ( #180 )
[Message] Camera Capture Feedback.
Field Name | Type | Units | Values | Description |
---|
time_usec | uint64_t | us | | Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB). |
target_system | uint8_t | | | System ID. |
cam_idx | uint8_t | | | Camera ID. |
img_idx | uint16_t | | | Image index. |
lat | int32_t | degE7 | | Latitude. |
lng | int32_t | degE7 | | Longitude. |
alt_msl | float | m | | Altitude (MSL). |
alt_rel | float | m | | Altitude (Relative to HOME location). |
roll | float | deg | | Camera Roll angle (earth frame, +-180). |
pitch | float | deg | | Camera Pitch angle (earth frame, +-180). |
yaw | float | deg | | Camera Yaw (earth frame, 0-360, true). |
foc_len | float | mm | | Focal Length. |
flags | uint8_t | | CAMERA_FEEDBACK_FLAGS | Feedback flags. |
completed_captures ** | uint16_t | | | Completed image captures. |
BATTERY2 ( #181 )
DEPRECATED: Replaced by BATTERY_STATUS (2017-04).
[Message] 2nd Battery status
Field Name | Type | Units | Description |
---|
voltage | uint16_t | mV | Voltage. |
current_battery | int16_t | cA | Battery current, -1: autopilot does not measure the current. |
AHRS3 ( #182 )
[Message] Status of third AHRS filter if available. This is for ANU research group (Ali and Sean).
Field Name | Type | Units | Description |
---|
roll | float | rad | Roll angle. |
pitch | float | rad | Pitch angle. |
yaw | float | rad | Yaw angle. |
altitude | float | m | Altitude (MSL). |
lat | int32_t | degE7 | Latitude. |
lng | int32_t | degE7 | Longitude. |
v1 | float | | Test variable1. |
v2 | float | | Test variable2. |
v3 | float | | Test variable3. |
v4 | float | | Test variable4. |
AUTOPILOT_VERSION_REQUEST ( #183 )
[Message] Request the autopilot version from the system/component.
Field Name | Type | Description |
---|
target_system | uint8_t | System ID. |
target_component | uint8_t | Component ID. |
REMOTE_LOG_DATA_BLOCK ( #184 )
[Message] Send a block of log data to remote location.
Field Name | Type | Values | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
seqno | uint32_t | MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS | Log data block sequence number. |
data | uint8_t[200] | | Log data block. |
REMOTE_LOG_BLOCK_STATUS ( #185 )
[Message] Send Status of each log block that autopilot board might have sent.
Field Name | Type | Values | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
seqno | uint32_t | | Log data block sequence number. |
status | uint8_t | MAV_REMOTE_LOG_DATA_BLOCK_STATUSES | Log data block status. |
LED_CONTROL ( #186 )
[Message] Control vehicle LEDs.
Field Name | Type | Description |
---|
target_system | uint8_t | System ID. |
target_component | uint8_t | Component ID. |
instance | uint8_t | Instance (LED instance to control or 255 for all LEDs). |
pattern | uint8_t | Pattern (see LED_PATTERN_ENUM). |
custom_len | uint8_t | Custom Byte Length. |
custom_bytes | uint8_t[24] | Custom Bytes. |
MAG_CAL_PROGRESS ( #191 )
[Message] Reports progress of compass calibration.
Field Name | Type | Units | Values | Description |
---|
compass_id | uint8_t | | | Compass being calibrated. |
cal_mask | uint8_t | | | Bitmask of compasses being calibrated. |
cal_status | uint8_t | | MAG_CAL_STATUS | Calibration Status. |
attempt | uint8_t | | | Attempt number. |
completion_pct | uint8_t | % | | Completion percentage. |
completion_mask | uint8_t[10] | | | Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid). |
direction_x | float | | | Body frame direction vector for display. |
direction_y | float | | | Body frame direction vector for display. |
direction_z | float | | | Body frame direction vector for display. |
MAG_CAL_REPORT ( #192 )
[Message] Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.
Field Name | Type | Units | Values | Description |
---|
compass_id | uint8_t | | | Compass being calibrated. |
cal_mask | uint8_t | | | Bitmask of compasses being calibrated. |
cal_status | uint8_t | | MAG_CAL_STATUS | Calibration Status. |
autosaved | uint8_t | | | 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters. |
fitness | float | mgauss | | RMS milligauss residuals. |
ofs_x | float | | | X offset. |
ofs_y | float | | | Y offset. |
ofs_z | float | | | Z offset. |
diag_x | float | | | X diagonal (matrix 11). |
diag_y | float | | | Y diagonal (matrix 22). |
diag_z | float | | | Z diagonal (matrix 33). |
offdiag_x | float | | | X off-diagonal (matrix 12 and 21). |
offdiag_y | float | | | Y off-diagonal (matrix 13 and 31). |
offdiag_z | float | | | Z off-diagonal (matrix 32 and 23). |
orientation_confidence ** | float | | | Confidence in orientation (higher is better). |
old_orientation ** | uint8_t | | MAV_SENSOR_ORIENTATION | orientation before calibration. |
new_orientation ** | uint8_t | | MAV_SENSOR_ORIENTATION | orientation after calibration. |
EKF_STATUS_REPORT ( #193 )
[Message] EKF Status message including flags and variances.
Field Name | Type | Values | Description |
---|
flags | uint16_t | EKF_STATUS_FLAGS | Flags. |
velocity_variance | float | | Velocity variance. |
pos_horiz_variance | float | | Horizontal Position variance. |
pos_vert_variance | float | | Vertical Position variance. |
compass_variance | float | | Compass variance. |
terrain_alt_variance | float | | Terrain Altitude variance. |
airspeed_variance ** | float | | Airspeed variance. |
PID_TUNING ( #194 )
[Message] PID tuning information.
Field Name | Type | Units | Values | Description |
---|
axis | uint8_t | | PID_TUNING_AXIS | Axis. |
desired | float | deg/s | | Desired rate. |
achieved | float | deg/s | | Achieved rate. |
FF | float | | | FF component. |
P | float | | | P component. |
I | float | | | I component. |
D | float | | | D component. |
DEEPSTALL ( #195 )
[Message] Deepstall path planning.
Field Name | Type | Units | Values | Description |
---|
landing_lat | int32_t | degE7 | | Landing latitude. |
landing_lon | int32_t | degE7 | | Landing longitude. |
path_lat | int32_t | degE7 | | Final heading start point, latitude. |
path_lon | int32_t | degE7 | | Final heading start point, longitude. |
arc_entry_lat | int32_t | degE7 | | Arc entry point, latitude. |
arc_entry_lon | int32_t | degE7 | | Arc entry point, longitude. |
altitude | float | m | | Altitude. |
expected_travel_distance | float | m | | Distance the aircraft expects to travel during the deepstall. |
cross_track_error | float | m | | Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND). |
stage | uint8_t | | DEEPSTALL_STAGE | Deepstall stage. |
GIMBAL_REPORT ( #200 )
[Message] 3 axis gimbal measurements.
Field Name | Type | Units | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
delta_time | float | s | Time since last update. |
delta_angle_x | float | rad | Delta angle X. |
delta_angle_y | float | rad | Delta angle Y. |
delta_angle_z | float | rad | Delta angle X. |
delta_velocity_x | float | m/s | Delta velocity X. |
delta_velocity_y | float | m/s | Delta velocity Y. |
delta_velocity_z | float | m/s | Delta velocity Z. |
joint_roll | float | rad | Joint ROLL. |
joint_el | float | rad | Joint EL. |
joint_az | float | rad | Joint AZ. |
GIMBAL_CONTROL ( #201 )
[Message] Control message for rate gimbal.
Field Name | Type | Units | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
demanded_rate_x | float | rad/s | Demanded angular rate X. |
demanded_rate_y | float | rad/s | Demanded angular rate Y. |
demanded_rate_z | float | rad/s | Demanded angular rate Z. |
GIMBAL_TORQUE_CMD_REPORT ( #214 )
[Message] 100 Hz gimbal torque command telemetry.
Field Name | Type | Description |
---|
target_system | uint8_t | System ID. |
target_component | uint8_t | Component ID. |
rl_torque_cmd | int16_t | Roll Torque Command. |
el_torque_cmd | int16_t | Elevation Torque Command. |
az_torque_cmd | int16_t | Azimuth Torque Command. |
GOPRO_HEARTBEAT ( #215 )
[Message] Heartbeat from a HeroBus attached GoPro.
GOPRO_GET_REQUEST ( #216 )
[Message] Request a GOPRO_COMMAND response from the GoPro.
Field Name | Type | Values | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
cmd_id | uint8_t | GOPRO_COMMAND | Command ID. |
GOPRO_GET_RESPONSE ( #217 )
[Message] Response from a GOPRO_COMMAND get request.
GOPRO_SET_REQUEST ( #218 )
[Message] Request to set a GOPRO_COMMAND with a desired.
Field Name | Type | Values | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
cmd_id | uint8_t | GOPRO_COMMAND | Command ID. |
value | uint8_t[4] | | Value. |
GOPRO_SET_RESPONSE ( #219 )
[Message] Response from a GOPRO_COMMAND set request.
[Message] RPM sensor output.
Field Name | Type | Description |
---|
rpm1 | float | RPM Sensor1. |
rpm2 | float | RPM Sensor2. |
DEVICE_OP_READ ( #11000 )
[Message] (MAVLink 2) Read registers for a device.
Field Name | Type | Values | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
request_id | uint32_t | | Request ID - copied to reply. |
bustype | uint8_t | DEVICE_OP_BUSTYPE | The bus type. |
bus | uint8_t | | Bus number. |
address | uint8_t | | Bus address. |
busname | char[40] | | Name of device on bus (for SPI). |
regstart | uint8_t | | First register to read. |
count | uint8_t | | Count of registers to read. |
DEVICE_OP_READ_REPLY ( #11001 )
[Message] (MAVLink 2) Read registers reply.
Field Name | Type | Description |
---|
request_id | uint32_t | Request ID - copied from request. |
result | uint8_t | 0 for success, anything else is failure code. |
regstart | uint8_t | Starting register. |
count | uint8_t | Count of bytes read. |
data | uint8_t[128] | Reply data. |
DEVICE_OP_WRITE ( #11002 )
[Message] (MAVLink 2) Write registers for a device.
Field Name | Type | Values | Description |
---|
target_system | uint8_t | | System ID. |
target_component | uint8_t | | Component ID. |
request_id | uint32_t | | Request ID - copied to reply. |
bustype | uint8_t | DEVICE_OP_BUSTYPE | The bus type. |
bus | uint8_t | | Bus number. |
address | uint8_t | | Bus address. |
busname | char[40] | | Name of device on bus (for SPI). |
regstart | uint8_t | | First register to write. |
count | uint8_t | | Count of registers to write. |
data | uint8_t[128] | | Write data. |
DEVICE_OP_WRITE_REPLY ( #11003 )
[Message] (MAVLink 2) Write registers reply.
Field Name | Type | Description |
---|
request_id | uint32_t | Request ID - copied from request. |
result | uint8_t | 0 for success, anything else is failure code. |
ADAP_TUNING ( #11010 )
[Message] (MAVLink 2) Adaptive Controller tuning information.
Field Name | Type | Units | Values | Description |
---|
axis | uint8_t | | PID_TUNING_AXIS | Axis. |
desired | float | deg/s | | Desired rate. |
achieved | float | deg/s | | Achieved rate. |
error | float | | | Error between model and vehicle. |
theta | float | | | Theta estimated state predictor. |
omega | float | | | Omega estimated state predictor. |
sigma | float | | | Sigma estimated state predictor. |
theta_dot | float | | | Theta derivative. |
omega_dot | float | | | Omega derivative. |
sigma_dot | float | | | Sigma derivative. |
f | float | | | Projection operator value. |
f_dot | float | | | Projection operator derivative. |
u | float | | | u adaptive controlled output command. |
VISION_POSITION_DELTA ( #11011 )
[Message] (MAVLink 2) Camera vision based attitude and position deltas.
Field Name | Type | Units | Description |
---|
time_usec | uint64_t | us | Timestamp (synced to UNIX time or since system boot). |
time_delta_usec | uint64_t | us | Time since the last reported camera frame. |
angle_delta | float[3] | | Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation. |
position_delta | float[3] | m | Change in position from previous to current frame rotated into body frame (0=forward, 1=right, 2=down). |
confidence | float | % | Normalised confidence value from 0 to 100. |
[Message] (MAVLink 2) Angle of Attack and Side Slip Angle.
Field Name | Type | Units | Description |
---|
time_usec | uint64_t | us | Timestamp (since boot or Unix epoch). |
AOA | float | deg | Angle of Attack. |
SSA | float | deg | Side Slip Angle. |
ESC_TELEMETRY_1_TO_4 ( #11030 )
[Message] (MAVLink 2) ESC Telemetry Data for ESCs 1 to 4, matching data sent by BLHeli ESCs.
Field Name | Type | Units | Description |
---|
temperature | uint8_t[4] | degC | Temperature. |
voltage | uint16_t[4] | cV | Voltage. |
current | uint16_t[4] | cA | Current. |
totalcurrent | uint16_t[4] | mAh | Total current. |
rpm | uint16_t[4] | rpm | RPM (eRPM). |
count | uint16_t[4] | | count of telemetry packets received (wraps at 65535). |
ESC_TELEMETRY_5_TO_8 ( #11031 )
[Message] (MAVLink 2) ESC Telemetry Data for ESCs 5 to 8, matching data sent by BLHeli ESCs.
Field Name | Type | Units | Description |
---|
temperature | uint8_t[4] | degC | Temperature. |
voltage | uint16_t[4] | cV | Voltage. |
current | uint16_t[4] | cA | Current. |
totalcurrent | uint16_t[4] | mAh | Total current. |
rpm | uint16_t[4] | rpm | RPM (eRPM). |
count | uint16_t[4] | | count of telemetry packets received (wraps at 65535). |
ESC_TELEMETRY_9_TO_12 ( #11032 )
[Message] (MAVLink 2) ESC Telemetry Data for ESCs 9 to 12, matching data sent by BLHeli ESCs.
Field Name | Type | Units | Description |
---|
temperature | uint8_t[4] | degC | Temperature. |
voltage | uint16_t[4] | cV | Voltage. |
current | uint16_t[4] | cA | Current. |
totalcurrent | uint16_t[4] | mAh | Total current. |
rpm | uint16_t[4] | rpm | RPM (eRPM). |
count | uint16_t[4] | | count of telemetry packets received (wraps at 65535). |