Minimal Set

These are the messages which must be supported by any MAVLink system, reproduced from the original documentation at mavlink.io – MAVLink Minimal Set.

The HEARTBEAT message is of special interest here, since it is used to communicate the node state to and from the Manager application.

Generally the nodes in the simulator system are expected to send MAV_AUTOPILOT_INVALID. When choosing a component id, first see if there is a more specific one in MARSH_COMPONENT, otherwise use the standard values here.

Definition list

Generated on 2024-09-04T13:00:31 from commit c0d8d14

MAVLink Protocol Version

The current MAVLink version is 2.3. The minor version numbers (after the dot) range from 1-255.

MAVLink Type Enumerations

MAV_AUTOPILOT

[Enum] Micro air vehicle / autopilot classes. This identifies the individual model.

Value Field Name Description
0 MAV_AUTOPILOT_GENERIC Generic autopilot, full support for everything
1 MAV_AUTOPILOT_RESERVED Reserved for future use.
2 MAV_AUTOPILOT_SLUGS SLUGS autopilot, http://slugsuav.soe.ucsc.edu
3 MAV_AUTOPILOT_ARDUPILOTMEGA ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org
4 MAV_AUTOPILOT_OPENPILOT OpenPilot, http://openpilot.org
5 MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY Generic autopilot only supporting simple waypoints
6 MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY Generic autopilot supporting waypoints and other simple navigation commands
7 MAV_AUTOPILOT_GENERIC_MISSION_FULL Generic autopilot supporting the full mission command set
8 MAV_AUTOPILOT_INVALID No valid autopilot, e.g. a GCS or other MAVLink component
9 MAV_AUTOPILOT_PPZ PPZ UAV - http://nongnu.org/paparazzi
10 MAV_AUTOPILOT_UDB UAV Dev Board
11 MAV_AUTOPILOT_FP FlexiPilot
12 MAV_AUTOPILOT_PX4 PX4 Autopilot - http://px4.io/
13 MAV_AUTOPILOT_SMACCMPILOT SMACCMPilot - http://smaccmpilot.org
14 MAV_AUTOPILOT_AUTOQUAD AutoQuad -- http://autoquad.org
15 MAV_AUTOPILOT_ARMAZILA Armazila -- http://armazila.com
16 MAV_AUTOPILOT_AEROB Aerob -- http://aerob.ru
17 MAV_AUTOPILOT_ASLUAV ASLUAV autopilot -- http://www.asl.ethz.ch
18 MAV_AUTOPILOT_SMARTAP SmartAP Autopilot - http://sky-drones.com
19 MAV_AUTOPILOT_AIRRAILS AirRails - http://uaventure.com
20 MAV_AUTOPILOT_REFLEX Fusion Reflex - https://fusion.engineering

MAV_TYPE

[Enum] MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA).

Value Field Name Description
0 MAV_TYPE_GENERIC Generic micro air vehicle
1 MAV_TYPE_FIXED_WING Fixed wing aircraft.
2 MAV_TYPE_QUADROTOR Quadrotor
3 MAV_TYPE_COAXIAL Coaxial helicopter
4 MAV_TYPE_HELICOPTER Normal helicopter with tail rotor.
5 MAV_TYPE_ANTENNA_TRACKER Ground installation
6 MAV_TYPE_GCS Operator control unit / ground control station
7 MAV_TYPE_AIRSHIP Airship, controlled
8 MAV_TYPE_FREE_BALLOON Free balloon, uncontrolled
9 MAV_TYPE_ROCKET Rocket
10 MAV_TYPE_GROUND_ROVER Ground rover
11 MAV_TYPE_SURFACE_BOAT Surface vessel, boat, ship
12 MAV_TYPE_SUBMARINE Submarine
13 MAV_TYPE_HEXAROTOR Hexarotor
14 MAV_TYPE_OCTOROTOR Octorotor
15 MAV_TYPE_TRICOPTER Tricopter
16 MAV_TYPE_FLAPPING_WING Flapping wing
17 MAV_TYPE_KITE Kite
18 MAV_TYPE_ONBOARD_CONTROLLER Onboard companion controller
19 MAV_TYPE_VTOL_TAILSITTER_DUOROTOR Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR.
20 MAV_TYPE_VTOL_TAILSITTER_QUADROTOR Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR.
21 MAV_TYPE_VTOL_TILTROTOR Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight.
22 MAV_TYPE_VTOL_FIXEDROTOR VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases.
23 MAV_TYPE_VTOL_TAILSITTER Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate.
24 MAV_TYPE_VTOL_TILTWING Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode.
25 MAV_TYPE_VTOL_RESERVED5 VTOL reserved 5
26 MAV_TYPE_GIMBAL Gimbal
27 MAV_TYPE_ADSB ADSB system
28 MAV_TYPE_PARAFOIL Steerable, nonrigid airfoil
29 MAV_TYPE_DODECAROTOR Dodecarotor
30 MAV_TYPE_CAMERA Camera
31 MAV_TYPE_CHARGING_STATION Charging station
32 MAV_TYPE_FLARM FLARM collision avoidance system
33 MAV_TYPE_SERVO Servo
34 MAV_TYPE_ODID Open Drone ID. See https://mavlink.io/en/services/opendroneid.html.
35 MAV_TYPE_DECAROTOR Decarotor
36 MAV_TYPE_BATTERY Battery
37 MAV_TYPE_PARACHUTE Parachute
38 MAV_TYPE_LOG Log
39 MAV_TYPE_OSD OSD
40 MAV_TYPE_IMU IMU
41 MAV_TYPE_GPS GPS
42 MAV_TYPE_WINCH Winch
43 MAV_TYPE_GENERIC_MULTIROTOR Generic multirotor that does not fit into a specific type or whose type is unknown

