Subset of Common Set

These messages are reproduced from the original documentation at mavlink.io – MAVLink Common Message Set. This is only a subset of the full list, including only messages used in the MARSH project, to make the protocol less overwhelming.

Before designing a new message, first check the original documentation linked above. If you find a useful message in the common set, consider editing the list of identifiers used for generating this page.

Conventions

Message MANUAL_SETPOINT is used for desired control positions (as displayed in Lidia), so the values for all fields should be treated as normalized controls positions between -1 and 1 instead of rad/s. It is not supported by ArduPilot at all, and only used for Rover in PX4, so no collisions are expected.

Message RAW_RPM for helicopters should send rotor with index 0, and then engines in order.

The message SIM_STATE and other messages with accelerations, report them as would be measured by an on-board accelerometer. The values correspond to accelerations in the body reference frame axes: X forward, Y right, Z down. The gravity should also be included, so for a stationary and horizontal vehicle the acceleration vector in meters per second squared is [0, 0, -9.80665], with X component becoming positive as it accelerates forward (tested with ArduPilot SITL).

Specifically message SIM_STATE should be sent with attitude encoded both as quaternion and Euler angles if possible. If a sender is outputting only Euler angles, the quaternion should be sent as [0, 0, 0, 0] (instead of [1, 0, 0, 0] for identity rotation). The receivers can detect if the quaternion contains valid data by comparing the vector magnitude (all components squared) to 1 with some tolerance for numeric error.

Definition list

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

MAVLink Include Files: standard.xml

MAVLink Protocol Version

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

This file has protocol dialect: 0.

MAVLink Type Enumerations

MAV_PARAM_TYPE

[Enum] Specifies the datatype of a MAVLink parameter.

Value Field Name Description
1 MAV_PARAM_TYPE_UINT8 8-bit unsigned integer
2 MAV_PARAM_TYPE_INT8 8-bit signed integer
3 MAV_PARAM_TYPE_UINT16 16-bit unsigned integer
4 MAV_PARAM_TYPE_INT16 16-bit signed integer
5 MAV_PARAM_TYPE_UINT32 32-bit unsigned integer
6 MAV_PARAM_TYPE_INT32 32-bit signed integer
7 MAV_PARAM_TYPE_UINT64 64-bit unsigned integer
8 MAV_PARAM_TYPE_INT64 64-bit signed integer
9 MAV_PARAM_TYPE_REAL32 32-bit floating-point
10 MAV_PARAM_TYPE_REAL64 64-bit floating-point

MAV_SEVERITY

[Enum] Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/.

Value Field Name Description
0 MAV_SEVERITY_EMERGENCY System is unusable. This is a "panic" condition.
1 MAV_SEVERITY_ALERT Action should be taken immediately. Indicates error in non-critical systems.
2 MAV_SEVERITY_CRITICAL Action must be taken immediately. Indicates failure in a primary system.
3 MAV_SEVERITY_ERROR Indicates an error in secondary/redundant systems.
4 MAV_SEVERITY_WARNING Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.
5 MAV_SEVERITY_NOTICE An unusual event has occurred, though not an error condition. This should be investigated for the root cause.
6 MAV_SEVERITY_INFO Normal operational messages. Useful for logging. No action is required for these messages.
7 MAV_SEVERITY_DEBUG Useful non-operational messages that can assist in debugging. These should not occur during normal operation.

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.

Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries

MAVLink Messages

PARAM_REQUEST_READ ( #20 )

[Message] 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 https://mavlink.io/en/services/parameter.html for a full documentation of QGroundControl and IMU code.

Field Name Type Description
target_system uint8_t System ID
target_component uint8_t Component ID
param_id char[16] Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_index int16_t Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)

