MAVLINK ArduPilotMega Message Set

These messages define the ArduPilot specific message set, which is custom to http://ardupilot.org.

This 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.

ACCELCAL_VEHICLE_POS

ValueField NameDescription
1ACCELCAL_VEHICLE_POS_LEVEL
2ACCELCAL_VEHICLE_POS_LEFT
3ACCELCAL_VEHICLE_POS_RIGHT
4ACCELCAL_VEHICLE_POS_NOSEDOWN
5ACCELCAL_VEHICLE_POS_NOSEUP
6ACCELCAL_VEHICLE_POS_BACK
16777215ACCELCAL_VEHICLE_POS_SUCCESS
16777216ACCELCAL_VEHICLE_POS_FAILED

LIMITS_STATE

ValueField NameDescription
0LIMITS_INITPre-initialization.
1LIMITS_DISABLEDDisabled.
2LIMITS_ENABLEDChecking limits.
3LIMITS_TRIGGEREDA limit has been breached.
4LIMITS_RECOVERINGTaking action e.g. Return/RTL.
5LIMITS_RECOVEREDWe're no longer in breach of a limit.

LIMIT_MODULE

ValueField NameDescription
1LIMIT_GPSLOCKPre-initialization.
2LIMIT_GEOFENCEDisabled.
4LIMIT_ALTITUDEChecking limits.

RALLY_FLAGS

Flags in RALLY_POINT message.

ValueField NameDescription
1FAVORABLE_WINDFlag set when requiring favorable winds for landing.
2LAND_IMMEDIATELYFlag 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.

PARACHUTE_ACTION

ValueField NameDescription
0PARACHUTE_DISABLEDisable parachute release.
1PARACHUTE_ENABLEEnable parachute release.
2PARACHUTE_RELEASERelease parachute.

GRIPPER_ACTIONS

Gripper actions.

ValueField NameDescription
0GRIPPER_ACTION_RELEASEGripper release cargo.
1GRIPPER_ACTION_GRABGripper grab onto cargo.

WINCH_ACTIONS

Winch actions.

ValueField NameDescription
0WINCH_RELAXEDRelax winch.
1WINCH_RELATIVE_LENGTH_CONTROLWinch unwinds or winds specified length of cable optionally using specified rate.
2WINCH_RATE_CONTROLWinch unwinds or winds cable at specified rate in meters/seconds.

CAMERA_STATUS_TYPES

ValueField NameDescription
0CAMERA_STATUS_TYPE_HEARTBEATCamera heartbeat, announce camera component ID at 1Hz.
1CAMERA_STATUS_TYPE_TRIGGERCamera image triggered.
2CAMERA_STATUS_TYPE_DISCONNECTCamera connection lost.
3CAMERA_STATUS_TYPE_ERRORCamera unknown error.
4CAMERA_STATUS_TYPE_LOWBATTCamera battery low. Parameter p1 shows reported voltage.
5CAMERA_STATUS_TYPE_LOWSTORECamera storage low. Parameter p1 shows reported shots remaining.
6CAMERA_STATUS_TYPE_LOWSTOREVCamera storage low. Parameter p1 shows reported video minutes remaining.

CAMERA_FEEDBACK_FLAGS

ValueField NameDescription
0CAMERA_FEEDBACK_PHOTOShooting photos, not video.
1CAMERA_FEEDBACK_VIDEOShooting video, not stills.
2CAMERA_FEEDBACK_BADEXPOSUREUnable to achieve requested exposure (e.g. shutter speed too low).
3CAMERA_FEEDBACK_CLOSEDLOOPClosed loop feedback from camera, we know for sure it has successfully taken a picture.
4CAMERA_FEEDBACK_OPENLOOPOpen loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture.

MAV_MODE_GIMBAL

ValueField NameDescription
0MAV_MODE_GIMBAL_UNINITIALIZEDGimbal is powered on but has not started initializing yet.
1MAV_MODE_GIMBAL_CALIBRATING_PITCHGimbal is currently running calibration on the pitch axis.
2MAV_MODE_GIMBAL_CALIBRATING_ROLLGimbal is currently running calibration on the roll axis.
3MAV_MODE_GIMBAL_CALIBRATING_YAWGimbal is currently running calibration on the yaw axis.
4MAV_MODE_GIMBAL_INITIALIZEDGimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter.
5MAV_MODE_GIMBAL_ACTIVEGimbal is actively stabilizing.
6MAV_MODE_GIMBAL_RATE_CMD_TIMEOUTGimbal 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_AXIS

ValueField NameDescription
0GIMBAL_AXIS_YAWGimbal yaw axis.
1GIMBAL_AXIS_PITCHGimbal pitch axis.
2GIMBAL_AXIS_ROLLGimbal roll axis.

GIMBAL_AXIS_CALIBRATION_STATUS

ValueField NameDescription
0GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESSAxis calibration is in progress.
1GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDEDAxis calibration succeeded.
2GIMBAL_AXIS_CALIBRATION_STATUS_FAILEDAxis calibration failed.

GIMBAL_AXIS_CALIBRATION_REQUIRED

ValueField NameDescription
0GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWNWhether or not this axis requires calibration is unknown at this time.
1GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUEThis axis requires calibration.
2GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSEThis axis does not require calibration.

GOPRO_HEARTBEAT_STATUS

ValueField NameDescription
0GOPRO_HEARTBEAT_STATUS_DISCONNECTEDNo GoPro connected.
1GOPRO_HEARTBEAT_STATUS_INCOMPATIBLEThe detected GoPro is not HeroBus compatible.
2GOPRO_HEARTBEAT_STATUS_CONNECTEDA HeroBus compatible GoPro is connected.
3GOPRO_HEARTBEAT_STATUS_ERRORAn unrecoverable error was encountered with the connected GoPro, it may require a power cycle.

GOPRO_HEARTBEAT_FLAGS

ValueField NameDescription
1GOPRO_FLAG_RECORDINGGoPro is currently recording.

GOPRO_REQUEST_STATUS

ValueField NameDescription
0GOPRO_REQUEST_SUCCESSThe write message with ID indicated succeeded.
1GOPRO_REQUEST_FAILEDThe write message with ID indicated failed.

GOPRO_COMMAND

