方言:ArduPilotMega
ardupilotmega.xml 的ArduPilot MAVLink分支可能包含尚未合并到本文档中的消息。 The documentation below may not be accurate if the dialect owner has not pushed changes.
这些消息定义了ArduPilot特定的消息集,该消息集是 http://ardupilot.org 的自定义消息。
这个话题是一种 XML 定义文件的可读形式: ardupilotmega.xml 。
已添加到 MAVLink 1 消息中的 MAVLink 2 扩展字段以蓝色显示。 - Entities from dialects are displayed only as headings (with link to original)
Protocol dialect: 2
MAVLink Include Files
Summary
The following sections list all entities in the dialect (both included and defined in this file).
Messages
SENSOR_OFFSETS (150)
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) — [DEP]
DEPRECATED: Replaced By MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS (2014-07)
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)
State of autopilot RAM.
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)
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. |
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)
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 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 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 with some status from autopilot to GCS about camera or antenna mount.
Field Name | Type | Units | Values | 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. |
mount_mode ++ | uint8_t | | MAV_MOUNT_MODE | Mount operating mode. |
FENCE_POINT (160)
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)
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)
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)
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)
Status of key hardware.
Field Name | Type | Units | Description |
---|
Vcc | uint16_t | mV | Board voltage. |
I2Cerr | uint8_t | | I2C error count. |
RADIO (166)
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)
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)
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)
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)
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)
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)
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)
Rangefinder reporting.
Field Name | Type | Units | Description |
---|
distance | float | m | Distance. |
voltage | float | V | Raw voltage if available, zero otherwise. |
AIRSPEED_AUTOCAL (174)
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)
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)
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)
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)
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)
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)
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) — [DEP]
DEPRECATED: Replaced By BATTERY_STATUS (2017-04)
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)
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)
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)
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)
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)
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)
Reports progress of compass calibration.
Field Name | Type | Units | Values | Description |
---|
compass_id | uint8_t | | | Compass being calibrated. |
Messages with same value are from the same source (instance). | | 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. |
EKF_STATUS_REPORT (193)
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)
PID tuning information.
Messages with same value are from the same source (instance). | | desired | float
| | Desired rate. | | achieved | float
| | Achieved rate. | | FF | float
| | FF component. | | P | float
| | P component. | | I | float
| | I component. | | D | float
| | D component. | | SRate ++ | float
| | Slew rate. | | PDmod ++ | float
| | P/D oscillation modifier. |
DEEPSTALL (195)
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)
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)
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)
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)
Heartbeat from a HeroBus attached GoPro.
GOPRO_GET_REQUEST (216)
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)
Response from a GOPRO_COMMAND get request.
GOPRO_SET_REQUEST (218)
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)
Response from a GOPRO_COMMAND set request.
RPM (226)
RPM sensor output.
Field Name | Type | Description |
---|
rpm1 | float | RPM Sensor1. |
rpm2 | float | RPM Sensor2. |
DEVICE_OP_READ (11000)
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. |
bank ++ | uint8_t | | Bank number. |
DEVICE_OP_READ_REPLY (11001)
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. |
bank ++ | uint8_t | Bank number. |
DEVICE_OP_WRITE (11002)
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. |
bank ++ | uint8_t | | Bank number. |
DEVICE_OP_WRITE_REPLY (11003)
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)
Adaptive Controller tuning information.
Messages with same value are from the same source (instance). | | 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)
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] | rad | Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD. |
position_delta | float[3] | m | Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD. |
confidence | float | % | Normalised confidence value from 0 to 100. |
AOA_SSA (11020)
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)
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)
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)
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). |
OSD_PARAM_CONFIG (11033)
Configure an OSD parameter slot.
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. |
osd_screen | uint8_t | | OSD parameter screen index. |
osd_index | uint8_t | | OSD parameter display index. |
param_id | char[16] | | Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string |
config_type | uint8_t | OSD_PARAM_CONFIG_TYPE | Config type. |
min_value | float | | OSD parameter minimum value. |
max_value | float | | OSD parameter maximum value. |
increment | float | | OSD parameter increment. |
OSD_PARAM_CONFIG_REPLY (11034)
Configure OSD parameter reply.
Field Name | Type | Values | Description |
---|
request_id | uint32_t | | Request ID - copied from request. |
result | uint8_t | OSD_PARAM_CONFIG_ERROR | Config error type. |
OSD_PARAM_SHOW_CONFIG (11035)
Read a configured an OSD parameter slot.
Field Name | Type | Description |
---|
target_system | uint8_t | System ID. |
target_component | uint8_t | Component ID. |
request_id | uint32_t | Request ID - copied to reply. |
osd_screen | uint8_t | OSD parameter screen index. |
osd_index | uint8_t | OSD parameter display index. |
OSD_PARAM_SHOW_CONFIG_REPLY (11036)
Read configured OSD parameter reply.
Field Name | Type | Values | Description |
---|
request_id | uint32_t | | Request ID - copied from request. |
result | uint8_t | OSD_PARAM_CONFIG_ERROR | Config error type. |
param_id | char[16] | | Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string |
config_type | uint8_t | OSD_PARAM_CONFIG_TYPE | Config type. |
min_value | float | | OSD parameter minimum value. |
max_value | float | | OSD parameter maximum value. |
increment | float | | OSD parameter increment. |
OBSTACLE_DISTANCE_3D (11037) — [WIP]
WORK IN PROGRESS: Do not use in stable production environments (it may change).
Obstacle located as a 3D vector.
Field Name | Type | Units | Values | Description |
---|
time_boot_ms | uint32_t | ms | | Timestamp (time since system boot). |
sensor_type | uint8_t | | MAV_DISTANCE_SENSOR | Class id of the distance sensor type. |
frame | uint8_t | | MAV_FRAME | Coordinate frame of reference. |
obstacle_id | uint16_t | | | Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined. |
Messages with same value are from the same source (instance). | | x | float
| m | | X position of the obstacle. | | y | float
| m | | Y position of the obstacle. | | z | float
| m | | Z position of the obstacle. | | min_distance | float
| m | | Minimum distance the sensor can measure. | | max_distance | float
| m | | Maximum distance the sensor can measure. |
WATER_DEPTH (11038)
Water depth
Field Name | Type | Units | Description |
---|
time_boot_ms | uint32_t | ms | Timestamp (time since system boot) |
id | uint8_t | | Onboard ID of the sensor |
Messages with same value are from the same source (instance). | | healthy | uint8_t
| | Sensor data healthy (0=unhealthy, 1=healthy) | | lat | int32_t
| degE7 | Latitude | | lng | int32_t
| degE7 | Longitude | | alt | float
| m | Altitude (MSL) of vehicle | | roll | float
| rad | Roll angle | | pitch | float
| rad | Pitch angle | | yaw | float
| rad | Yaw angle | | distance | float
| m | Distance (uncorrected) | | temperature | float
| degC | Water temperature |
MCU_STATUS (11039)
The MCU status, giving MCU temperature and voltage. The min and max voltages are to allow for detecting power supply instability.
Field Name | Type | Units | Description |
---|
id | uint8_t | | MCU instance |
Messages with same value are from the same source (instance). | | MCU_temperature | int16_t
| cdegC | MCU Internal temperature | | MCU_voltage | uint16_t
| mV | MCU voltage | | MCU_voltage_min | uint16_t
| mV | MCU voltage minimum | | MCU_voltage_max | uint16_t
| mV | MCU voltage maximum |
Enumerated Types
ACCELCAL_VEHICLE_POS
HEADING_TYPE
SCRIPTING_CMD
LIMITS_STATE
LIMIT_MODULE
(Bitmask)
RALLY_FLAGS
(Bitmask) Flags in RALLY_POINT message.
Value | 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. |
CAMERA_STATUS_TYPES
CAMERA_FEEDBACK_FLAGS
MAV_MODE_GIMBAL
GIMBAL_AXIS
GIMBAL_AXIS_CALIBRATION_STATUS
GIMBAL_AXIS_CALIBRATION_REQUIRED
GOPRO_HEARTBEAT_STATUS
GOPRO_HEARTBEAT_FLAGS
(Bitmask)
GOPRO_REQUEST_STATUS
GOPRO_COMMAND
GOPRO_CAPTURE_MODE
GOPRO_RESOLUTION
GOPRO_FRAME_RATE
GOPRO_FIELD_OF_VIEW
GOPRO_VIDEO_SETTINGS_FLAGS
(Bitmask)
GOPRO_PHOTO_RESOLUTION
GOPRO_PROTUNE_WHITE_BALANCE
GOPRO_PROTUNE_COLOUR
GOPRO_PROTUNE_GAIN
GOPRO_PROTUNE_SHARPNESS
GOPRO_PROTUNE_EXPOSURE
GOPRO_CHARGING
GOPRO_MODEL
GOPRO_BURST_RATE
MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL
LED_CONTROL_PATTERN
EKF_STATUS_FLAGS
(Bitmask) Flags in EKF_STATUS message.
PID_TUNING_AXIS
MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS
Special ACK block numbers control activation of dataflash log streaming.
MAV_REMOTE_LOG_DATA_BLOCK_STATUSES
Possible remote log data block statuses.
DEVICE_OP_BUSTYPE
Bus types for device operations.
DEEPSTALL_STAGE
Deepstall flight stage.
PLANE_MODE
A mapping of plane flight modes for custom_mode field of heartbeat.
COPTER_MODE
A mapping of copter flight modes for custom_mode field of heartbeat.
SUB_MODE
A mapping of sub flight modes for custom_mode field of heartbeat.
ROVER_MODE
A mapping of rover flight modes for custom_mode field of heartbeat.
TRACKER_MODE
A mapping of antenna tracker flight modes for custom_mode field of heartbeat.
OSD_PARAM_CONFIG_TYPE
The type of parameter for the OSD parameter editor.
OSD_PARAM_CONFIG_ERROR
The error type for the OSD parameter editor.
Commands (MAV_CMD)
MAV_CMD_NAV_ALTITUDE_WAIT (83)
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 | Units |
---|
1 (Altitude) | Altitude. | m |
2 (Descent Speed) | Descent speed. | m/s |
3 (Wiggle Time) | How long to wiggle the control surfaces to prevent them seizing up. | s |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_DO_SET_RESUME_REPEAT_DIST (215)
Set the distance to be repeated on mission resume
Param (Label) | Description | Units |
---|
1 (Distance) | Distance. | m |
2 | Empty. | |
3 | Empty. | |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_DO_SPRAYER (216)
Control attached liquid sprayer
Param (Label) | Description | Values |
---|
1 (Sprayer Enable) | 0: disable sprayer. 1: enable sprayer. | min: 0 max: 1 inc: 1 |
2 | Empty. | |
3 | Empty. | |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_DO_SEND_SCRIPT_MESSAGE (217)
Pass instructions onto scripting, a script should be checking for a new command
Param (Label) | Description | Values |
---|
1 (ID) | uint16 ID value to be passed to scripting | min: 0 max: 65535 inc: 1 |
2 (param 1) | float value to be passed to scripting | |
3 (param 2) | float value to be passed to scripting | |
4 (param 3) | float value to be passed to scripting | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_DO_AUX_FUNCTION (218)
Execute auxiliary function
MAV_CMD_POWER_OFF_INITIATED (42000)
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)
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)
FLY button has been held for 1.5 seconds.
Param (Label) | Description | Units |
---|
1 (Takeoff Altitude) | Takeoff altitude. | m |
2 | Empty. | |
3 | Empty. | |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_SOLO_BTN_PAUSE_CLICK (42003)
PAUSE button has been clicked.
Param (Label) | Description | Values |
---|
1 (Shot Mode) | 1 if Solo is in a shot mode, 0 otherwise. | min: 0 max: 1 inc: 1 |
2 | Empty. | |
3 | Empty. | |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_FIXED_MAG_CAL (42004)
Magnetometer calibration based on fixed position
in earth field given by inclination, declination and intensity.
Param (Label) | Description | Units |
---|
1 (Declination) | Magnetic declination. | deg |
2 (Inclination) | Magnetic inclination. | deg |
3 (Intensity) | Magnetic intensity. | mgauss |
4 (Yaw) | Yaw. | deg |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_FIXED_MAG_CAL_FIELD (42005)
Magnetometer calibration based on fixed expected field values.
Param (Label) | Description | Units |
---|
1 (Field X) | Field strength X. | mgauss |
2 (Field Y) | Field strength Y. | mgauss |
3 (Field Z) | Field strength Z. | mgauss |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_SET_EKF_SOURCE_SET (42007)
Set EKF sensor source set.
Param (Label) | Description | Values |
---|
1 (SourceSetId) | Source Set Id. | min: 1 max: 3 inc: 1 |
2 | Empty. | |
3 | Empty. | |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_DO_START_MAG_CAL (42424)
Initiate a magnetometer calibration.
Param (Label) | Description | Values | Units |
---|
1 (Magnetometers Bitmask) | Bitmask of magnetometers to calibrate. Use 0 to calibrate all sensors that can be started (sensors may not start if disabled, unhealthy, etc.). The command will NACK if calibration does not start for a sensor explicitly specified by the bitmask. | min: 0 max: 255 inc: 1 | |
2 (Retry on Failure) | Automatically retry on failure (0=no retry, 1=retry). | min: 0 max: 1 inc: 1 | |
3 (Autosave) | Save without user input (0=require input, 1=autosave). | min: 0 max: 1 inc: 1 | |
4 (Delay) | Delay. | | s |
5 (Autoreboot) | Autoreboot (0=user reboot, 1=autoreboot). | min: 0 max: 1 inc: 1 | |
6 | Empty. | | |
7 | Empty. | |
MAV_CMD_DO_ACCEPT_MAG_CAL (42425)
Accept a magnetometer calibration.
Param (Label) | Description | Values |
---|
1 (Magnetometers Bitmask) | Bitmask of magnetometers that calibration is accepted (0 means all). | min: 0 max: 255 inc: 1 |
2 | Empty. | |
3 | Empty. | |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_DO_CANCEL_MAG_CAL (42426)
Cancel a running magnetometer calibration.
Param (Label) | Description | Values |
---|
1 (Magnetometers Bitmask) | Bitmask of magnetometers to cancel a running calibration (0 means all). | min: 0 max: 255 inc: 1 |
2 | Empty. | |
3 | Empty. | |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_SET_FACTORY_TEST_MODE (42427)
Command autopilot to get into factory test/diagnostic mode.
Param (Label) | Description | Values |
---|
1 (Test Mode) | 0: activate test mode, 1: exit test mode. | min: 0 max: 1 inc: 1 |
2 | Empty. | |
3 | Empty. | |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_DO_SEND_BANNER (42428)
Reply with the version banner.
Param (Label) | Description |
---|
1 | Empty. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_ACCELCAL_VEHICLE_POS (42429)
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 | Values |
---|
1 (Position) | Position. | ACCELCAL_VEHICLE_POS |
2 | Empty. | |
3 | Empty. | |
4 | Empty. | |
5 | Empty. | |
6 | Empty. | |
7 | Empty. |
MAV_CMD_GIMBAL_RESET (42501)
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)
Reports progress and success or failure of gimbal axis calibration procedure.
Param (Label) | Description | Values | Units |
---|
1 (Axis) | Gimbal axis we're reporting calibration progress for. | GIMBAL_AXIS | |
2 (Progress) | Current calibration progress for this axis. | min: 0 max: 100 | % |
3 (Status) | Status of the calibration. | GIMBAL_AXIS_CALIBRATION_STATUS | |
4 | Empty. | | |
5 | Empty. | | |
6 | Empty. | | |
7 | Empty. | |
MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION (42503)
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)
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_FLASH_BOOTLOADER (42650)
Update the bootloader
Param (Label) | Description | Values |
---|
1 | Empty | |
2 | Empty | |
3 | Empty | |
4 | Empty | |
5 (Magic Number) | Magic number - set to 290876 to actually flash | inc: 1 |
6 | Empty | |
7 | Empty |
MAV_CMD_BATTERY_RESET (42651)
Reset battery capacity for batteries that accumulate consumed battery via integration.
Param (Label) | Description | Values |
---|
1 (battery mask) | Bitmask of batteries to reset. Least significant bit is for the first battery. | |
2 (percentage) | Battery percentage remaining to set. | min: 0 max: 100 inc: 1 |
MAV_CMD_DEBUG_TRAP (42700)
Issue a trap signal to the autopilot process, presumably to enter the debugger.
Param (Label) | Description |
---|
1 | Magic number - set to 32451 to actually trap. |
2 | Empty. |
3 | Empty. |
4 | Empty. |
5 | Empty. |
6 | Empty. |
7 | Empty. |
MAV_CMD_SCRIPTING (42701)
Control onboard scripting.
Param (Label) | Description | Values |
---|
1 | Scripting command to execute | SCRIPTING_CMD |
MAV_CMD_NAV_SCRIPT_TIME (42702)
Scripting command as NAV command with wait for completion.
Param (Label) | Description | Units |
---|
1 (command) | integer command number (0 to 255) | |
2 (timeout) | timeout for operation in seconds. Zero means no timeout (0 to 255) | s |
3 (arg1) | argument1. | |
4 (arg2) | argument2. | |
5 | Empty | |
6 | Empty | |
7 | Empty |
MAV_CMD_NAV_ATTITUDE_TIME (42703)
Maintain an attitude for a specified time.
Param (Label) | Description | Units |
---|
1 (time) | Time to maintain specified attitude and climb rate | s |
2 (roll) | Roll angle in degrees (positive is lean right, negative is lean left) | deg |
3 (pitch) | Pitch angle in degrees (positive is lean back, negative is lean forward) | deg |
4 (yaw) | Yaw angle | deg |
5 (climb_rate) | Climb rate | m/s |
6 | Empty | |
7 | Empty |
MAV_CMD_GUIDED_CHANGE_SPEED (43000)
Change flight speed at a given rate. This slews the vehicle at a controllable rate between it's previous speed and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.)
Param (Label) | Description | Values | Units |
---|
1 (speed type) | Airspeed or groundspeed. | SPEED_TYPE | |
2 (speed target) | Target Speed | | m/s |
3 (speed rate-of-change) | Acceleration rate, 0 to take effect instantly | | m/s/s |
4 | Empty | | |
5 | Empty | | |
6 | Empty | | |
7 | Empty | |
MAV_CMD_GUIDED_CHANGE_ALTITUDE (43001)
Change target altitude at a given rate. This slews the vehicle at a controllable rate between it's previous altitude and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.)
Param (Label) | Description | Values | Units |
---|
1 | Empty | | |
2 | Empty | | |
3 (alt rate-of-change) | Rate of change, toward new altitude. 0 for maximum rate change. Positive numbers only, as negative numbers will not converge on the new target alt. | min: 0 | m/s/s |
4 | Empty | | |
5 | Empty | | |
6 | Empty | | |
7 (target alt) | Target Altitude | | m |
MAV_CMD_GUIDED_CHANGE_HEADING (43002)
Change to target heading at a given rate, overriding previous heading/s. This slews the vehicle at a controllable rate between it's previous heading and the new one. (affects GUIDED only. Exiting GUIDED returns aircraft to normal behaviour defined elsewhere. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.)
Param (Label) | Description | Values | Units |
---|
1 (heading type) | course-over-ground or raw vehicle heading. | HEADING_TYPE | |
2 (heading target) | Target heading. | min: 0 max: 359.99 | deg |
3 (heading rate-of-change) | Maximum centripetal accelearation, ie rate of change, toward new heading. | | m/s/s |
4 | Empty | | |
5 | Empty | | |
6 | Empty | | |
7 | Empty | | |