MAV_MODE_FLAG

[Enum] These flags encode the MAV mode.

Value Field Name Description
128 MAV_MODE_FLAG_SAFETY_ARMED 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state.
64 MAV_MODE_FLAG_MANUAL_INPUT_ENABLED 0b01000000 remote control input is enabled.
32 MAV_MODE_FLAG_HIL_ENABLED 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.
16 MAV_MODE_FLAG_STABILIZE_ENABLED 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.
8 MAV_MODE_FLAG_GUIDED_ENABLED 0b00001000 guided mode enabled, system flies waypoints / mission items.
4 MAV_MODE_FLAG_AUTO_ENABLED 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.
2 MAV_MODE_FLAG_TEST_ENABLED 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.
1 MAV_MODE_FLAG_CUSTOM_MODE_ENABLED 0b00000001 Reserved for future use.

MAV_MODE_FLAG_DECODE_POSITION

[Enum] These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.

Value Field Name Description
128 MAV_MODE_FLAG_DECODE_POSITION_SAFETY First bit: 10000000
64 MAV_MODE_FLAG_DECODE_POSITION_MANUAL Second bit: 01000000
32 MAV_MODE_FLAG_DECODE_POSITION_HIL Third bit: 00100000
16 MAV_MODE_FLAG_DECODE_POSITION_STABILIZE Fourth bit: 00010000
8 MAV_MODE_FLAG_DECODE_POSITION_GUIDED Fifth bit: 00001000
4 MAV_MODE_FLAG_DECODE_POSITION_AUTO Sixth bit: 00000100
2 MAV_MODE_FLAG_DECODE_POSITION_TEST Seventh bit: 00000010
1 MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE Eighth bit: 00000001

MAV_STATE

[Enum]

Value Field Name Description
0 MAV_STATE_UNINIT Uninitialized system, state is unknown.
1 MAV_STATE_BOOT System is booting up.
2 MAV_STATE_CALIBRATING System is calibrating and not flight-ready.
3 MAV_STATE_STANDBY System is grounded and on standby. It can be launched any time.
4 MAV_STATE_ACTIVE System is active and might be already airborne. Motors are engaged.
5 MAV_STATE_CRITICAL System is in a non-normal flight mode (failsafe). It can however still navigate.
6 MAV_STATE_EMERGENCY System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down.
7 MAV_STATE_POWEROFF System just initialized its power-down sequence, will shut down now.
8 MAV_STATE_FLIGHT_TERMINATION System is terminating itself (failsafe or commanded).

MAV_COMPONENT

[Enum] Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded.