ValueField NameDescription
0GOPRO_COMMAND_POWER(Get/Set).
1GOPRO_COMMAND_CAPTURE_MODE(Get/Set).
2GOPRO_COMMAND_SHUTTER(___/Set).
3GOPRO_COMMAND_BATTERY(Get/___).
4GOPRO_COMMAND_MODEL(Get/___).
5GOPRO_COMMAND_VIDEO_SETTINGS(Get/Set).
6GOPRO_COMMAND_LOW_LIGHT(Get/Set).
7GOPRO_COMMAND_PHOTO_RESOLUTION(Get/Set).
8GOPRO_COMMAND_PHOTO_BURST_RATE(Get/Set).
9GOPRO_COMMAND_PROTUNE(Get/Set).
10GOPRO_COMMAND_PROTUNE_WHITE_BALANCE(Get/Set) Hero 3+ Only.
11GOPRO_COMMAND_PROTUNE_COLOUR(Get/Set) Hero 3+ Only.
12GOPRO_COMMAND_PROTUNE_GAIN(Get/Set) Hero 3+ Only.
13GOPRO_COMMAND_PROTUNE_SHARPNESS(Get/Set) Hero 3+ Only.
14GOPRO_COMMAND_PROTUNE_EXPOSURE(Get/Set) Hero 3+ Only.
15GOPRO_COMMAND_TIME(Get/Set).
16GOPRO_COMMAND_CHARGING(Get/Set).

GOPRO_CAPTURE_MODE

ValueField NameDescription
0GOPRO_CAPTURE_MODE_VIDEOVideo mode.
1GOPRO_CAPTURE_MODE_PHOTOPhoto mode.
2GOPRO_CAPTURE_MODE_BURSTBurst mode, Hero 3+ only.
3GOPRO_CAPTURE_MODE_TIME_LAPSETime lapse mode, Hero 3+ only.
4GOPRO_CAPTURE_MODE_MULTI_SHOTMulti shot mode, Hero 4 only.
5GOPRO_CAPTURE_MODE_PLAYBACKPlayback mode, Hero 4 only, silver only except when LCD or HDMI is connected to black.
6GOPRO_CAPTURE_MODE_SETUPPlayback mode, Hero 4 only.
255GOPRO_CAPTURE_MODE_UNKNOWNMode not yet known.

GOPRO_RESOLUTION

ValueField NameDescription
0GOPRO_RESOLUTION_480p848 x 480 (480p).
1GOPRO_RESOLUTION_720p1280 x 720 (720p).
2GOPRO_RESOLUTION_960p1280 x 960 (960p).
3GOPRO_RESOLUTION_1080p1920 x 1080 (1080p).
4GOPRO_RESOLUTION_1440p1920 x 1440 (1440p).
5GOPRO_RESOLUTION_2_7k_17_92704 x 1440 (2.7k-17:9).
6GOPRO_RESOLUTION_2_7k_16_92704 x 1524 (2.7k-16:9).
7GOPRO_RESOLUTION_2_7k_4_32704 x 2028 (2.7k-4:3).
8GOPRO_RESOLUTION_4k_16_93840 x 2160 (4k-16:9).
9GOPRO_RESOLUTION_4k_17_94096 x 2160 (4k-17:9).
10GOPRO_RESOLUTION_720p_SUPERVIEW1280 x 720 (720p-SuperView).
11GOPRO_RESOLUTION_1080p_SUPERVIEW1920 x 1080 (1080p-SuperView).
12GOPRO_RESOLUTION_2_7k_SUPERVIEW2704 x 1520 (2.7k-SuperView).
13GOPRO_RESOLUTION_4k_SUPERVIEW3840 x 2160 (4k-SuperView).

GOPRO_FRAME_RATE

ValueField NameDescription
0GOPRO_FRAME_RATE_1212 FPS.
1GOPRO_FRAME_RATE_1515 FPS.
2GOPRO_FRAME_RATE_2424 FPS.
3GOPRO_FRAME_RATE_2525 FPS.
4GOPRO_FRAME_RATE_3030 FPS.
5GOPRO_FRAME_RATE_4848 FPS.
6GOPRO_FRAME_RATE_5050 FPS.
7GOPRO_FRAME_RATE_6060 FPS.
8GOPRO_FRAME_RATE_8080 FPS.
9GOPRO_FRAME_RATE_9090 FPS.
10GOPRO_FRAME_RATE_100100 FPS.
11GOPRO_FRAME_RATE_120120 FPS.
12GOPRO_FRAME_RATE_240240 FPS.
13GOPRO_FRAME_RATE_12_512.5 FPS.

GOPRO_FIELD_OF_VIEW

ValueField NameDescription
0GOPRO_FIELD_OF_VIEW_WIDE0x00: Wide.
1GOPRO_FIELD_OF_VIEW_MEDIUM0x01: Medium.
2GOPRO_FIELD_OF_VIEW_NARROW0x02: Narrow.

GOPRO_VIDEO_SETTINGS_FLAGS

ValueField NameDescription
1GOPRO_VIDEO_SETTINGS_TV_MODE0=NTSC, 1=PAL.

GOPRO_PHOTO_RESOLUTION

ValueField NameDescription
0GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM5MP Medium.
1GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM7MP Medium.
2GOPRO_PHOTO_RESOLUTION_7MP_WIDE7MP Wide.
3GOPRO_PHOTO_RESOLUTION_10MP_WIDE10MP Wide.
4GOPRO_PHOTO_RESOLUTION_12MP_WIDE12MP Wide.

GOPRO_PROTUNE_WHITE_BALANCE

ValueField NameDescription
0GOPRO_PROTUNE_WHITE_BALANCE_AUTOAuto.
1GOPRO_PROTUNE_WHITE_BALANCE_3000K3000K.
2GOPRO_PROTUNE_WHITE_BALANCE_5500K5500K.
3GOPRO_PROTUNE_WHITE_BALANCE_6500K6500K.
4GOPRO_PROTUNE_WHITE_BALANCE_RAWCamera Raw.

GOPRO_PROTUNE_COLOUR

ValueField NameDescription
0GOPRO_PROTUNE_COLOUR_STANDARDAuto.
1GOPRO_PROTUNE_COLOUR_NEUTRALNeutral.

GOPRO_PROTUNE_GAIN

ValueField NameDescription
0GOPRO_PROTUNE_GAIN_400ISO 400.
1GOPRO_PROTUNE_GAIN_800ISO 800 (Only Hero 4).
2GOPRO_PROTUNE_GAIN_1600ISO 1600.
3GOPRO_PROTUNE_GAIN_3200ISO 3200 (Only Hero 4).
4GOPRO_PROTUNE_GAIN_6400ISO 6400.

GOPRO_PROTUNE_SHARPNESS

