-
Notifications
You must be signed in to change notification settings - Fork 1
MAVLINK Common Message Set
Table of Contents generated with DocToc
###MAV_TYPE_GENERIC
- 0
- Generic micro air vehicle.
###MAV_TYPE_FIXED_WING
- 1
- Fixed wing aircraft.
###MAV_TYPE_QUADROTOR
- 2
- Quadrotor
###MAV_TYPE_COAXIAL
- 3
- Coaxial helicopter
###MAV_TYPE_HELICOPTER
- 4
- Normal helicopter with tail rotor.
###MAV_TYPE_ANTENNA_TRACKER
- 5
- Ground installation
###MAV_TYPE_GCS
- 6
- Operator control unit, ground control station
###MAV_TYPE_AIRSHIP
- 7
- Airship, controlled
###MAV_TYPE_FREE_BALLOON
- 8
- Free balloon, uncontrolled
###MAV_TYPE_ROCKET
- 9
- Rocket
###MAV_TYPE_GROUND_ROVER
- 10
- Ground rover
###MAV_TYPE_SURFACE_BOAT
- 11
- Surface vessel, boat, ship
###MAV_TYPE_SUBMARINE
- 12
- Submarine
###MAV_TYPE_HEXAROTOR
- 13
- Hexarotor
###MAV_TYPE_OCTOROTOR
- 14
- Octorotor
###MAV_TYPE_TRICOPTER
- 15
- Tricopter
###MAV_TYPE_FLAPPING_WING
- 16
- Flapping wing
###MAV_TYPE_KITE
- 17
- Kite
###MAV_TYPE_ONBOARD_CONTROLLER
- 18
- Onboard companion controller
###MAV_TYPE_VTOL_DUOROTOR
- 19
- Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.
###MAV_TYPE_VTOL_QUADROTOR
- 20
- Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.
###MAV_TYPE_VTOL_TILTROTOR
- 21
- Tiltrotor VTOL
###MAV_TYPE_VTOL_RESERVED2
- 22
- VTOL reserved 2
###MAV_TYPE_VTOL_RESERVED3
- 23
- VTOL reserved 3
###MAV_TYPE_VTOL_RESERVED4
- 24
- VTOL reserved 4
###MAV_TYPE_VTOL_RESERVED5
- 25
- VTOL reserved 5
###MAV_TYPE_GIMBAL
- 26
- Onboard gimbal
###MAV_TYPE_ADSB
- 27
- Onboard ADSB peripheral
###MAV_TYPE_ENUM_END
- 28
- end of systemType
###MAV_AUTOPILOT_GENERIC
- 0
- Generic autopilot, full support for everything
###MAV_AUTOPILOT_RESERVED
- 1
- Reserved for future use.
###MAV_AUTOPILOT_SLUGS
- 2
- SLUGS autopilot, http://slugsuav.soe.ucsc.edu
###MAV_AUTOPILOT_ARDUPILOTMEGA
- 3
- ArduPilotMega / ArduCopter, http://diydrones.com
###MAV_AUTOPILOT_OPENPILOT
- 4
- OpenPilot, http://openpilot.org
###MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY
- 5
- Generic autopilot only supporting simple waypoints
###MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY
- 6
- Generic autopilot supporting waypoints and other simple navigation commands
###MAV_AUTOPILOT_GENERIC_MISSION_FULL
- 7
- Generic autopilot supporting the full mission command set
###MAV_AUTOPILOT_INVALID
- 8
- No valid autopilot, e.g. a GCS or other MAVLink component
###MAV_AUTOPILOT_PPZ
- 9
- PPZ UAV - http://nongnu.org/paparazzi
###MAV_AUTOPILOT_UDB
- 10
- UAV Dev Board
###MAV_AUTOPILOT_FP
- 11
- FlexiPilot
###MAV_AUTOPILOT_PX4
- 12
- PX4 Autopilot - http://pixhawk.ethz.ch/px4/
###MAV_AUTOPILOT_SMACCMPILOT
- 13
- SMACCMPilot - http://smaccmpilot.org
###MAV_AUTOPILOT_AUTOQUAD
- 14
- AutoQuad -- http://autoquad.org
###MAV_AUTOPILOT_ARMAZILA
- 15
- Armazila -- http://armazila.com
###MAV_AUTOPILOT_AEROB
- 16
- Aerob -- http://aerob.ru
###MAV_AUTOPILOT_ASLUAV
- 17
- ASLUAV autopilot -- http://www.asl.ethz.ch
###MAV_AUTOPILOT_ENUM_END
- 18
- end of autopilotType
###MAV_MODE_PREFLIGHT
- 0
- System is not ready to fly, booting, calibrating, etc. No flag is set.
###MAV_MODE_MANUAL_DISARMED
- 64
- System is allowed to be active, under manual (RC) control, no stabilization
###MAV_MODE_TEST_DISARMED
- 66
- UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
###MAV_MODE_STABILIZE_DISARMED
- 80
- System is allowed to be active, under assisted RC control.
###MAV_MODE_GUIDED_DISARMED
- 88
- System is allowed to be active, under autonomous control, manual setpoint
###MAV_MODE_AUTO_DISARMED
- 92
- System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)
###MAV_MODE_MANUAL_ARMED
- 192
- System is allowed to be active, under manual (RC) control, no stabilization
###MAV_MODE_TEST_ARMED
- 194
- UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.
###MAV_MODE_STABILIZE_ARMED
- 208
- System is allowed to be active, under assisted RC control.
###MAV_MODE_GUIDED_ARMED
- 216
- System is allowed to be active, under autonomous control, manual setpoint
###MAV_MODE_AUTO_ARMED
- 220
- System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)
###MAV_MODE_ENUM_END
- 221
- end of systemMode
###MAV_STATE_UNINIT
- 0
- Uninitialized system, state is unknown.
###MAV_STATE_BOOT
- 1
- System is booting up.
###MAV_STATE_CALIBRATING
- 2
- System is calibrating and not flight-ready.
###MAV_STATE_STANDBY
- 3
- System is grounded and on standby. It can be launched any time.
###MAV_STATE_ACTIVE
- 4
- System is active and might be already airborne. Motors are engaged.
###MAV_STATE_CRITICAL
- 5
- System is in a non-normal flight mode. It can however still navigate.
###MAV_STATE_EMERGENCY
- 6
- System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.
###MAV_STATE_POWEROFF
- 7
- System just initialized its power-down sequence, will shut down now.
###MAV_STATE_ENUM_END
- 8
- end of systemState
###MAV_COMP_ID_ALL
- 0
###MAV_COMP_ID_CAMERA
- 100
###MAV_COMP_ID_SERVO1
- 140
###MAV_COMP_ID_SERVO2
- 141
###MAV_COMP_ID_SERVO3
- 142
###MAV_COMP_ID_SERVO4
- 143
###MAV_COMP_ID_SERVO5
- 144
###MAV_COMP_ID_SERVO6
- 145
###MAV_COMP_ID_SERVO7
- 146
###MAV_COMP_ID_SERVO8
- 147
###MAV_COMP_ID_SERVO9
- 148
###MAV_COMP_ID_SERVO10
- 149
###MAV_COMP_ID_SERVO11
- 150
###MAV_COMP_ID_SERVO12
- 151
###MAV_COMP_ID_SERVO13
- 152
###MAV_COMP_ID_SERVO14
- 153
###MAV_COMP_ID_GIMBAL
- 154
###MAV_COMP_ID_LOG
- 155
###MAV_COMP_ID_ADSB
- 156
###MAV_COMP_ID_OSD
- 157
- On Screen Display (OSD) devices for video links
###MAV_COMP_ID_PERIPHERAL
- 158
- Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter sub-protocol
###MAV_COMP_ID_QX1_GIMBAL
- 159
###MAV_COMP_ID_MAPPER
- 180
###MAV_COMP_ID_MISSIONPLANNER
- 190
###MAV_COMP_ID_PATHPLANNER
- 195
###MAV_COMP_ID_IMU
- 200
###MAV_COMP_ID_IMU_2
- 201
###MAV_COMP_ID_IMU_3
- 202
###MAV_COMP_ID_GPS
- 220
###MAV_COMP_ID_UDP_BRIDGE
- 240
###MAV_COMP_ID_UART_BRIDGE
- 241
###MAV_COMP_ID_SYSTEM_CONTROL
- 250
###MAV_COMPONENT_ENUM_END
- 251
###HEARTBEAT
- 0
- The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).
###SYS_STATUS
- 1
- The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.
###SYSTEM_TIME
- 2
- The system time is the time of the master clock, typically the computer clock of the main onboard computer.
###PING
- 4
- A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.
###CHANGE_OPERATOR_CONTROL
- 5
- Request to control this MAV
###CHANGE_OPERATOR_CONTROL_ACK
- 6
- Accept / deny control of this MAV
###AUTH_KEY
- 7
- Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.
###SET_MODE
- 11
- THIS INTERFACE IS DEPRECATED. USE COMMAND_LONG with MAV_CMD_DO_SET_MODE INSTEAD. Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.
###PARAM_REQUEST_READ
- 20
- Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.
###PARAM_REQUEST_LIST
- 21
- Request all parameters of this component. After this request, all parameters are emitted.
###PARAM_VALUE
- 22
- Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.
###PARAM_SET
- 23
- Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.
###GPS_RAW_INT
- 24
- The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).
###GPS_STATUS
- 25
- The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.
###SCALED_IMU
- 26
- The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units
###RAW_IMU
- 27
- The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.
###RAW_PRESSURE
- 28
- The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.
###SCALED_PRESSURE
- 29
- The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.
###ATTITUDE
- 30
- The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).
###ATTITUDE_QUATERNION
- 31
- The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).
###LOCAL_POSITION_NED
- 32
- The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)
###GLOBAL_POSITION_INT
- 33
- The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient.
###RC_CHANNELS_SCALED
- 34
- The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX.
###RC_CHANNELS_RAW
- 35
- The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.
###SERVO_OUTPUT_RAW
- 36
- The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.
###MISSION_REQUEST_PARTIAL_LIST
- 37
- Request a partial list of mission items from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol. If start and end index are the same, just send one waypoint.
###MISSION_WRITE_PARTIAL_LIST
- 38
- This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!
###MISSION_ITEM
- 39
- Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol.
###MISSION_REQUEST
- 40
- Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol
###MISSION_SET_CURRENT
- 41
- Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between).
###MISSION_CURRENT
- 42
- Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item.
###MISSION_REQUEST_LIST
- 43
- Request the overall list of mission items from the system/component.
###MISSION_COUNT
- 44
- This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs.
###MISSION_CLEAR_ALL
- 45
- Delete all mission items at once.
###MISSION_ITEM_REACHED
- 46
- A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION.
###MISSION_ACK
- 47
- Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).
###SET_GPS_GLOBAL_ORIGIN
- 48
- As local waypoints exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.
###GPS_GLOBAL_ORIGIN
- 49
- Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position
###PARAM_MAP_RC
- 50
- Bind a RC channel to a parameter. The parameter should change accoding to the RC channel value.
###MISSION_REQUEST_INT
- 51
- Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. http://qgroundcontrol.org/mavlink/waypoint_protocol
###SAFETY_SET_ALLOWED_AREA
- 54
- Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations.
###SAFETY_ALLOWED_AREA
- 55
- Read out the safety zone the MAV currently assumes.
###ATTITUDE_QUATERNION_COV
- 61
- The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).
###NAV_CONTROLLER_OUTPUT
- 62
- The state of the fixed wing navigation and position controller.
###GLOBAL_POSITION_INT_COV
- 63
- The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset.
###LOCAL_POSITION_NED_COV
- 64
- The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)
###RC_CHANNELS
- 65
- The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.
###REQUEST_DATA_STREAM
- 66
- THIS INTERFACE IS DEPRECATED. USE SET_MESSAGE_INTERVAL INSTEAD.
###DATA_STREAM
- 67
- THIS INTERFACE IS DEPRECATED. USE MESSAGE_INTERVAL INSTEAD.
###MANUAL_CONTROL
- 69
- This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled an buttons are also transmit as boolean values of their
###RC_CHANNELS_OVERRIDE
- 70
- The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of UINT16_MAX means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.
###MISSION_ITEM_INT
- 73
- Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol.
###VFR_HUD
- 74
- Metrics typically displayed on a HUD for fixed wing aircraft
###COMMAND_INT
- 75
- Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value.
###COMMAND_LONG
- 76
- Send a command with up to seven parameters to the MAV
###COMMAND_ACK
- 77
- Report status of a command. Includes feedback wether the command was executed.
###MANUAL_SETPOINT
- 81
- Setpoint in roll, pitch, yaw and thrust from the operator
###SET_ATTITUDE_TARGET
- 82
- Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system).
###ATTITUDE_TARGET
- 83
- Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way.
###SET_POSITION_TARGET_LOCAL_NED
- 84
- Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system).
###POSITION_TARGET_LOCAL_NED
- 85
- Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way.
###SET_POSITION_TARGET_GLOBAL_INT
- 86
- Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system).
###POSITION_TARGET_GLOBAL_INT
- 87
- Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way.
###LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET
- 89
- The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)
###HIL_STATE
- 90
- DEPRECATED PACKET! Suffers from missing airspeed fields and singularities due to Euler angles. Please use HIL_STATE_QUATERNION instead. Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.
###HIL_CONTROLS
- 91
- Sent from autopilot to simulation. Hardware in the loop control outputs
###HIL_RC_INPUTS_RAW
- 92
- Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.
###HIL_ACTUATOR_CONTROLS
- 93
- Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS)
###OPTICAL_FLOW
- 100
- Optical flow from a flow sensor (e.g. optical mouse sensor)
###GLOBAL_VISION_POSITION_ESTIMATE
- 101
###VISION_POSITION_ESTIMATE
- 102
###VISION_SPEED_ESTIMATE
- 103
###VICON_POSITION_ESTIMATE
- 104
###HIGHRES_IMU
- 105
- The IMU readings in SI units in NED body frame
###OPTICAL_FLOW_RAD
- 106
- Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)
###HIL_SENSOR
- 107
- The IMU readings in SI units in NED body frame
###SIM_STATE
- 108
- Status of simulation environment, if used
###RADIO_STATUS
- 109
- Status generated by radio and injected into MAVLink stream.
###FILE_TRANSFER_PROTOCOL
- 110
- File transfer message
###TIMESYNC
- 111
- Time synchronization message.
###CAMERA_TRIGGER
- 112
- Camera-IMU triggering and synchronisation message.
###HIL_GPS
- 113
- The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).
###HIL_OPTICAL_FLOW
- 114
- Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)
###HIL_STATE_QUATERNION
- 115
- Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations.
###SCALED_IMU2
- 116
- The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units
###LOG_REQUEST_LIST
- 117
- Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called.
###LOG_ENTRY
- 118
- Reply to LOG_REQUEST_LIST
###LOG_REQUEST_DATA
- 119
- Request a chunk of a log
###LOG_DATA
- 120
- Reply to LOG_REQUEST_DATA
###LOG_ERASE
- 121
- Erase all logs
###LOG_REQUEST_END
- 122
- Stop log transfer and resume normal logging
###GPS_INJECT_DATA
- 123
- data for injecting into the onboard GPS (used for DGPS)
###GPS2_RAW
- 124
- Second GPS data. Coordinate frame is right-handed, Z-axis up (GPS frame).
###POWER_STATUS
- 125
- Power supply status
###SERIAL_CONTROL
- 126
- Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate.
###GPS_RTK
- 127
- RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting
###GPS2_RTK
- 128
- RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting
###SCALED_IMU3
- 129
- The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units
###DATA_TRANSMISSION_HANDSHAKE
- 130
###ENCAPSULATED_DATA
- 131
###DISTANCE_SENSOR
- 132
###TERRAIN_REQUEST
- 133
- Request for terrain data and terrain status
###TERRAIN_DATA
- 134
- Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST
###TERRAIN_CHECK
- 135
- Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission.
###TERRAIN_REPORT
- 136
- Response from a TERRAIN_CHECK request
###SCALED_PRESSURE2
- 137
- Barometer readings for 2nd barometer
###ATT_POS_MOCAP
- 138
- Motion capture attitude and position
###SET_ACTUATOR_CONTROL_TARGET
- 139
- Set the vehicle attitude and body angular rates.
###ACTUATOR_CONTROL_TARGET
- 140
- Set the vehicle attitude and body angular rates.
###ALTITUDE
- 141
- The current system altitude.
###RESOURCE_REQUEST
- 142
- The autopilot is requesting a resource (file, binary, other type of data)
###SCALED_PRESSURE3
- 143
- Barometer readings for 3rd barometer
###FOLLOW_TARGET
- 144
- current motion information from a designated system
###CONTROL_SYSTEM_STATE
- 146
- The smoothed, monotonic system state used to feed the control loops of the system.
###BATTERY_STATUS
- 147
- Battery information
###AUTOPILOT_VERSION
- 148
- Version and capability of autopilot software
###LANDING_TARGET
- 149
- The location of a landing area captured from a downward facing camera
###ESTIMATOR_STATUS
- 230
- Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovaton test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovaton test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user.
###WIND_COV
- 231
###GPS_INPUT
- 232
- GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the sytem.
###GPS_RTCM_DATA
- 233
- WORK IN PROGRESS! RTCM message for injecting into the onboard GPS (used for DGPS)
###HIGH_LATENCY
- 234
- Message appropriate for high latency connections like Iridium
###VIBRATION
- 241
- Vibration levels and accelerometer clipping
###HOME_POSITION
- 242
- This message can be requested by sending the MAV_CMD_GET_HOME_POSITION command. The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The position the system will return to and land on. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector.
###SET_HOME_POSITION
- 243
- The position the system will return to and land on. The position is set automatically by the system during the takeoff in case it was not explicitely set by the operator before or after. The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector.
###MESSAGE_INTERVAL
- 244
- This interface replaces DATA_STREAM
###EXTENDED_SYS_STATE
- 245
- Provides state for additional features
###ADSB_VEHICLE
- 246
- The location and information of an ADSB vehicle
###COLLISION
- 247
- Information about a potential collision
###V2_EXTENSION
- 248
- Message implementing parts of the V2 payload specs in V1 frames for transitional support.
###MEMORY_VECT
- 249
- Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.
###DEBUG_VECT
- 250
###NAMED_VALUE_FLOAT
- 251
- Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.
###NAMED_VALUE_INT
- 252
- Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.
###STATUSTEXT
- 253
- Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).
###DEBUG
- 254
- Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.
###SETUP_SIGNING
- 256
- Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing
###BUTTON_CHANGE
- 257
- Report button state change
###PLAY_TUNE
- 258
- Control vehicle tone generation (buzzer)
###LOGGING_DATA
- 266
- A message containing logged data (see also MAV_CMD_LOGGING_START)
###LOGGING_DATA_ACKED
- 267
- A message containing logged data which requires a LOGGING_ACK to be sent back
###LOGGING_ACK
- 268
- An ack for a LOGGING_DATA_ACKED message