Value Field Name Description
0 MAV_COMP_ID_ALL Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message.
1 MAV_COMP_ID_AUTOPILOT1 System flight controller component ("autopilot"). Only one autopilot is expected in a particular system.
25 MAV_COMP_ID_USER1 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
26 MAV_COMP_ID_USER2 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
27 MAV_COMP_ID_USER3 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
28 MAV_COMP_ID_USER4 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
29 MAV_COMP_ID_USER5 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
30 MAV_COMP_ID_USER6 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
31 MAV_COMP_ID_USER7 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
32 MAV_COMP_ID_USER8 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
33 MAV_COMP_ID_USER9 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
34 MAV_COMP_ID_USER10 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
35 MAV_COMP_ID_USER11 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
36 MAV_COMP_ID_USER12 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
37 MAV_COMP_ID_USER13 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
38 MAV_COMP_ID_USER14 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
39 MAV_COMP_ID_USER15 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
40 MAV_COMP_ID_USER16 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
41 MAV_COMP_ID_USER17 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
42 MAV_COMP_ID_USER18 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
43 MAV_COMP_ID_USER19 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
44 MAV_COMP_ID_USER20 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
45 MAV_COMP_ID_USER21 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
46 MAV_COMP_ID_USER22 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
47 MAV_COMP_ID_USER23 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
48 MAV_COMP_ID_USER24 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
49 MAV_COMP_ID_USER25 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
50 MAV_COMP_ID_USER26 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
51 MAV_COMP_ID_USER27 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
52 MAV_COMP_ID_USER28 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
53 MAV_COMP_ID_USER29 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
54 MAV_COMP_ID_USER30 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
55 MAV_COMP_ID_USER31 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
56 MAV_COMP_ID_USER32 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
57 MAV_COMP_ID_USER33 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
58 MAV_COMP_ID_USER34 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
59 MAV_COMP_ID_USER35 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
60 MAV_COMP_ID_USER36 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
61 MAV_COMP_ID_USER37 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
62 MAV_COMP_ID_USER38 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
63 MAV_COMP_ID_USER39 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
64 MAV_COMP_ID_USER40 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
65 MAV_COMP_ID_USER41 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
66 MAV_COMP_ID_USER42 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
67 MAV_COMP_ID_USER43 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
68 MAV_COMP_ID_TELEMETRY_RADIO Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages).
69 MAV_COMP_ID_USER45 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
70 MAV_COMP_ID_USER46 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
71 MAV_COMP_ID_USER47 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
72 MAV_COMP_ID_USER48 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
73 MAV_COMP_ID_USER49 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
74 MAV_COMP_ID_USER50 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
75 MAV_COMP_ID_USER51 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
76 MAV_COMP_ID_USER52 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
77 MAV_COMP_ID_USER53 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
78 MAV_COMP_ID_USER54 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
79 MAV_COMP_ID_USER55 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
80 MAV_COMP_ID_USER56 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
81 MAV_COMP_ID_USER57 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
82 MAV_COMP_ID_USER58 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
83 MAV_COMP_ID_USER59 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
84 MAV_COMP_ID_USER60 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
85 MAV_COMP_ID_USER61 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
86 MAV_COMP_ID_USER62 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
87 MAV_COMP_ID_USER63 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
88 MAV_COMP_ID_USER64 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
89 MAV_COMP_ID_USER65 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
90 MAV_COMP_ID_USER66 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
91 MAV_COMP_ID_USER67 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
92 MAV_COMP_ID_USER68 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
93 MAV_COMP_ID_USER69 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
94 MAV_COMP_ID_USER70 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
95 MAV_COMP_ID_USER71 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
96 MAV_COMP_ID_USER72 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
97 MAV_COMP_ID_USER73 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
98 MAV_COMP_ID_USER74 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
99 MAV_COMP_ID_USER75 Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network.
100 MAV_COMP_ID_CAMERA Camera #1.
101 MAV_COMP_ID_CAMERA2 Camera #2.
102 MAV_COMP_ID_CAMERA3 Camera #3.
103 MAV_COMP_ID_CAMERA4 Camera #4.
104 MAV_COMP_ID_CAMERA5 Camera #5.
105 MAV_COMP_ID_CAMERA6 Camera #6.
140 MAV_COMP_ID_SERVO1 Servo #1.
141 MAV_COMP_ID_SERVO2 Servo #2.
142 MAV_COMP_ID_SERVO3 Servo #3.
143 MAV_COMP_ID_SERVO4 Servo #4.
144 MAV_COMP_ID_SERVO5 Servo #5.
145 MAV_COMP_ID_SERVO6 Servo #6.
146 MAV_COMP_ID_SERVO7 Servo #7.
147 MAV_COMP_ID_SERVO8 Servo #8.
148 MAV_COMP_ID_SERVO9 Servo #9.
149 MAV_COMP_ID_SERVO10 Servo #10.
150 MAV_COMP_ID_SERVO11 Servo #11.
151 MAV_COMP_ID_SERVO12 Servo #12.
152 MAV_COMP_ID_SERVO13 Servo #13.
153 MAV_COMP_ID_SERVO14 Servo #14.
154 MAV_COMP_ID_GIMBAL Gimbal #1.
155 MAV_COMP_ID_LOG Logging component.
156 MAV_COMP_ID_ADSB Automatic Dependent Surveillance-Broadcast (ADS-B) component.
157 MAV_COMP_ID_OSD On Screen Display (OSD) devices for video links.
158 MAV_COMP_ID_PERIPHERAL Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice.
159 MAV_COMP_ID_QX1_GIMBAL