ValueField NameDescription
0GOPRO_PROTUNE_SHARPNESS_LOWLow Sharpness.
1GOPRO_PROTUNE_SHARPNESS_MEDIUMMedium Sharpness.
2GOPRO_PROTUNE_SHARPNESS_HIGHHigh Sharpness.

GOPRO_PROTUNE_EXPOSURE

ValueField NameDescription
0GOPRO_PROTUNE_EXPOSURE_NEG_5_0-5.0 EV (Hero 3+ Only).
1GOPRO_PROTUNE_EXPOSURE_NEG_4_5-4.5 EV (Hero 3+ Only).
2GOPRO_PROTUNE_EXPOSURE_NEG_4_0-4.0 EV (Hero 3+ Only).
3GOPRO_PROTUNE_EXPOSURE_NEG_3_5-3.5 EV (Hero 3+ Only).
4GOPRO_PROTUNE_EXPOSURE_NEG_3_0-3.0 EV (Hero 3+ Only).
5GOPRO_PROTUNE_EXPOSURE_NEG_2_5-2.5 EV (Hero 3+ Only).
6GOPRO_PROTUNE_EXPOSURE_NEG_2_0-2.0 EV.
7GOPRO_PROTUNE_EXPOSURE_NEG_1_5-1.5 EV.
8GOPRO_PROTUNE_EXPOSURE_NEG_1_0-1.0 EV.
9GOPRO_PROTUNE_EXPOSURE_NEG_0_5-0.5 EV.
10GOPRO_PROTUNE_EXPOSURE_ZERO0.0 EV.
11GOPRO_PROTUNE_EXPOSURE_POS_0_5+0.5 EV.
12GOPRO_PROTUNE_EXPOSURE_POS_1_0+1.0 EV.
13GOPRO_PROTUNE_EXPOSURE_POS_1_5+1.5 EV.
14GOPRO_PROTUNE_EXPOSURE_POS_2_0+2.0 EV.
15GOPRO_PROTUNE_EXPOSURE_POS_2_5+2.5 EV (Hero 3+ Only).
16GOPRO_PROTUNE_EXPOSURE_POS_3_0+3.0 EV (Hero 3+ Only).
17GOPRO_PROTUNE_EXPOSURE_POS_3_5+3.5 EV (Hero 3+ Only).
18GOPRO_PROTUNE_EXPOSURE_POS_4_0+4.0 EV (Hero 3+ Only).
19GOPRO_PROTUNE_EXPOSURE_POS_4_5+4.5 EV (Hero 3+ Only).
20GOPRO_PROTUNE_EXPOSURE_POS_5_0+5.0 EV (Hero 3+ Only).

GOPRO_CHARGING

ValueField NameDescription
0GOPRO_CHARGING_DISABLEDCharging disabled.
1GOPRO_CHARGING_ENABLEDCharging enabled.

GOPRO_MODEL

ValueField NameDescription
0GOPRO_MODEL_UNKNOWNUnknown gopro model.
1GOPRO_MODEL_HERO_3_PLUS_SILVERHero 3+ Silver (HeroBus not supported by GoPro).
2GOPRO_MODEL_HERO_3_PLUS_BLACKHero 3+ Black.
3GOPRO_MODEL_HERO_4_SILVERHero 4 Silver.
4GOPRO_MODEL_HERO_4_BLACKHero 4 Black.

GOPRO_BURST_RATE

ValueField NameDescription
0GOPRO_BURST_RATE_3_IN_1_SECOND3 Shots / 1 Second.
1GOPRO_BURST_RATE_5_IN_1_SECOND5 Shots / 1 Second.
2GOPRO_BURST_RATE_10_IN_1_SECOND10 Shots / 1 Second.
3GOPRO_BURST_RATE_10_IN_2_SECOND10 Shots / 2 Second.
4GOPRO_BURST_RATE_10_IN_3_SECOND10 Shots / 3 Second (Hero 4 Only).
5GOPRO_BURST_RATE_30_IN_1_SECOND30 Shots / 1 Second.
6GOPRO_BURST_RATE_30_IN_2_SECOND30 Shots / 2 Second.
7GOPRO_BURST_RATE_30_IN_3_SECOND30 Shots / 3 Second.
8GOPRO_BURST_RATE_30_IN_6_SECOND30 Shots / 6 Second.

LED_CONTROL_PATTERN

ValueField NameDescription
0LED_CONTROL_PATTERN_OFFLED patterns off (return control to regular vehicle control).
1LED_CONTROL_PATTERN_FIRMWAREUPDATELEDs show pattern during firmware update.
255LED_CONTROL_PATTERN_CUSTOMCustom Pattern using custom bytes fields.

EKF_STATUS_FLAGS

Flags in EKF_STATUS message.

ValueField NameDescription
1EKF_ATTITUDESet if EKF's attitude estimate is good.
2EKF_VELOCITY_HORIZSet if EKF's horizontal velocity estimate is good.
4EKF_VELOCITY_VERTSet if EKF's vertical velocity estimate is good.
8EKF_POS_HORIZ_RELSet if EKF's horizontal position (relative) estimate is good.
16EKF_POS_HORIZ_ABSSet if EKF's horizontal position (absolute) estimate is good.
32EKF_POS_VERT_ABSSet if EKF's vertical position (absolute) estimate is good.
64EKF_POS_VERT_AGLSet if EKF's vertical position (above ground) estimate is good.
128EKF_CONST_POS_MODEEKF is in constant position mode and does not know it's absolute or relative position.
256EKF_PRED_POS_HORIZ_RELSet if EKF's predicted horizontal position (relative) estimate is good.
512EKF_PRED_POS_HORIZ_ABSSet if EKF's predicted horizontal position (absolute) estimate is good.

PID_TUNING_AXIS

ValueField NameDescription
1PID_TUNING_ROLL
2PID_TUNING_PITCH
3PID_TUNING_YAW
4PID_TUNING_ACCZ
5PID_TUNING_STEER
6PID_TUNING_LANDING

MAG_CAL_STATUS

ValueField NameDescription
0MAG_CAL_NOT_STARTED
1MAG_CAL_WAITING_TO_START
2MAG_CAL_RUNNING_STEP_ONE
3MAG_CAL_RUNNING_STEP_TWO
4MAG_CAL_SUCCESS
5MAG_CAL_FAILED
6MAG_CAL_BAD_ORIENTATION

MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS

Special ACK block numbers control activation of dataflash log streaming.

