MAVLINK ArduPilotMega Message Set
These messages define the APM 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.
MAVLink Type Enumerations
ACCELCAL_VEHICLE_POS
CMD ID | Field Name | Description |
---|---|---|
1 | ACCELCAL_VEHICLE_POS_LEVEL | |
2 | ACCELCAL_VEHICLE_POS_LEFT | |
3 | ACCELCAL_VEHICLE_POS_RIGHT | |
4 | ACCELCAL_VEHICLE_POS_NOSEDOWN | |
5 | ACCELCAL_VEHICLE_POS_NOSEUP | |
6 | ACCELCAL_VEHICLE_POS_BACK | |
16777215 | ACCELCAL_VEHICLE_POS_SUCCESS | |
16777216 | ACCELCAL_VEHICLE_POS_FAILED |
MAV_CMD
CMD ID | Field Name | Description |
---|---|---|
211 | MAV_CMD_DO_GRIPPER | Mission command to operate EPM gripper |
Mission Param #1 | gripper number (a number from 1 to max number of grippers on the vehicle) | |
Mission Param #2 | gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum) | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
212 | MAV_CMD_DO_AUTOTUNE_ENABLE | Enable/disable autotune |
Mission Param #1 | enable (1: enable, 0:disable) | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
83 | MAV_CMD_NAV_ALTITUDE_WAIT | 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. |
Mission Param #1 | altitude (m) | |
Mission Param #2 | descent speed (m/s) | |
Mission Param #3 | Wiggle Time (s) | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42000 | MAV_CMD_POWER_OFF_INITIATED | A system wide power-off event has been initiated. |
Mission Param #1 | Empty | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42001 | MAV_CMD_SOLO_BTN_FLY_CLICK | FLY button has been clicked. |
Mission Param #1 | Empty | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42002 | MAV_CMD_SOLO_BTN_FLY_HOLD | FLY button has been held for 1.5 seconds. |
Mission Param #1 | Takeoff altitude | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42003 | MAV_CMD_SOLO_BTN_PAUSE_CLICK | PAUSE button has been clicked. |
Mission Param #1 | 1 if Solo is in a shot mode, 0 otherwise | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42004 | MAV_CMD_FIXED_MAG_CAL | Magnetometer calibration based on fixed position in earth field given by inclination, declination and intensity |
Mission Param #1 | MagDeclinationDegrees | |
Mission Param #2 | MagInclinationDegrees | |
Mission Param #3 | MagIntensityMilliGauss | |
Mission Param #4 | YawDegrees | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42005 | MAV_CMD_FIXED_MAG_CAL_FIELD | Magnetometer calibration based on fixed expected field values in milliGauss |
Mission Param #1 | FieldX | |
Mission Param #2 | FieldY | |
Mission Param #3 | FieldZ | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42424 | MAV_CMD_DO_START_MAG_CAL | Initiate a magnetometer calibration |
Mission Param #1 | uint8_t bitmask of magnetometers (0 means all) | |
Mission Param #2 | Automatically retry on failure (0=no retry, 1=retry). | |
Mission Param #3 | Save without user input (0=require input, 1=autosave). | |
Mission Param #4 | Delay (seconds) | |
Mission Param #5 | Autoreboot (0=user reboot, 1=autoreboot) | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42425 | MAV_CMD_DO_ACCEPT_MAG_CAL | Initiate a magnetometer calibration |
Mission Param #1 | uint8_t bitmask of magnetometers (0 means all) | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42426 | MAV_CMD_DO_CANCEL_MAG_CAL | Cancel a running magnetometer calibration |
Mission Param #1 | uint8_t bitmask of magnetometers (0 means all) | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42429 | MAV_CMD_ACCELCAL_VEHICLE_POS | 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. |
Mission Param #1 | Position, one of the ACCELCAL_VEHICLE_POS enum values | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42428 | MAV_CMD_DO_SEND_BANNER | Reply with the version banner |
Mission Param #1 | Empty | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42427 | MAV_CMD_SET_FACTORY_TEST_MODE | Command autopilot to get into factory test/diagnostic mode |
Mission Param #1 | 0 means get out of test mode, 1 means get into test mode | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42501 | MAV_CMD_GIMBAL_RESET | Causes the gimbal to reset and boot as if it was just powered on |
Mission Param #1 | Empty | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42502 | MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS | Reports progress and success or failure of gimbal axis calibration procedure |
Mission Param #1 | Gimbal axis we're reporting calibration progress for | |
Mission Param #2 | Current calibration progress for this axis, 0x64=100% | |
Mission Param #3 | Status of the calibration | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42503 | MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION | Starts commutation calibration on the gimbal |
Mission Param #1 | Empty | |
Mission Param #2 | Empty | |
Mission Param #3 | Empty | |
Mission Param #4 | Empty | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
||
42505 | MAV_CMD_GIMBAL_FULL_RESET | Erases gimbal application and parameters |
Mission Param #1 | Magic number | |
Mission Param #2 | Magic number | |
Mission Param #3 | Magic number | |
Mission Param #4 | Magic number | |
Mission Param #5 | Magic number | |
Mission Param #6 | Magic number | |
Mission Param #7 | Magic number | |
|
||
42600 | MAV_CMD_DO_WINCH | Command to operate winch |
Mission Param #1 | winch number (0 for the default winch, otherwise a number from 1 to max number of winches on the vehicle) | |
Mission Param #2 | action (0=relax, 1=relative length control, 2=rate control. See WINCH_ACTIONS enum) | |
Mission Param #3 | release length (cable distance to unwind in meters, negative numbers to wind in cable) | |
Mission Param #4 | release rate (meters/second) | |
Mission Param #5 | Empty | |
Mission Param #6 | Empty | |
Mission Param #7 | Empty | |
|
LIMITS_STATE
CMD ID | Field Name | Description |
---|---|---|
0 | LIMITS_INIT | pre-initialization |
1 | LIMITS_DISABLED | disabled |
2 | LIMITS_ENABLED | checking limits |
3 | LIMITS_TRIGGERED | a limit has been breached |
4 | LIMITS_RECOVERING | taking action eg. RTL |
5 | LIMITS_RECOVERED | we're no longer in breach of a limit |
LIMIT_MODULE
CMD ID | Field Name | Description |
---|---|---|
1 | LIMIT_GPSLOCK | pre-initialization |
2 | LIMIT_GEOFENCE | disabled |
4 | LIMIT_ALTITUDE | checking limits |
RALLY_FLAGS
Flags in RALLY_POINT message
CMD ID | 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. |
PARACHUTE_ACTION
CMD ID | Field Name | Description |
---|---|---|
0 | PARACHUTE_DISABLE | Disable parachute release |
1 | PARACHUTE_ENABLE | Enable parachute release |
2 | PARACHUTE_RELEASE | Release parachute |
GRIPPER_ACTIONS
Gripper actions.
CMD ID | Field Name | Description |
---|---|---|
0 | GRIPPER_ACTION_RELEASE | gripper release of cargo |
1 | GRIPPER_ACTION_GRAB | gripper grabs onto cargo |
WINCH_ACTIONS
Winch actions
CMD ID | Field Name | Description |
---|---|---|
0 | WINCH_RELAXED | relax winch |
1 | WINCH_RELATIVE_LENGTH_CONTROL | winch unwinds or winds specified length of cable optionally using specified rate |
2 | WINCH_RATE_CONTROL | winch unwinds or winds cable at specified rate in meters/seconds |
CAMERA_STATUS_TYPES
CMD ID | Field Name | Description |
---|---|---|
0 | CAMERA_STATUS_TYPE_HEARTBEAT | Camera heartbeat, announce camera component ID at 1hz |
1 | CAMERA_STATUS_TYPE_TRIGGER | Camera image triggered |
2 | CAMERA_STATUS_TYPE_DISCONNECT | Camera connection lost |
3 | CAMERA_STATUS_TYPE_ERROR | Camera unknown error |
4 | CAMERA_STATUS_TYPE_LOWBATT | Camera battery low. Parameter p1 shows reported voltage |
5 | CAMERA_STATUS_TYPE_LOWSTORE | Camera storage low. Parameter p1 shows reported shots remaining |
6 | CAMERA_STATUS_TYPE_LOWSTOREV | Camera storage low. Parameter p1 shows reported video minutes remaining |
CAMERA_FEEDBACK_FLAGS
CMD ID | Field Name | Description |
---|---|---|
0 | CAMERA_FEEDBACK_PHOTO | Shooting photos, not video |
1 | CAMERA_FEEDBACK_VIDEO | Shooting video, not stills |
2 | CAMERA_FEEDBACK_BADEXPOSURE | Unable to achieve requested exposure (e.g. shutter speed too low) |
3 | CAMERA_FEEDBACK_CLOSEDLOOP | Closed loop feedback from camera, we know for sure it has successfully taken a picture |
4 | CAMERA_FEEDBACK_OPENLOOP | Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture |
MAV_MODE_GIMBAL
CMD ID | Field Name | Description |
---|---|---|
0 | MAV_MODE_GIMBAL_UNINITIALIZED | Gimbal is powered on but has not started initializing yet |
1 | MAV_MODE_GIMBAL_CALIBRATING_PITCH | Gimbal is currently running calibration on the pitch axis |
2 | MAV_MODE_GIMBAL_CALIBRATING_ROLL | Gimbal is currently running calibration on the roll axis |
3 | MAV_MODE_GIMBAL_CALIBRATING_YAW | Gimbal is currently running calibration on the yaw axis |
4 | MAV_MODE_GIMBAL_INITIALIZED | Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter |
5 | MAV_MODE_GIMBAL_ACTIVE | Gimbal is actively stabilizing |
6 | MAV_MODE_GIMBAL_RATE_CMD_TIMEOUT | Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command |
GIMBAL_AXIS
CMD ID | Field Name | Description |
---|---|---|
0 | GIMBAL_AXIS_YAW | Gimbal yaw axis |
1 | GIMBAL_AXIS_PITCH | Gimbal pitch axis |
2 | GIMBAL_AXIS_ROLL | Gimbal roll axis |
GIMBAL_AXIS_CALIBRATION_STATUS
CMD ID | Field Name | Description |
---|---|---|
0 | GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS | Axis calibration is in progress |
1 | GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED | Axis calibration succeeded |
2 | GIMBAL_AXIS_CALIBRATION_STATUS_FAILED | Axis calibration failed |
GIMBAL_AXIS_CALIBRATION_REQUIRED
CMD ID | Field Name | Description |
---|---|---|
0 | GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN | Whether or not this axis requires calibration is unknown at this time |
1 | GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE | This axis requires calibration |
2 | GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE | This axis does not require calibration |
GOPRO_HEARTBEAT_STATUS
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_HEARTBEAT_STATUS_DISCONNECTED | No GoPro connected |
1 | GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE | The detected GoPro is not HeroBus compatible |
2 | GOPRO_HEARTBEAT_STATUS_CONNECTED | A HeroBus compatible GoPro is connected |
3 | GOPRO_HEARTBEAT_STATUS_ERROR | An unrecoverable error was encountered with the connected GoPro, it may require a power cycle |
GOPRO_HEARTBEAT_FLAGS
CMD ID | Field Name | Description |
---|---|---|
1 | GOPRO_FLAG_RECORDING | GoPro is currently recording |
GOPRO_REQUEST_STATUS
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_REQUEST_SUCCESS | The write message with ID indicated succeeded |
1 | GOPRO_REQUEST_FAILED | The write message with ID indicated failed |
GOPRO_COMMAND
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_COMMAND_POWER | (Get/Set) |
1 | GOPRO_COMMAND_CAPTURE_MODE | (Get/Set) |
2 | GOPRO_COMMAND_SHUTTER | (___/Set) |
3 | GOPRO_COMMAND_BATTERY | (Get/___) |
4 | GOPRO_COMMAND_MODEL | (Get/___) |
5 | GOPRO_COMMAND_VIDEO_SETTINGS | (Get/Set) |
6 | GOPRO_COMMAND_LOW_LIGHT | (Get/Set) |
7 | GOPRO_COMMAND_PHOTO_RESOLUTION | (Get/Set) |
8 | GOPRO_COMMAND_PHOTO_BURST_RATE | (Get/Set) |
9 | GOPRO_COMMAND_PROTUNE | (Get/Set) |
10 | GOPRO_COMMAND_PROTUNE_WHITE_BALANCE | (Get/Set) Hero 3+ Only |
11 | GOPRO_COMMAND_PROTUNE_COLOUR | (Get/Set) Hero 3+ Only |
12 | GOPRO_COMMAND_PROTUNE_GAIN | (Get/Set) Hero 3+ Only |
13 | GOPRO_COMMAND_PROTUNE_SHARPNESS | (Get/Set) Hero 3+ Only |
14 | GOPRO_COMMAND_PROTUNE_EXPOSURE | (Get/Set) Hero 3+ Only |
15 | GOPRO_COMMAND_TIME | (Get/Set) |
16 | GOPRO_COMMAND_CHARGING | (Get/Set) |
GOPRO_CAPTURE_MODE
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_CAPTURE_MODE_VIDEO | Video mode |
1 | GOPRO_CAPTURE_MODE_PHOTO | Photo mode |
2 | GOPRO_CAPTURE_MODE_BURST | Burst mode, hero 3+ only |
3 | GOPRO_CAPTURE_MODE_TIME_LAPSE | Time lapse mode, hero 3+ only |
4 | GOPRO_CAPTURE_MODE_MULTI_SHOT | Multi shot mode, hero 4 only |
5 | GOPRO_CAPTURE_MODE_PLAYBACK | Playback mode, hero 4 only, silver only except when LCD or HDMI is connected to black |
6 | GOPRO_CAPTURE_MODE_SETUP | Playback mode, hero 4 only |
255 | GOPRO_CAPTURE_MODE_UNKNOWN | Mode not yet known |
GOPRO_RESOLUTION
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_RESOLUTION_480p | 848 x 480 (480p) |
1 | GOPRO_RESOLUTION_720p | 1280 x 720 (720p) |
2 | GOPRO_RESOLUTION_960p | 1280 x 960 (960p) |
3 | GOPRO_RESOLUTION_1080p | 1920 x 1080 (1080p) |
4 | GOPRO_RESOLUTION_1440p | 1920 x 1440 (1440p) |
5 | GOPRO_RESOLUTION_2_7k_17_9 | 2704 x 1440 (2.7k-17:9) |
6 | GOPRO_RESOLUTION_2_7k_16_9 | 2704 x 1524 (2.7k-16:9) |
7 | GOPRO_RESOLUTION_2_7k_4_3 | 2704 x 2028 (2.7k-4:3) |
8 | GOPRO_RESOLUTION_4k_16_9 | 3840 x 2160 (4k-16:9) |
9 | GOPRO_RESOLUTION_4k_17_9 | 4096 x 2160 (4k-17:9) |
10 | GOPRO_RESOLUTION_720p_SUPERVIEW | 1280 x 720 (720p-SuperView) |
11 | GOPRO_RESOLUTION_1080p_SUPERVIEW | 1920 x 1080 (1080p-SuperView) |
12 | GOPRO_RESOLUTION_2_7k_SUPERVIEW | 2704 x 1520 (2.7k-SuperView) |
13 | GOPRO_RESOLUTION_4k_SUPERVIEW | 3840 x 2160 (4k-SuperView) |
GOPRO_FRAME_RATE
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_FRAME_RATE_12 | 12 FPS |
1 | GOPRO_FRAME_RATE_15 | 15 FPS |
2 | GOPRO_FRAME_RATE_24 | 24 FPS |
3 | GOPRO_FRAME_RATE_25 | 25 FPS |
4 | GOPRO_FRAME_RATE_30 | 30 FPS |
5 | GOPRO_FRAME_RATE_48 | 48 FPS |
6 | GOPRO_FRAME_RATE_50 | 50 FPS |
7 | GOPRO_FRAME_RATE_60 | 60 FPS |
8 | GOPRO_FRAME_RATE_80 | 80 FPS |
9 | GOPRO_FRAME_RATE_90 | 90 FPS |
10 | GOPRO_FRAME_RATE_100 | 100 FPS |
11 | GOPRO_FRAME_RATE_120 | 120 FPS |
12 | GOPRO_FRAME_RATE_240 | 240 FPS |
13 | GOPRO_FRAME_RATE_12_5 | 12.5 FPS |
GOPRO_FIELD_OF_VIEW
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_FIELD_OF_VIEW_WIDE | 0x00: Wide |
1 | GOPRO_FIELD_OF_VIEW_MEDIUM | 0x01: Medium |
2 | GOPRO_FIELD_OF_VIEW_NARROW | 0x02: Narrow |
GOPRO_VIDEO_SETTINGS_FLAGS
CMD ID | Field Name | Description |
---|---|---|
1 | GOPRO_VIDEO_SETTINGS_TV_MODE | 0=NTSC, 1=PAL |
GOPRO_PHOTO_RESOLUTION
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM | 5MP Medium |
1 | GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM | 7MP Medium |
2 | GOPRO_PHOTO_RESOLUTION_7MP_WIDE | 7MP Wide |
3 | GOPRO_PHOTO_RESOLUTION_10MP_WIDE | 10MP Wide |
4 | GOPRO_PHOTO_RESOLUTION_12MP_WIDE | 12MP Wide |
GOPRO_PROTUNE_WHITE_BALANCE
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_PROTUNE_WHITE_BALANCE_AUTO | Auto |
1 | GOPRO_PROTUNE_WHITE_BALANCE_3000K | 3000K |
2 | GOPRO_PROTUNE_WHITE_BALANCE_5500K | 5500K |
3 | GOPRO_PROTUNE_WHITE_BALANCE_6500K | 6500K |
4 | GOPRO_PROTUNE_WHITE_BALANCE_RAW | Camera Raw |
GOPRO_PROTUNE_COLOUR
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_PROTUNE_COLOUR_STANDARD | Auto |
1 | GOPRO_PROTUNE_COLOUR_NEUTRAL | Neutral |
GOPRO_PROTUNE_GAIN
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_PROTUNE_GAIN_400 | ISO 400 |
1 | GOPRO_PROTUNE_GAIN_800 | ISO 800 (Only Hero 4) |
2 | GOPRO_PROTUNE_GAIN_1600 | ISO 1600 |
3 | GOPRO_PROTUNE_GAIN_3200 | ISO 3200 (Only Hero 4) |
4 | GOPRO_PROTUNE_GAIN_6400 | ISO 6400 |
GOPRO_PROTUNE_SHARPNESS
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_PROTUNE_SHARPNESS_LOW | Low Sharpness |
1 | GOPRO_PROTUNE_SHARPNESS_MEDIUM | Medium Sharpness |
2 | GOPRO_PROTUNE_SHARPNESS_HIGH | High Sharpness |
GOPRO_PROTUNE_EXPOSURE
GOPRO_CHARGING
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_CHARGING_DISABLED | Charging disabled |
1 | GOPRO_CHARGING_ENABLED | Charging enabled |
GOPRO_MODEL
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_MODEL_UNKNOWN | Unknown gopro model |
1 | GOPRO_MODEL_HERO_3_PLUS_SILVER | Hero 3+ Silver (HeroBus not supported by GoPro) |
2 | GOPRO_MODEL_HERO_3_PLUS_BLACK | Hero 3+ Black |
3 | GOPRO_MODEL_HERO_4_SILVER | Hero 4 Silver |
4 | GOPRO_MODEL_HERO_4_BLACK | Hero 4 Black |
GOPRO_BURST_RATE
CMD ID | Field Name | Description |
---|---|---|
0 | GOPRO_BURST_RATE_3_IN_1_SECOND | 3 Shots / 1 Second |
1 | GOPRO_BURST_RATE_5_IN_1_SECOND | 5 Shots / 1 Second |
2 | GOPRO_BURST_RATE_10_IN_1_SECOND | 10 Shots / 1 Second |
3 | GOPRO_BURST_RATE_10_IN_2_SECOND | 10 Shots / 2 Second |
4 | GOPRO_BURST_RATE_10_IN_3_SECOND | 10 Shots / 3 Second (Hero 4 Only) |
5 | GOPRO_BURST_RATE_30_IN_1_SECOND | 30 Shots / 1 Second |
6 | GOPRO_BURST_RATE_30_IN_2_SECOND | 30 Shots / 2 Second |
7 | GOPRO_BURST_RATE_30_IN_3_SECOND | 30 Shots / 3 Second |
8 | GOPRO_BURST_RATE_30_IN_6_SECOND | 30 Shots / 6 Second |
LED_CONTROL_PATTERN
CMD ID | Field Name | Description |
---|---|---|
0 | LED_CONTROL_PATTERN_OFF | LED patterns off (return control to regular vehicle control) |
1 | LED_CONTROL_PATTERN_FIRMWAREUPDATE | LEDs show pattern during firmware update |
255 | LED_CONTROL_PATTERN_CUSTOM | Custom Pattern using custom bytes fields |
EKF_STATUS_FLAGS
Flags in EKF_STATUS message
CMD ID | Field Name | Description |
---|---|---|
1 | EKF_ATTITUDE | set if EKF's attitude estimate is good |
2 | EKF_VELOCITY_HORIZ | set if EKF's horizontal velocity estimate is good |
4 | EKF_VELOCITY_VERT | set if EKF's vertical velocity estimate is good |
8 | EKF_POS_HORIZ_REL | set if EKF's horizontal position (relative) estimate is good |
16 | EKF_POS_HORIZ_ABS | set if EKF's horizontal position (absolute) estimate is good |
32 | EKF_POS_VERT_ABS | set if EKF's vertical position (absolute) estimate is good |
64 | EKF_POS_VERT_AGL | set if EKF's vertical position (above ground) estimate is good |
128 | EKF_CONST_POS_MODE | EKF is in constant position mode and does not know it's absolute or relative position |
256 | EKF_PRED_POS_HORIZ_REL | set if EKF's predicted horizontal position (relative) estimate is good |
512 | EKF_PRED_POS_HORIZ_ABS | set if EKF's predicted horizontal position (absolute) estimate is good |
PID_TUNING_AXIS
CMD ID | Field Name | Description |
---|---|---|
1 | PID_TUNING_ROLL | |
2 | PID_TUNING_PITCH | |
3 | PID_TUNING_YAW | |
4 | PID_TUNING_ACCZ | |
5 | PID_TUNING_STEER | |
6 | PID_TUNING_LANDING |
MAG_CAL_STATUS
CMD ID | Field Name | Description |
---|---|---|
0 | MAG_CAL_NOT_STARTED | |
1 | MAG_CAL_WAITING_TO_START | |
2 | MAG_CAL_RUNNING_STEP_ONE | |
3 | MAG_CAL_RUNNING_STEP_TWO | |
4 | MAG_CAL_SUCCESS | |
5 | MAG_CAL_FAILED |
MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS
Special ACK block numbers control activation of dataflash log streaming
CMD ID | Field Name | Description |
---|---|---|
2147483645 | MAV_REMOTE_LOG_DATA_BLOCK_STOP | UAV to stop sending DataFlash blocks |
2147483646 | MAV_REMOTE_LOG_DATA_BLOCK_START | UAV to start sending DataFlash blocks |
MAV_REMOTE_LOG_DATA_BLOCK_STATUSES
Possible remote log data block statuses
CMD ID | Field Name | Description |
---|---|---|
0 | MAV_REMOTE_LOG_DATA_BLOCK_NACK | This block has NOT been received |
1 | MAV_REMOTE_LOG_DATA_BLOCK_ACK | This block has been received |
DEVICE_OP_BUSTYPE
Bus types for device operations
CMD ID | Field Name | Description |
---|---|---|
0 | DEVICE_OP_BUSTYPE_I2C | I2C Device operation |
1 | DEVICE_OP_BUSTYPE_SPI | SPI Device operation |
DEEPSTALL_STAGE
Deepstall flight stage
CMD ID | Field Name | Description |
---|---|---|
0 | DEEPSTALL_STAGE_FLY_TO_LANDING | Flying to the landing point |
1 | DEEPSTALL_STAGE_ESTIMATE_WIND | Building an estimate of the wind |
2 | DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT | Waiting to breakout of the loiter to fly the approach |
3 | DEEPSTALL_STAGE_FLY_TO_ARC | Flying to the first arc point to turn around to the landing point |
4 | DEEPSTALL_STAGE_ARC | Turning around back to the deepstall landing point |
5 | DEEPSTALL_STAGE_APPROACH | Approaching the landing point |
6 | DEEPSTALL_STAGE_LAND | Stalling and steering towards the land point |
PLANE_MODE
A mapping of plane flight modes for custom_mode field of heartbeat
CMD ID | Field Name | Description |
---|---|---|
0 | PLANE_MODE_MANUAL | |
1 | PLANE_MODE_CIRCLE | |
2 | PLANE_MODE_STABILIZE | |
3 | PLANE_MODE_TRAINING | |
4 | PLANE_MODE_ACRO | |
5 | PLANE_MODE_FLY_BY_WIRE_A | |
6 | PLANE_MODE_FLY_BY_WIRE_B | |
7 | PLANE_MODE_CRUISE | |
8 | PLANE_MODE_AUTOTUNE | |
10 | PLANE_MODE_AUTO | |
11 | PLANE_MODE_RTL | |
12 | PLANE_MODE_LOITER | |
14 | PLANE_MODE_AVOID_ADSB | |
15 | PLANE_MODE_GUIDED | |
16 | PLANE_MODE_INITIALIZING | |
17 | PLANE_MODE_QSTABILIZE | |
18 | PLANE_MODE_QHOVER | |
19 | PLANE_MODE_QLOITER | |
20 | PLANE_MODE_QLAND | |
21 | PLANE_MODE_QRTL |
COPTER_MODE
A mapping of copter flight modes for custom_mode field of heartbeat
CMD ID | Field Name | Description |
---|---|---|
0 | COPTER_MODE_STABILIZE | |
1 | COPTER_MODE_ACRO | |
2 | COPTER_MODE_ALT_HOLD | |
3 | COPTER_MODE_AUTO | |
4 | COPTER_MODE_GUIDED | |
5 | COPTER_MODE_LOITER | |
6 | COPTER_MODE_RTL | |
7 | COPTER_MODE_CIRCLE | |
9 | COPTER_MODE_LAND | |
11 | COPTER_MODE_DRIFT | |
13 | COPTER_MODE_SPORT | |
14 | COPTER_MODE_FLIP | |
15 | COPTER_MODE_AUTOTUNE | |
16 | COPTER_MODE_POSHOLD | |
17 | COPTER_MODE_BRAKE | |
18 | COPTER_MODE_THROW | |
19 | COPTER_MODE_AVOID_ADSB | |
20 | COPTER_MODE_GUIDED_NOGPS | |
21 | COPTER_MODE_SMART_RTL |
SUB_MODE
A mapping of sub flight modes for custom_mode field of heartbeat
CMD ID | Field Name | Description |
---|---|---|
0 | SUB_MODE_STABILIZE | |
1 | SUB_MODE_ACRO | |
2 | SUB_MODE_ALT_HOLD | |
3 | SUB_MODE_AUTO | |
4 | SUB_MODE_GUIDED | |
7 | SUB_MODE_CIRCLE | |
9 | SUB_MODE_SURFACE | |
16 | SUB_MODE_POSHOLD | |
19 | SUB_MODE_MANUAL |
ROVER_MODE
A mapping of rover flight modes for custom_mode field of heartbeat
CMD ID | Field Name | Description |
---|---|---|
0 | ROVER_MODE_MANUAL | |
1 | ROVER_MODE_ACRO | |
3 | ROVER_MODE_STEERING | |
4 | ROVER_MODE_HOLD | |
10 | ROVER_MODE_AUTO | |
11 | ROVER_MODE_RTL | |
12 | ROVER_MODE_SMART_RTL | |
15 | ROVER_MODE_GUIDED | |
16 | ROVER_MODE_INITIALIZING |
TRACKER_MODE
A mapping of antenna tracker flight modes for custom_mode field of heartbeat
CMD ID | Field Name | Description |
---|---|---|
0 | TRACKER_MODE_MANUAL | |
1 | TRACKER_MODE_STOP | |
2 | TRACKER_MODE_SCAN | |
3 | TRACKER_MODE_SERVO_TEST | |
10 | TRACKER_MODE_AUTO | |
16 | TRACKER_MODE_INITIALIZING |
MAVLink Messages
SENSOR_OFFSETS ( #150 )
Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.
Field Name | Type | 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 | magnetic declination (radians) (Units: rad) |
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. Use MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS instead. 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 APM memory
Field Name | Type | Description |
---|---|---|
brkval | uint16_t | heap top |
freemem | uint16_t | free memory (Units: bytes) |
freemem32 ** | uint32_t | free memory (32 bit) (Units: bytes) |
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 |
DIGICAM_CONFIGURE ( #154 )
Configure on-board Camera Control System.
Field Name | Type | 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 | Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) (Units: ds) |
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 |
MOUNT_CONFIGURE ( #156 )
Message to configure a camera mount, directional antenna, etc.
Field Name | Type | Description |
---|---|---|
target_system | uint8_t | System ID |
target_component | uint8_t | Component ID |
mount_mode | uint8_t | mount operating mode (see MAV_MOUNT_MODE enum) (Enum:MAV_MOUNT_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(deg*100) or lat, depending on mount mode |
input_b | int32_t | roll(deg*100) or lon depending on mount mode |
input_c | int32_t | yaw(deg*100) or alt (in 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 APM to GCS about camera or antenna mount
Field Name | Type | Description |
---|---|---|
target_system | uint8_t | System ID |
target_component | uint8_t | Component ID |
pointing_a | int32_t | pitch(deg*100) (Units: cdeg) |
pointing_b | int32_t | roll(deg*100) (Units: cdeg) |
pointing_c | int32_t | yaw(deg*100) (Units: cdeg) |
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 | 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 | Latitude of point (Units: deg) |
lng | float | Longitude of point (Units: deg) |
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) |
FENCE_STATUS ( #162 )
Status of geo-fencing. Sent in extended status stream when fencing enabled
Field Name | Type | Description |
---|---|---|
breach_status | uint8_t | 0 if currently inside fence, 1 if outside |
breach_count | uint16_t | number of fence breaches |
breach_type | uint8_t | last breach type (see FENCE_BREACH_* enum) (Enum:FENCE_BREACH ) |
breach_time | uint32_t | time of last breach in milliseconds since boot (Units: ms) |
AHRS ( #163 )
Status of DCM attitude estimator
Field Name | Type | Description |
---|---|---|
omegaIx | float | X gyro drift estimate rad/s (Units: rad/s) |
omegaIy | float | Y gyro drift estimate rad/s (Units: rad/s) |
omegaIz | float | Z gyro drift estimate rad/s (Units: rad/s) |
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 | Description |
---|---|---|
roll | float | Roll angle (rad) (Units: rad) |
pitch | float | Pitch angle (rad) (Units: rad) |
yaw | float | Yaw angle (rad) (Units: rad) |
xacc | float | X acceleration m/s/s (Units: m/s/s) |
yacc | float | Y acceleration m/s/s (Units: m/s/s) |
zacc | float | Z acceleration m/s/s (Units: m/s/s) |
xgyro | float | Angular speed around X axis rad/s (Units: rad/s) |
ygyro | float | Angular speed around Y axis rad/s (Units: rad/s) |
zgyro | float | Angular speed around Z axis rad/s (Units: rad/s) |
lat | int32_t | Latitude in degrees * 1E7 (Units: degE7) |
lng | int32_t | Longitude in degrees * 1E7 (Units: degE7) |
HWSTATUS ( #165 )
Status of key hardware
Field Name | Type | Description |
---|---|---|
Vcc | uint16_t | board voltage (mV) (Units: mV) |
I2Cerr | uint8_t | I2C error count |
RADIO ( #166 )
Status generated by radio
Field Name | Type | Description |
---|---|---|
rssi | uint8_t | local signal strength |
remrssi | uint8_t | remote signal strength |
txbuf | uint8_t | how full the tx buffer is as a percentage (Units: %) |
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 | Description |
---|---|---|
limits_state | uint8_t | state of AP_Limits, (see enum LimitState, LIMITS_STATE) (Enum:LIMITS_STATE ) |
last_trigger | uint32_t | time of last breach in milliseconds since boot (Units: ms) |
last_action | uint32_t | time of last recovery action in milliseconds since boot (Units: ms) |
last_recovery | uint32_t | time of last successful recovery in milliseconds since boot (Units: ms) |
last_clear | uint32_t | time of last all-clear in milliseconds since boot (Units: ms) |
breach_count | uint16_t | number of fence breaches |
mods_enabled | uint8_t | AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) (Enum:LIMIT_MODULE ) |
mods_required | uint8_t | AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) (Enum:LIMIT_MODULE ) |
mods_triggered | uint8_t | AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) (Enum:LIMIT_MODULE ) |
WIND ( #168 )
Wind estimation
Field Name | Type | Description |
---|---|---|
direction | float | wind direction that wind is coming from (degrees) (Units: deg) |
speed | float | wind speed in ground plane (m/s) (Units: m/s) |
speed_z | float | vertical wind speed (m/s) (Units: m/s) |
DATA16 ( #169 )
Data packet, size 16
Field Name | Type | Description |
---|---|---|
type | uint8_t | data type |
len | uint8_t | data length (Units: bytes) |
data | uint8_t[16] | raw data |
DATA32 ( #170 )
Data packet, size 32
Field Name | Type | Description |
---|---|---|
type | uint8_t | data type |
len | uint8_t | data length (Units: bytes) |
data | uint8_t[32] | raw data |
DATA64 ( #171 )
Data packet, size 64
Field Name | Type | Description |
---|---|---|
type | uint8_t | data type |
len | uint8_t | data length (Units: bytes) |
data | uint8_t[64] | raw data |
DATA96 ( #172 )
Data packet, size 96
Field Name | Type | Description |
---|---|---|
type | uint8_t | data type |
len | uint8_t | data length (Units: bytes) |
data | uint8_t[96] | raw data |
RANGEFINDER ( #173 )
Rangefinder reporting
Field Name | Type | Description |
---|---|---|
distance | float | distance in meters (Units: m) |
voltage | float | raw voltage if available, zero otherwise (Units: V) |
AIRSPEED_AUTOCAL ( #174 )
Airspeed auto-calibration
Field Name | Type | Description |
---|---|---|
vx | float | GPS velocity north m/s (Units: m/s) |
vy | float | GPS velocity east m/s (Units: m/s) |
vz | float | GPS velocity down m/s (Units: m/s) |
diff_pressure | float | Differential pressure pascals (Units: Pa) |
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 | 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 | Latitude of point in degrees * 1E7 (Units: degE7) |
lng | int32_t | Longitude of point in degrees * 1E7 (Units: degE7) |
alt | int16_t | Transit / loiter altitude in meters relative to home (Units: m) |
break_alt | int16_t | Break altitude in meters relative to home (Units: m) |
land_dir | uint16_t | Heading to aim for when landing. In centi-degrees. (Units: cdeg) |
flags | uint8_t | See RALLY_FLAGS enum for definition of the bitmask. (Enum:RALLY_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 | Description |
---|---|---|
throttle | uint16_t | throttle (percent*10) (Units: d%) |
current | float | current (Ampere) (Units: A) |
interference | uint16_t | interference (percent) (Units: %) |
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 | Description |
---|---|---|
roll | float | Roll angle (rad) (Units: rad) |
pitch | float | Pitch angle (rad) (Units: rad) |
yaw | float | Yaw angle (rad) (Units: rad) |
altitude | float | Altitude (MSL) (Units: m) |
lat | int32_t | Latitude in degrees * 1E7 (Units: degE7) |
lng | int32_t | Longitude in degrees * 1E7 (Units: degE7) |
CAMERA_STATUS ( #179 )
Camera Event
Field Name | Type | Description |
---|---|---|
time_usec | uint64_t | Image timestamp (microseconds since UNIX epoch, according to camera clock) (Units: us) |
target_system | uint8_t | System ID |
cam_idx | uint8_t | Camera ID |
img_idx | uint16_t | Image index |
event_id | uint8_t | See CAMERA_STATUS_TYPES enum for definition of the bitmask (Enum:CAMERA_STATUS_TYPES ) |
p1 | float | Parameter 1 (meaning depends on event, see CAMERA_STATUS_TYPES enum) |
p2 | float | Parameter 2 (meaning depends on event, see CAMERA_STATUS_TYPES enum) |
p3 | float | Parameter 3 (meaning depends on event, see CAMERA_STATUS_TYPES enum) |
p4 | float | Parameter 4 (meaning depends on event, see CAMERA_STATUS_TYPES enum) |
CAMERA_FEEDBACK ( #180 )
Camera Capture Feedback
Field Name | Type | Description |
---|---|---|
time_usec | uint64_t | Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB) (Units: us) |
target_system | uint8_t | System ID |
cam_idx | uint8_t | Camera ID |
img_idx | uint16_t | Image index |
lat | int32_t | Latitude in (deg * 1E7) (Units: degE7) |
lng | int32_t | Longitude in (deg * 1E7) (Units: degE7) |
alt_msl | float | Altitude Absolute (meters AMSL) (Units: m) |
alt_rel | float | Altitude Relative (meters above HOME location) (Units: m) |
roll | float | Camera Roll angle (earth frame, degrees, +-180) (Units: deg) |
pitch | float | Camera Pitch angle (earth frame, degrees, +-180) (Units: deg) |
yaw | float | Camera Yaw (earth frame, degrees, 0-360, true) (Units: deg) |
foc_len | float | Focal Length (mm) (Units: mm) |
flags | uint8_t | See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask (Enum:CAMERA_FEEDBACK_FLAGS ) |
BATTERY2 ( #181 )
2nd Battery status
Field Name | Type | Description |
---|---|---|
voltage | uint16_t | voltage in millivolts (Units: mV) |
current_battery | int16_t | Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (Units: cA) |
AHRS3 ( #182 )
Status of third AHRS filter if available. This is for ANU research group (Ali and Sean)
Field Name | Type | Description |
---|---|---|
roll | float | Roll angle (rad) (Units: rad) |
pitch | float | Pitch angle (rad) (Units: rad) |
yaw | float | Yaw angle (rad) (Units: rad) |
altitude | float | Altitude (MSL) (Units: m) |
lat | int32_t | Latitude in degrees * 1E7 (Units: degE7) |
lng | int32_t | Longitude in degrees * 1E7 (Units: degE7) |
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 | Description |
---|---|---|
target_system | uint8_t | System ID |
target_component | uint8_t | Component ID |
seqno | uint32_t | log data block sequence number (Enum:MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS ) |
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 | Description |
---|---|---|
target_system | uint8_t | System ID |
target_component | uint8_t | Component ID |
seqno | uint32_t | log data block sequence number |
status | uint8_t | log data block status (Enum:MAV_REMOTE_LOG_DATA_BLOCK_STATUSES ) |
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 | Description |
---|---|---|
compass_id | uint8_t | Compass being calibrated |
cal_mask | uint8_t | Bitmask of compasses being calibrated |
cal_status | uint8_t | Status (see MAG_CAL_STATUS enum) (Enum:MAG_CAL_STATUS ) |
attempt | uint8_t | Attempt number |
completion_pct | uint8_t | Completion percentage (Units: %) |
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 )
Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.
Field Name | Type | Description |
---|---|---|
compass_id | uint8_t | Compass being calibrated |
cal_mask | uint8_t | Bitmask of compasses being calibrated |
cal_status | uint8_t | Status (see MAG_CAL_STATUS enum) (Enum:MAG_CAL_STATUS ) |
autosaved | uint8_t | 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters |
fitness | float | RMS milligauss residuals (Units: mgauss) |
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) |
EKF_STATUS_REPORT ( #193 )
EKF Status message including flags and variances
Field Name | Type | Description |
---|---|---|
flags | uint16_t | Flags (Enum:EKF_STATUS_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 |
PID_TUNING ( #194 )
PID tuning information
Field Name | Type | Description |
---|---|---|
axis | uint8_t | axis (Enum:PID_TUNING_AXIS ) |
desired | float | desired rate (degrees/s) (Units: deg/s) |
achieved | float | achieved rate (degrees/s) (Units: deg/s) |
FF | float | FF component |
P | float | P component |
I | float | I component |
D | float | D component |
DEEPSTALL ( #195 )
Deepstall path planning
Field Name | Type | Description |
---|---|---|
landing_lat | int32_t | Landing latitude (deg * 1E7) (Units: degE7) |
landing_lon | int32_t | Landing longitude (deg * 1E7) (Units: degE7) |
path_lat | int32_t | Final heading start point, latitude (deg * 1E7) (Units: degE7) |
path_lon | int32_t | Final heading start point, longitude (deg * 1E7) (Units: degE7) |
arc_entry_lat | int32_t | Arc entry point, latitude (deg * 1E7) (Units: degE7) |
arc_entry_lon | int32_t | Arc entry point, longitude (deg * 1E7) (Units: degE7) |
altitude | float | Altitude (meters) (Units: m) |
expected_travel_distance | float | Distance the aircraft expects to travel during the deepstall (Units: m) |
cross_track_error | float | Deepstall cross track error in meters (only valid when in DEEPSTALL_STAGE_LAND) (Units: m) |
stage | uint8_t | Deepstall stage, see enum MAV_DEEPSTALL_STAGE (Enum:DEEPSTALL_STAGE ) |
GIMBAL_REPORT ( #200 )
3 axis gimbal mesuraments
Field Name | Type | Description |
---|---|---|
target_system | uint8_t | System ID |
target_component | uint8_t | Component ID |
delta_time | float | Time since last update (seconds) (Units: s) |
delta_angle_x | float | Delta angle X (radians) (Units: rad) |
delta_angle_y | float | Delta angle Y (radians) (Units: rad) |
delta_angle_z | float | Delta angle X (radians) (Units: rad) |
delta_velocity_x | float | Delta velocity X (m/s) (Units: m/s) |
delta_velocity_y | float | Delta velocity Y (m/s) (Units: m/s) |
delta_velocity_z | float | Delta velocity Z (m/s) (Units: m/s) |
joint_roll | float | Joint ROLL (radians) (Units: rad) |
joint_el | float | Joint EL (radians) (Units: rad) |
joint_az | float | Joint AZ (radians) (Units: rad) |
GIMBAL_CONTROL ( #201 )
Control message for rate gimbal
Field Name | Type | Description |
---|---|---|
target_system | uint8_t | System ID |
target_component | uint8_t | Component ID |
demanded_rate_x | float | Demanded angular rate X (rad/s) (Units: rad/s) |
demanded_rate_y | float | Demanded angular rate Y (rad/s) (Units: rad/s) |
demanded_rate_z | float | Demanded angular rate Z (rad/s) (Units: rad/s) |
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
Field Name | Type | Description |
---|---|---|
status | uint8_t | Status (Enum:GOPRO_HEARTBEAT_STATUS ) |
capture_mode | uint8_t | Current capture mode (Enum:GOPRO_CAPTURE_MODE ) |
flags | uint8_t | additional status bits (Enum:GOPRO_HEARTBEAT_FLAGS ) |
GOPRO_GET_REQUEST ( #216 )
Request a GOPRO_COMMAND response from the GoPro
Field Name | Type | Description |
---|---|---|
target_system | uint8_t | System ID |
target_component | uint8_t | Component ID |
cmd_id | uint8_t | Command ID (Enum:GOPRO_COMMAND ) |
GOPRO_GET_RESPONSE ( #217 )
Response from a GOPRO_COMMAND get request
Field Name | Type | Description |
---|---|---|
cmd_id | uint8_t | Command ID (Enum:GOPRO_COMMAND ) |
status | uint8_t | Status (Enum:GOPRO_REQUEST_STATUS ) |
value | uint8_t[4] | Value |
GOPRO_SET_REQUEST ( #218 )
Request to set a GOPRO_COMMAND with a desired
Field Name | Type | Description |
---|---|---|
target_system | uint8_t | System ID |
target_component | uint8_t | Component ID |
cmd_id | uint8_t | Command ID (Enum:GOPRO_COMMAND ) |
value | uint8_t[4] | Value |
GOPRO_SET_RESPONSE ( #219 )
Response from a GOPRO_COMMAND set request
Field Name | Type | Description |
---|---|---|
cmd_id | uint8_t | Command ID (Enum:GOPRO_COMMAND ) |
status | uint8_t | Status (Enum:GOPRO_REQUEST_STATUS ) |
RPM ( #226 )
RPM sensor output
Field Name | Type | Description |
---|---|---|
rpm1 | float | RPM Sensor1 |
rpm2 | float | RPM Sensor2 |
DEVICE_OP_READ ( #11000 )
(MAVLink 2) Read registers for a device
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 |
bustype | uint8_t | The bus type (Enum:DEVICE_OP_BUSTYPE ) |
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 )
(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 )
(MAVLink 2) Write registers for a device
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 |
bustype | uint8_t | The bus type (Enum:DEVICE_OP_BUSTYPE ) |
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 )
(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 )
(MAVLink 2) Adaptive Controller tuning information
Field Name | Type | Description |
---|---|---|
axis | uint8_t | axis (Enum:PID_TUNING_AXIS ) |
desired | float | desired rate (degrees/s) (Units: deg/s) |
achieved | float | achieved rate (degrees/s) (Units: deg/s) |
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 )
(MAVLink 2) camera vision based attitude and position deltas
Field Name | Type | Description |
---|---|---|
time_usec | uint64_t | Timestamp (microseconds, synced to UNIX time or since system boot) (Units: us) |
time_delta_usec | uint64_t | Time in microseconds since the last reported camera frame (Units: us) |
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] | Change in position in meters from previous to current frame rotated into body frame (0=forward, 1=right, 2=down) (Units: m) |
confidence | float | normalised confidence value from 0 to 100 (Units: %) |
AOA_SSA ( #11020 )
(MAVLink 2) Angle of Attack and Side Slip Angle
Field Name | Type | Description |
---|---|---|
time_usec | uint64_t | Timestamp (micros since boot or Unix epoch) (Units: us) |
AOA | float | Angle of Attack (degrees) (Units: deg) |
SSA | float | Side Slip Angle (degrees) (Units: deg) |