DEPRECATED: Replaced by MAV_COMP_ID_GIMBAL (2018-11). All gimbals should use MAV_COMP_ID_GIMBAL.

Gimbal ID for QX1.
160 MAV_COMP_ID_FLARM FLARM collision alert component.
161 MAV_COMP_ID_PARACHUTE Parachute component.
169 MAV_COMP_ID_WINCH Winch component.
171 MAV_COMP_ID_GIMBAL2 Gimbal #2.
172 MAV_COMP_ID_GIMBAL3 Gimbal #3.
173 MAV_COMP_ID_GIMBAL4 Gimbal #4
174 MAV_COMP_ID_GIMBAL5 Gimbal #5.
175 MAV_COMP_ID_GIMBAL6 Gimbal #6.
180 MAV_COMP_ID_BATTERY Battery #1.
181 MAV_COMP_ID_BATTERY2 Battery #2.
189 MAV_COMP_ID_MAVCAN CAN over MAVLink client.
190 MAV_COMP_ID_MISSIONPLANNER Component that can generate/supply a mission flight plan (e.g. GCS or developer API).
191 MAV_COMP_ID_ONBOARD_COMPUTER Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
192 MAV_COMP_ID_ONBOARD_COMPUTER2 Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
193 MAV_COMP_ID_ONBOARD_COMPUTER3 Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
194 MAV_COMP_ID_ONBOARD_COMPUTER4 Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on.
195 MAV_COMP_ID_PATHPLANNER Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.).
196 MAV_COMP_ID_OBSTACLE_AVOIDANCE Component that plans a collision free path between two points.
197 MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY Component that provides position estimates using VIO techniques.
198 MAV_COMP_ID_PAIRING_MANAGER Component that manages pairing of vehicle and GCS.
200 MAV_COMP_ID_IMU Inertial Measurement Unit (IMU) #1.
201 MAV_COMP_ID_IMU_2 Inertial Measurement Unit (IMU) #2.
202 MAV_COMP_ID_IMU_3 Inertial Measurement Unit (IMU) #3.
220 MAV_COMP_ID_GPS GPS #1.
221 MAV_COMP_ID_GPS2 GPS #2.
236 MAV_COMP_ID_ODID_TXRX_1 Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
237 MAV_COMP_ID_ODID_TXRX_2 Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
238 MAV_COMP_ID_ODID_TXRX_3 Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet).
240 MAV_COMP_ID_UDP_BRIDGE Component to bridge MAVLink to UDP (i.e. from a UART).
241 MAV_COMP_ID_UART_BRIDGE Component to bridge to UART (i.e. from UDP).
242 MAV_COMP_ID_TUNNEL_NODE Component handling TUNNEL messages (e.g. vendor specific GUI of a component).
250 MAV_COMP_ID_SYSTEM_CONTROL

DEPRECATED: Replaced by MAV_COMP_ID_ALL (2018-11). System control does not require a separate component ID. Instead, system commands should be sent with target_component=MAV_COMP_ID_ALL allowing the target component to use any appropriate component id.

Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.).

MAVLink Commands (MAV_CMD)

MAVLink commands (MAV_CMD) and messages are different! These commands define the values of up to 7 parameters that are packaged INSIDE specific messages used in the Mission Protocol and Command Protocol. Use commands for actions in missions or if you need acknowledgment and/or retry logic from a request. Otherwise use messages.

MAVLink Messages

HEARTBEAT ( #0 )

[Message] The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html

Field Name Type Values Description
type uint8_t MAV_TYPE Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
autopilot uint8_t MAV_AUTOPILOT Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
base_mode uint8_t MAV_MODE_FLAG System mode bitmap.
custom_mode uint32_t A bitfield for use for autopilot-specific flags
system_status uint8_t MAV_STATE System status flag.
mavlink_version uint8_t_mavlink_version MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version

PROTOCOL_VERSION ( #300 )

WORK IN PROGRESS: Do not use in stable production environments (it may change).

[Message] (MAVLink 2) Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly.

Field Name Type Description
version uint16_t Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
min_version uint16_t Minimum MAVLink version supported
max_version uint16_t Maximum MAVLink version supported (set to the same value as version by default)
spec_version_hash uint8_t[8] The first 8 bytes (not characters printed in hex!) of the git hash.
library_version_hash uint8_t[8] The first 8 bytes (not characters printed in hex!) of the git hash.