ValueField NameDescription
2147483645MAV_REMOTE_LOG_DATA_BLOCK_STOPUAV to stop sending DataFlash blocks.
2147483646MAV_REMOTE_LOG_DATA_BLOCK_STARTUAV to start sending DataFlash blocks.

MAV_REMOTE_LOG_DATA_BLOCK_STATUSES

Possible remote log data block statuses.

ValueField NameDescription
0MAV_REMOTE_LOG_DATA_BLOCK_NACKThis block has NOT been received.
1MAV_REMOTE_LOG_DATA_BLOCK_ACKThis block has been received.

DEVICE_OP_BUSTYPE

Bus types for device operations.

ValueField NameDescription
0DEVICE_OP_BUSTYPE_I2CI2C Device operation.
1DEVICE_OP_BUSTYPE_SPISPI Device operation.

DEEPSTALL_STAGE

Deepstall flight stage.

ValueField NameDescription
0DEEPSTALL_STAGE_FLY_TO_LANDINGFlying to the landing point.
1DEEPSTALL_STAGE_ESTIMATE_WINDBuilding an estimate of the wind.
2DEEPSTALL_STAGE_WAIT_FOR_BREAKOUTWaiting to breakout of the loiter to fly the approach.
3DEEPSTALL_STAGE_FLY_TO_ARCFlying to the first arc point to turn around to the landing point.
4DEEPSTALL_STAGE_ARCTurning around back to the deepstall landing point.
5DEEPSTALL_STAGE_APPROACHApproaching the landing point.
6DEEPSTALL_STAGE_LANDStalling and steering towards the land point.

PLANE_MODE

A mapping of plane flight modes for custom_mode field of heartbeat.

ValueField NameDescription
0PLANE_MODE_MANUAL
1PLANE_MODE_CIRCLE
2PLANE_MODE_STABILIZE
3PLANE_MODE_TRAINING
4PLANE_MODE_ACRO
5PLANE_MODE_FLY_BY_WIRE_A
6PLANE_MODE_FLY_BY_WIRE_B
7PLANE_MODE_CRUISE
8PLANE_MODE_AUTOTUNE
10PLANE_MODE_AUTO
11PLANE_MODE_RTL
12PLANE_MODE_LOITER
14PLANE_MODE_AVOID_ADSB
15PLANE_MODE_GUIDED
16PLANE_MODE_INITIALIZING
17PLANE_MODE_QSTABILIZE
18PLANE_MODE_QHOVER
19PLANE_MODE_QLOITER
20PLANE_MODE_QLAND
21PLANE_MODE_QRTL

COPTER_MODE

A mapping of copter flight modes for custom_mode field of heartbeat.

ValueField NameDescription
0COPTER_MODE_STABILIZE
1COPTER_MODE_ACRO
2COPTER_MODE_ALT_HOLD
3COPTER_MODE_AUTO
4COPTER_MODE_GUIDED
5COPTER_MODE_LOITER
6COPTER_MODE_RTL
7COPTER_MODE_CIRCLE
9COPTER_MODE_LAND
11COPTER_MODE_DRIFT
13COPTER_MODE_SPORT
14COPTER_MODE_FLIP
15COPTER_MODE_AUTOTUNE
16COPTER_MODE_POSHOLD
17COPTER_MODE_BRAKE
18COPTER_MODE_THROW
19COPTER_MODE_AVOID_ADSB
20COPTER_MODE_GUIDED_NOGPS
21COPTER_MODE_SMART_RTL

SUB_MODE

A mapping of sub flight modes for custom_mode field of heartbeat.

ValueField NameDescription
0SUB_MODE_STABILIZE
1SUB_MODE_ACRO
2SUB_MODE_ALT_HOLD
3SUB_MODE_AUTO
4SUB_MODE_GUIDED
7SUB_MODE_CIRCLE
9SUB_MODE_SURFACE
16SUB_MODE_POSHOLD
19SUB_MODE_MANUAL

ROVER_MODE

A mapping of rover flight modes for custom_mode field of heartbeat.

ValueField NameDescription
0ROVER_MODE_MANUAL
1ROVER_MODE_ACRO
3ROVER_MODE_STEERING
4ROVER_MODE_HOLD
5ROVER_MODE_LOITER
10ROVER_MODE_AUTO
11ROVER_MODE_RTL
12ROVER_MODE_SMART_RTL
15ROVER_MODE_GUIDED
16ROVER_MODE_INITIALIZING

TRACKER_MODE

A mapping of antenna tracker flight modes for custom_mode field of heartbeat.

ValueField NameDescription
0TRACKER_MODE_MANUAL
1TRACKER_MODE_STOP
2TRACKER_MODE_SCAN
3TRACKER_MODE_SERVO_TEST
10TRACKER_MODE_AUTO
16TRACKER_MODE_INITIALIZING

MAV_CMD_DO_GRIPPER (211 )

Mission command to operate EPM gripper.

ParamDescription
1Gripper number (a number from 1 to max number of grippers on the vehicle).
2Gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum).
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_DO_AUTOTUNE_ENABLE (212 )

Enable/disable autotune.

ParamDescription
1Enable (1: enable, 0:disable).
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

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.

ParamDescription
1Altitude (m).
2Descent speed (m/s).
3Wiggle Time (s).
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_POWER_OFF_INITIATED (42000 )

A system wide power-off event has been initiated.

ParamDescription
1Empty.
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_SOLO_BTN_FLY_CLICK (42001 )

FLY button has been clicked.

ParamDescription
1Empty.
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_SOLO_BTN_FLY_HOLD (42002 )

FLY button has been held for 1.5 seconds.

ParamDescription
1Takeoff altitude.
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_SOLO_BTN_PAUSE_CLICK (42003 )

PAUSE button has been clicked.

ParamDescription
11 if Solo is in a shot mode, 0 otherwise.
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_FIXED_MAG_CAL (42004 )

Magnetometer calibration based on fixed position in earth field given by inclination, declination and intensity.

ParamDescription
1MagDeclinationDegrees.
2MagInclinationDegrees.
3MagIntensityMilliGauss.
4YawDegrees.
5Empty.
6Empty.
7Empty.

MAV_CMD_FIXED_MAG_CAL_FIELD (42005 )

Magnetometer calibration based on fixed expected field values in milliGauss.

ParamDescription
1FieldX.
2FieldY.
3FieldZ.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_DO_START_MAG_CAL (42424 )

Initiate a magnetometer calibration.