PARAM_REQUEST_LIST ( #21 )

[Message] Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html

Field Name Type Description
target_system uint8_t System ID
target_component uint8_t Component ID

PARAM_VALUE ( #22 )

[Message] 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. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html

Field Name Type Values Description
param_id char[16] Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_value float Onboard parameter value
param_type uint8_t MAV_PARAM_TYPE Onboard parameter type.
param_count uint16_t Total number of onboard parameters
param_index uint16_t Index of this onboard parameter

PARAM_SET ( #23 )

[Message] Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at https://mavlink.io/en/services/parameter.html. PARAM_SET may also be called within the context of a transaction (started with MAV_CMD_PARAM_TRANSACTION). Within a transaction the receiving component should respond with PARAM_ACK_TRANSACTION to the setter component (instead of broadcasting PARAM_VALUE), and PARAM_SET should be re-sent if this is ACK not received.

Field Name Type Values Description
target_system uint8_t System ID
target_component uint8_t Component ID
param_id char[16] Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
param_value float Onboard parameter value
param_type uint8_t MAV_PARAM_TYPE Onboard parameter type.

ATTITUDE ( #30 )

[Message] The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic).

Field Name Type Units Description
time_boot_ms uint32_t ms Timestamp (time since system boot).
roll float rad Roll angle (-pi..+pi)
pitch float rad Pitch angle (-pi..+pi)
yaw float rad Yaw angle (-pi..+pi)
rollspeed float rad/s Roll angular speed
pitchspeed float rad/s Pitch angular speed
yawspeed float rad/s Yaw angular speed

LOCAL_POSITION_NED ( #32 )

[Message] 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)

Field Name Type Units Description
time_boot_ms uint32_t ms Timestamp (time since system boot).
x float m X Position
y float m Y Position
z float m Z Position
vx float m/s X Speed
vy float m/s Y Speed
vz float m/s Z Speed

MANUAL_CONTROL ( #69 )

[Message] 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 and buttons states are transmitted as individual on/off bits of a bitmask

Field Name Type Description
target uint8_t The system to be controlled.
x int16_t X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
y int16_t Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
z int16_t Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.
r int16_t R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
buttons uint16_t A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
buttons2 ** uint16_t A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.
enabled_extensions ** uint8_t Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6
s ** int16_t Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid.
t ** int16_t Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid.
aux1 ** int16_t Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset.
aux2 ** int16_t Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset.
aux3 ** int16_t Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset.
aux4 ** int16_t Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset.
aux5 ** int16_t Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset.
aux6 ** int16_t Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset.

MANUAL_SETPOINT ( #81 )

[Message] Setpoint in roll, pitch, yaw and thrust from the operator

Field Name Type Units Description
time_boot_ms uint32_t ms Timestamp (time since system boot).
roll float rad/s Desired roll rate
pitch float rad/s Desired pitch rate
yaw float rad/s Desired yaw rate
thrust float Collective thrust, normalized to 0 .. 1
mode_switch uint8_t Flight mode switch position, 0.. 255
manual_override_switch uint8_t Override mode switch position, 0.. 255

SIM_STATE ( #108 )

[Message] Status of simulation environment, if used

Field Name Type Units Description
q1 float True attitude quaternion component 1, w (1 in null-rotation)
q2 float True attitude quaternion component 2, x (0 in null-rotation)
q3 float True attitude quaternion component 3, y (0 in null-rotation)
q4 float True attitude quaternion component 4, z (0 in null-rotation)
roll float rad Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
pitch float rad Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
yaw float rad Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
xacc float m/s/s X acceleration
yacc float m/s/s Y acceleration
zacc float m/s/s Z acceleration
xgyro float rad/s Angular speed around X axis
ygyro float rad/s Angular speed around Y axis
zgyro float rad/s Angular speed around Z axis
lat float deg Latitude (lower precision). Both this and the lat_int field should be set.
lon float deg Longitude (lower precision). Both this and the lon_int field should be set.
alt float m Altitude
std_dev_horz float Horizontal position standard deviation
std_dev_vert float Vertical position standard deviation
vn float m/s True velocity in north direction in earth-fixed NED frame
ve float m/s True velocity in east direction in earth-fixed NED frame
vd float m/s True velocity in down direction in earth-fixed NED frame
lat_int ** int32_t degE7 Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred).
lon_int ** int32_t degE7 Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred).

STATUSTEXT ( #253 )

[Message] 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).

Field Name Type Values Description
severity uint8_t MAV_SEVERITY Severity of status. Relies on the definitions within RFC-5424.
text char[50] Status text message, without null termination character
id ** uint16_t Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.
chunk_seq ** uint8_t This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.

RAW_RPM ( #339 )

[Message] (MAVLink 2) RPM sensor data message.

Field Name Type Units Description
index uint8_t Index of this RPM sensor (0-indexed)
frequency float rpm Indicated rate