ParamDescription
1uint8_t bitmask of magnetometers (0 means all).
2Automatically retry on failure (0=no retry, 1=retry).
3Save without user input (0=require input, 1=autosave).
4Delay (seconds).
5Autoreboot (0=user reboot, 1=autoreboot).
6Empty.
7Empty.

MAV_CMD_DO_ACCEPT_MAG_CAL (42425 )

Initiate a magnetometer calibration.

ParamDescription
1uint8_t bitmask of magnetometers (0 means all).
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_DO_CANCEL_MAG_CAL (42426 )

Cancel a running magnetometer calibration.

ParamDescription
1uint8_t bitmask of magnetometers (0 means all).
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

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.

ParamDescription
1Position, one of the ACCELCAL_VEHICLE_POS enum values.
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_DO_SEND_BANNER (42428 )

Reply with the version banner.

ParamDescription
1Empty.
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_SET_FACTORY_TEST_MODE (42427 )

Command autopilot to get into factory test/diagnostic mode.

ParamDescription
10 means get out of test mode, 1 means get into test mode.
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_GIMBAL_RESET (42501 )

Causes the gimbal to reset and boot as if it was just powered on.

ParamDescription
1Empty.
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS (42502 )

Reports progress and success or failure of gimbal axis calibration procedure.

ParamDescription
1Gimbal axis we're reporting calibration progress for.
2Current calibration progress for this axis, 0x64=100%.
3Status of the calibration.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION (42503 )

Starts commutation calibration on the gimbal.

ParamDescription
1Empty.
2Empty.
3Empty.
4Empty.
5Empty.
6Empty.
7Empty.

MAV_CMD_GIMBAL_FULL_RESET (42505 )

Erases gimbal application and parameters.

ParamDescription
1Magic number.
2Magic number.
3Magic number.
4Magic number.
5Magic number.
6Magic number.
7Magic number.

MAV_CMD_DO_WINCH (42600 )

Command to operate winch.

ParamDescription
1Winch number (0 for the default winch, otherwise a number from 1 to max number of winches on the vehicle).
2Action (0=relax, 1=relative length control, 2=rate control. See WINCH_ACTIONS enum.).
3Release length (cable distance to unwind in meters, negative numbers to wind in cable).
4Release rate (meters/second).
5Empty.
6Empty.
7Empty.

MAV_CMD_FLASH_BOOTLOADER (42650 )

Update the bootloader

ParamDescription
1Empty
2Empty
3Empty
4Empty
5Magic number - set to 290876 to actually flash
6Empty
7Empty

SENSOR_OFFSETS ( #150 )

Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.

Field NameTypeUnitsDescription
mag_ofs_xint16_tMagnetometer X offset.
mag_ofs_yint16_tMagnetometer Y offset.
mag_ofs_zint16_tMagnetometer Z offset.
mag_declinationfloatradMagnetic declination.
raw_pressint32_tRaw pressure from barometer.
raw_tempint32_tRaw temperature from barometer.
gyro_cal_xfloatGyro X calibration.
gyro_cal_yfloatGyro Y calibration.
gyro_cal_zfloatGyro Z calibration.
accel_cal_xfloatAccel X calibration.
accel_cal_yfloatAccel Y calibration.
accel_cal_zfloatAccel Z calibration.

SET_MAG_OFFSETS ( #151 )

DEPRECATED: Replaced by MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS (2014-07).

Set the magnetometer offsets

Field NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
mag_ofs_xint16_tMagnetometer X offset.
mag_ofs_yint16_tMagnetometer Y offset.
mag_ofs_zint16_tMagnetometer Z offset.

MEMINFO ( #152 )

State of APM memory.

Field NameTypeUnitsDescription
brkvaluint16_tHeap top.
freememuint16_tbytesFree memory.
freemem32 **uint32_tbytesFree memory (32 bit).

AP_ADC ( #153 )

Raw ADC output.

Field NameTypeDescription
adc1uint16_tADC output 1.
adc2uint16_tADC output 2.
adc3uint16_tADC output 3.
adc4uint16_tADC output 4.
adc5uint16_tADC output 5.
adc6uint16_tADC output 6.

DIGICAM_CONFIGURE ( #154 )

Configure on-board Camera Control System.

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
modeuint8_tMode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
shutter_speeduint16_tDivisor number //e.g. 1000 means 1/1000 (0 means ignore).
apertureuint8_tF stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
isouint8_tISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
exposure_typeuint8_tExposure type enumeration from 1 to N (0 means ignore).
command_iduint8_tCommand Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
engine_cut_offuint8_tdsMain engine cut-off time before camera trigger (0 means no cut-off).
extra_paramuint8_tExtra parameters enumeration (0 means ignore).
extra_valuefloatCorrespondent value to given extra_param.

DIGICAM_CONTROL ( #155 )

Control on-board Camera Control System to take shots.

Field NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
sessionuint8_t0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
zoom_posuint8_t1 to N //Zoom's absolute position (0 means ignore).
zoom_stepint8_t-100 to 100 //Zooming step value to offset zoom from the current position.
focus_lockuint8_t0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
shotuint8_t0: ignore, 1: shot or start filming.
command_iduint8_tCommand Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
extra_paramuint8_tExtra parameters enumeration (0 means ignore).
extra_valuefloatCorrespondent value to given extra_param.

MOUNT_CONFIGURE ( #156 )

Message to configure a camera mount, directional antenna, etc.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
mount_modeuint8_tMAV_MOUNT_MODEMount operating mode.
stab_rolluint8_t(1 = yes, 0 = no).
stab_pitchuint8_t(1 = yes, 0 = no).
stab_yawuint8_t(1 = yes, 0 = no).

MOUNT_CONTROL ( #157 )

Message to control a camera mount, directional antenna, etc.

Field NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
input_aint32_tPitch (centi-degrees) or lat (degE7), depending on mount mode.
input_bint32_tRoll (centi-degrees) or lon (degE7) depending on mount mode.
input_cint32_tYaw (centi-degrees) or alt (cm) depending on mount mode.
save_positionuint8_tIf "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).

MOUNT_STATUS ( #158 )

Message with some status from APM to GCS about camera or antenna mount.

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
pointing_aint32_tcdegPitch.
pointing_bint32_tcdegRoll.
pointing_cint32_tcdegYaw.

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 NameTypeUnitsDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
idxuint8_tPoint index (first point is 1, 0 is for return point).
countuint8_tTotal number of points (for sanity checking).
latfloatdegLatitude of point.
lngfloatdegLongitude of point.

FENCE_FETCH_POINT ( #161 )

Request a current fence point from MAV.

Field NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
idxuint8_tPoint index (first point is 1, 0 is for return point).

FENCE_STATUS ( #162 )

Status of geo-fencing. Sent in extended status stream when fencing enabled.

Field NameTypeUnitsValuesDescription
breach_statusuint8_tBreach status (0 if currently inside fence, 1 if outside).
breach_countuint16_tNumber of fence breaches.
breach_typeuint8_tFENCE_BREACHLast breach type.
breach_timeuint32_tmsTime (since boot) of last breach.

AHRS ( #163 )

Status of DCM attitude estimator.

Field NameTypeUnitsDescription
omegaIxfloatrad/sX gyro drift estimate.
omegaIyfloatrad/sY gyro drift estimate.
omegaIzfloatrad/sZ gyro drift estimate.
accel_weightfloatAverage accel_weight.
renorm_valfloatAverage renormalisation value.
error_rpfloatAverage error_roll_pitch value.
error_yawfloatAverage error_yaw value.

SIMSTATE ( #164 )

Status of simulation environment, if used.

Field NameTypeUnitsDescription
rollfloatradRoll angle.
pitchfloatradPitch angle.
yawfloatradYaw angle.
xaccfloatm/s/sX acceleration.
yaccfloatm/s/sY acceleration.
zaccfloatm/s/sZ acceleration.
xgyrofloatrad/sAngular speed around X axis.
ygyrofloatrad/sAngular speed around Y axis.
zgyrofloatrad/sAngular speed around Z axis.
latint32_tdegE7Latitude.
lngint32_tdegE7Longitude.

HWSTATUS ( #165 )

Status of key hardware.

Field NameTypeUnitsDescription
Vccuint16_tmVBoard voltage.
I2Cerruint8_tI2C error count.

RADIO ( #166 )

Status generated by radio.

Field NameTypeUnitsDescription
rssiuint8_tLocal signal strength.
remrssiuint8_tRemote signal strength.
txbufuint8_t%How full the tx buffer is.
noiseuint8_tBackground noise level.
remnoiseuint8_tRemote background noise level.
rxerrorsuint16_tReceive errors.
fixeduint16_tCount of error corrected packets.

LIMITS_STATUS ( #167 )

Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled.

Field NameTypeUnitsValuesDescription
limits_stateuint8_tLIMITS_STATEState of AP_Limits.
last_triggeruint32_tmsTime (since boot) of last breach.
last_actionuint32_tmsTime (since boot) of last recovery action.
last_recoveryuint32_tmsTime (since boot) of last successful recovery.
last_clearuint32_tmsTime (since boot) of last all-clear.
breach_countuint16_tNumber of fence breaches.
mods_enableduint8_tLIMIT_MODULEAP_Limit_Module bitfield of enabled modules.
mods_requireduint8_tLIMIT_MODULEAP_Limit_Module bitfield of required modules.
mods_triggereduint8_tLIMIT_MODULEAP_Limit_Module bitfield of triggered modules.

WIND ( #168 )

Wind estimation.

Field NameTypeUnitsDescription
directionfloatdegWind direction (that wind is coming from).
speedfloatm/sWind speed in ground plane.
speed_zfloatm/sVertical wind speed.

DATA16 ( #169 )

Data packet, size 16.

Field NameTypeUnitsDescription
typeuint8_tData type.
lenuint8_tbytesData length.
datauint8_t[16]Raw data.

DATA32 ( #170 )

Data packet, size 32.

Field NameTypeUnitsDescription
typeuint8_tData type.
lenuint8_tbytesData length.
datauint8_t[32]Raw data.

DATA64 ( #171 )

Data packet, size 64.

Field NameTypeUnitsDescription
typeuint8_tData type.
lenuint8_tbytesData length.
datauint8_t[64]Raw data.

DATA96 ( #172 )

Data packet, size 96.

Field NameTypeUnitsDescription
typeuint8_tData type.
lenuint8_tbytesData length.
datauint8_t[96]Raw data.

RANGEFINDER ( #173 )

Rangefinder reporting.

Field NameTypeUnitsDescription
distancefloatmDistance.
voltagefloatVRaw voltage if available, zero otherwise.

AIRSPEED_AUTOCAL ( #174 )

Airspeed auto-calibration.

Field NameTypeUnitsDescription
vxfloatm/sGPS velocity north.
vyfloatm/sGPS velocity east.
vzfloatm/sGPS velocity down.
diff_pressurefloatPaDifferential pressure.
EAS2TASfloatEstimated to true airspeed ratio.
ratiofloatAirspeed ratio.
state_xfloatEKF state x.
state_yfloatEKF state y.
state_zfloatEKF state z.
PaxfloatEKF Pax.
PbyfloatEKF Pby.
PczfloatEKF 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 NameTypeUnitsValuesDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
idxuint8_tPoint index (first point is 0).
countuint8_tTotal number of points (for sanity checking).
latint32_tdegE7Latitude of point.
lngint32_tdegE7Longitude of point.
altint16_tmTransit / loiter altitude relative to home.
break_altint16_tmBreak altitude relative to home.
land_diruint16_tcdegHeading to aim for when landing.
flagsuint8_tRALLY_FLAGSConfiguration 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 NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
idxuint8_tPoint index (first point is 0).

COMPASSMOT_STATUS ( #177 )

Status of compassmot calibration.

Field NameTypeUnitsDescription
throttleuint16_td%Throttle.
currentfloatACurrent.
interferenceuint16_t%Interference.
CompensationXfloatMotor Compensation X.
CompensationYfloatMotor Compensation Y.
CompensationZfloatMotor Compensation Z.

AHRS2 ( #178 )

Status of secondary AHRS filter if available.

Field NameTypeUnitsDescription
rollfloatradRoll angle.
pitchfloatradPitch angle.
yawfloatradYaw angle.
altitudefloatmAltitude (MSL).
latint32_tdegE7Latitude.
lngint32_tdegE7Longitude.

CAMERA_STATUS ( #179 )

Camera Event.

Field NameTypeUnitsValuesDescription
time_usecuint64_tusImage timestamp (since UNIX epoch, according to camera clock).
target_systemuint8_tSystem ID.
cam_idxuint8_tCamera ID.
img_idxuint16_tImage index.
event_iduint8_tCAMERA_STATUS_TYPESEvent type.
p1floatParameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
p2floatParameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
p3floatParameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
p4floatParameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).

CAMERA_FEEDBACK ( #180 )

Camera Capture Feedback.

Field NameTypeUnitsValuesDescription
time_usecuint64_tusImage timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
target_systemuint8_tSystem ID.
cam_idxuint8_tCamera ID.
img_idxuint16_tImage index.
latint32_tdegE7Latitude.
lngint32_tdegE7Longitude.
alt_mslfloatmAltitude (MSL).
alt_relfloatmAltitude (Relative to HOME location).
rollfloatdegCamera Roll angle (earth frame, +-180).
pitchfloatdegCamera Pitch angle (earth frame, +-180).
yawfloatdegCamera Yaw (earth frame, 0-360, true).
foc_lenfloatmmFocal Length.
flagsuint8_tCAMERA_FEEDBACK_FLAGSFeedback flags.
completed_captures **uint16_tCompleted image captures.

BATTERY2 ( #181 )

DEPRECATED: Replaced by BATTERY_STATUS (2017-04).

2nd Battery status

Field NameTypeUnitsDescription
voltageuint16_tmVVoltage.
current_batteryint16_tcABattery 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 NameTypeUnitsDescription
rollfloatradRoll angle.
pitchfloatradPitch angle.
yawfloatradYaw angle.
altitudefloatmAltitude (MSL).
latint32_tdegE7Latitude.
lngint32_tdegE7Longitude.
v1floatTest variable1.
v2floatTest variable2.
v3floatTest variable3.
v4floatTest variable4.

AUTOPILOT_VERSION_REQUEST ( #183 )

Request the autopilot version from the system/component.

Field NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.

REMOTE_LOG_DATA_BLOCK ( #184 )

Send a block of log data to remote location.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
seqnouint32_tMAV_REMOTE_LOG_DATA_BLOCK_COMMANDSLog data block sequence number.
datauint8_t[200]Log data block.

REMOTE_LOG_BLOCK_STATUS ( #185 )

Send Status of each log block that autopilot board might have sent.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
seqnouint32_tLog data block sequence number.
statusuint8_tMAV_REMOTE_LOG_DATA_BLOCK_STATUSESLog data block status.

LED_CONTROL ( #186 )

Control vehicle LEDs.

Field NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
instanceuint8_tInstance (LED instance to control or 255 for all LEDs).
patternuint8_tPattern (see LED_PATTERN_ENUM).
custom_lenuint8_tCustom Byte Length.
custom_bytesuint8_t[24]Custom Bytes.

MAG_CAL_PROGRESS ( #191 )

Reports progress of compass calibration.

Field NameTypeUnitsValuesDescription
compass_iduint8_tCompass being calibrated.
cal_maskuint8_tBitmask of compasses being calibrated.
cal_statusuint8_tMAG_CAL_STATUSCalibration Status.
attemptuint8_tAttempt number.
completion_pctuint8_t%Completion percentage.
completion_maskuint8_t[10]Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
direction_xfloatBody frame direction vector for display.
direction_yfloatBody frame direction vector for display.
direction_zfloatBody frame direction vector for display.

MAG_CAL_REPORT ( #192 )

Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.

Field NameTypeUnitsValuesDescription
compass_iduint8_tCompass being calibrated.
cal_maskuint8_tBitmask of compasses being calibrated.
cal_statusuint8_tMAG_CAL_STATUSCalibration Status.
autosaveduint8_t0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
fitnessfloatmgaussRMS milligauss residuals.
ofs_xfloatX offset.
ofs_yfloatY offset.
ofs_zfloatZ offset.
diag_xfloatX diagonal (matrix 11).
diag_yfloatY diagonal (matrix 22).
diag_zfloatZ diagonal (matrix 33).
offdiag_xfloatX off-diagonal (matrix 12 and 21).
offdiag_yfloatY off-diagonal (matrix 13 and 31).
offdiag_zfloatZ off-diagonal (matrix 32 and 23).
orientation_confidence **floatConfidence in orientation (higher is better).
old_orientation **uint8_tMAV_SENSOR_ORIENTATIONorientation before calibration.
new_orientation **uint8_tMAV_SENSOR_ORIENTATIONorientation after calibration.

EKF_STATUS_REPORT ( #193 )

EKF Status message including flags and variances.

Field NameTypeValuesDescription
flagsuint16_tEKF_STATUS_FLAGSFlags.
velocity_variancefloatVelocity variance.
pos_horiz_variancefloatHorizontal Position variance.
pos_vert_variancefloatVertical Position variance.
compass_variancefloatCompass variance.
terrain_alt_variancefloatTerrain Altitude variance.
airspeed_variance **floatAirspeed variance.

PID_TUNING ( #194 )

PID tuning information.

Field NameTypeUnitsValuesDescription
axisuint8_tPID_TUNING_AXISAxis.
desiredfloatdeg/sDesired rate.
achievedfloatdeg/sAchieved rate.
FFfloatFF component.
PfloatP component.
IfloatI component.
DfloatD component.

DEEPSTALL ( #195 )

Deepstall path planning.

Field NameTypeUnitsValuesDescription
landing_latint32_tdegE7Landing latitude.
landing_lonint32_tdegE7Landing longitude.
path_latint32_tdegE7Final heading start point, latitude.
path_lonint32_tdegE7Final heading start point, longitude.
arc_entry_latint32_tdegE7Arc entry point, latitude.
arc_entry_lonint32_tdegE7Arc entry point, longitude.
altitudefloatmAltitude.
expected_travel_distancefloatmDistance the aircraft expects to travel during the deepstall.
cross_track_errorfloatmDeepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
stageuint8_tDEEPSTALL_STAGEDeepstall stage.

GIMBAL_REPORT ( #200 )

3 axis gimbal measurements.

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
delta_timefloatsTime since last update.
delta_angle_xfloatradDelta angle X.
delta_angle_yfloatradDelta angle Y.
delta_angle_zfloatradDelta angle X.
delta_velocity_xfloatm/sDelta velocity X.
delta_velocity_yfloatm/sDelta velocity Y.
delta_velocity_zfloatm/sDelta velocity Z.
joint_rollfloatradJoint ROLL.
joint_elfloatradJoint EL.
joint_azfloatradJoint AZ.

GIMBAL_CONTROL ( #201 )

Control message for rate gimbal.

Field NameTypeUnitsDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
demanded_rate_xfloatrad/sDemanded angular rate X.
demanded_rate_yfloatrad/sDemanded angular rate Y.
demanded_rate_zfloatrad/sDemanded angular rate Z.

GIMBAL_TORQUE_CMD_REPORT ( #214 )

100 Hz gimbal torque command telemetry.

Field NameTypeDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
rl_torque_cmdint16_tRoll Torque Command.
el_torque_cmdint16_tElevation Torque Command.
az_torque_cmdint16_tAzimuth Torque Command.

GOPRO_HEARTBEAT ( #215 )

Heartbeat from a HeroBus attached GoPro.

Field NameTypeValuesDescription
statusuint8_tGOPRO_HEARTBEAT_STATUSStatus.
capture_modeuint8_tGOPRO_CAPTURE_MODECurrent capture mode.
flagsuint8_tGOPRO_HEARTBEAT_FLAGSAdditional status bits.

GOPRO_GET_REQUEST ( #216 )

Request a GOPRO_COMMAND response from the GoPro.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
cmd_iduint8_tGOPRO_COMMANDCommand ID.

GOPRO_GET_RESPONSE ( #217 )

Response from a GOPRO_COMMAND get request.

Field NameTypeValuesDescription
cmd_iduint8_tGOPRO_COMMANDCommand ID.
statusuint8_tGOPRO_REQUEST_STATUSStatus.
valueuint8_t[4]Value.

GOPRO_SET_REQUEST ( #218 )

Request to set a GOPRO_COMMAND with a desired.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
cmd_iduint8_tGOPRO_COMMANDCommand ID.
valueuint8_t[4]Value.

GOPRO_SET_RESPONSE ( #219 )

Response from a GOPRO_COMMAND set request.

Field NameTypeValuesDescription
cmd_iduint8_tGOPRO_COMMANDCommand ID.
statusuint8_tGOPRO_REQUEST_STATUSStatus.

RPM ( #226 )

RPM sensor output.

Field NameTypeDescription
rpm1floatRPM Sensor1.
rpm2floatRPM Sensor2.

DEVICE_OP_READ ( #11000 )

(MAVLink 2) Read registers for a device.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
request_iduint32_tRequest ID - copied to reply.
bustypeuint8_tDEVICE_OP_BUSTYPEThe bus type.
busuint8_tBus number.
addressuint8_tBus address.
busnamechar[40]Name of device on bus (for SPI).
regstartuint8_tFirst register to read.
countuint8_tCount of registers to read.

DEVICE_OP_READ_REPLY ( #11001 )

(MAVLink 2) Read registers reply.

Field NameTypeDescription
request_iduint32_tRequest ID - copied from request.
resultuint8_t0 for success, anything else is failure code.
regstartuint8_tStarting register.
countuint8_tCount of bytes read.
datauint8_t[128]Reply data.

DEVICE_OP_WRITE ( #11002 )

(MAVLink 2) Write registers for a device.

Field NameTypeValuesDescription
target_systemuint8_tSystem ID.
target_componentuint8_tComponent ID.
request_iduint32_tRequest ID - copied to reply.
bustypeuint8_tDEVICE_OP_BUSTYPEThe bus type.
busuint8_tBus number.
addressuint8_tBus address.
busnamechar[40]Name of device on bus (for SPI).
regstartuint8_tFirst register to write.
countuint8_tCount of registers to write.
datauint8_t[128]Write data.

DEVICE_OP_WRITE_REPLY ( #11003 )

(MAVLink 2) Write registers reply.

Field NameTypeDescription
request_iduint32_tRequest ID - copied from request.
resultuint8_t0 for success, anything else is failure code.

ADAP_TUNING ( #11010 )

(MAVLink 2) Adaptive Controller tuning information.

Field NameTypeUnitsValuesDescription
axisuint8_tPID_TUNING_AXISAxis.
desiredfloatdeg/sDesired rate.
achievedfloatdeg/sAchieved rate.
errorfloatError between model and vehicle.
thetafloatTheta estimated state predictor.
omegafloatOmega estimated state predictor.
sigmafloatSigma estimated state predictor.
theta_dotfloatTheta derivative.
omega_dotfloatOmega derivative.
sigma_dotfloatSigma derivative.
ffloatProjection operator value.
f_dotfloatProjection operator derivative.
ufloatu adaptive controlled output command.

VISION_POSITION_DELTA ( #11011 )

(MAVLink 2) Camera vision based attitude and position deltas.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (synced to UNIX time or since system boot).
time_delta_usecuint64_tusTime since the last reported camera frame.
angle_deltafloat[3]Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation.
position_deltafloat[3]mChange in position from previous to current frame rotated into body frame (0=forward, 1=right, 2=down).
confidencefloat%Normalised confidence value from 0 to 100.

AOA_SSA ( #11020 )

(MAVLink 2) Angle of Attack and Side Slip Angle.

Field NameTypeUnitsDescription
time_usecuint64_tusTimestamp (since boot or Unix epoch).
AOAfloatdegAngle of Attack.
SSAfloatdegSide Slip Angle.

ESC_TELEMETRY_1_TO_4 ( #11030 )

(MAVLink 2) ESC Telemetry Data for ESCs 1 to 4, matching data sent by BLHeli ESCs.

Field NameTypeUnitsDescription
temperatureuint8_t[4]degCTemperature.
voltageuint16_t[4]cVVoltage.
currentuint16_t[4]cACurrent.
totalcurrentuint16_t[4]mAhTotal current.
rpmuint16_t[4]rpmRPM (eRPM).
countuint16_t[4]count of telemetry packets received (wraps at 65535).

ESC_TELEMETRY_5_TO_8 ( #11031 )

(MAVLink 2) ESC Telemetry Data for ESCs 5 to 8, matching data sent by BLHeli ESCs.

Field NameTypeUnitsDescription
temperatureuint8_t[4]degCTemperature.
voltageuint16_t[4]cVVoltage.
currentuint16_t[4]cACurrent.
totalcurrentuint16_t[4]mAhTotal current.
rpmuint16_t[4]rpmRPM (eRPM).
countuint16_t[4]count of telemetry packets received (wraps at 65535).

ESC_TELEMETRY_9_TO_12 ( #11032 )

(MAVLink 2) ESC Telemetry Data for ESCs 9 to 12, matching data sent by BLHeli ESCs.

Field NameTypeUnitsDescription
temperatureuint8_t[4]degCTemperature.
voltageuint16_t[4]cVVoltage.
currentuint16_t[4]cACurrent.
totalcurrentuint16_t[4]mAhTotal current.
rpmuint16_t[4]rpmRPM (eRPM).
countuint16_t[4]count of telemetry packets received (wraps at 65535).

results matching ""

    No results matching ""