The system time is the time of the master clock, typically the computer clock of the main onboard computer.
Timestamp of the master clock in microseconds since UNIX epoch.
Timestamp of the component clock since boot time in milliseconds.
UTC date and time from GPS module
GPS UTC date ddmmyy
GPS UTC time hhmmss
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.
Number of satellites visible
Global satellite ID
0: Satellite not used, 1: used for localization
Elevation (0: right on top of receiver, 90: on the horizon) of satellite
Direction of satellite, 0: 0 deg, 255: 360 deg.
Signal to noise ratio of satellite
Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed
System ID
Component ID
Sequence
The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
false:0, true:1
autocontinue to next wp
PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
PARAM5 / local: x position, global: latitude
PARAM6 / y position: global: longitude
PARAM7 / z position: global: altitude
Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message.
System ID
Component ID
Sequence
Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between).
System ID
Component ID
Sequence
Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint.
Sequence
Request the overall list of waypoints from the system/component.
System ID
Component ID
This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints.
System ID
Component ID
Number of Waypoints in the Sequence
Delete all waypoints at once.
System ID
Component ID
A certain waypoint 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 waypoint.
Sequence
Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).
System ID
Component ID
0: OK, 1: Error
Outputs of the APM navigation controller. The primary use of this message is to check the response and signs
of the controller before actual flight and to assist with tuning controller parameters
Current desired roll in degrees
Current desired pitch in degrees
Current desired heading in degrees
Bearing to current waypoint/target in degrees
Distance to active waypoint in meters
Current altitude error in meters
Current airspeed error in meters/second
Current crosstrack error on x-y plane in meters
The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint.
x position
y position
z position
yaw orientation in radians, 0 = NORTH
Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.
x position error
y position error
z position error
roll error (radians)
pitch error (radians)
yaw error (radians)
x velocity
y velocity
z velocity
The target requested to send the message stream.
The target requested to send the message stream.
The ID of the requested data stream
The requested interval between two messages of this type
1 to start sending, 0 to stop sending.
The ID of the requested data stream
The requested interval between two messages of this type
1 stream is enabled, 0 stream is stopped.
The system to be controlled
roll
pitch
yaw
thrust
roll control enabled auto:0, manual:1
pitch auto:0, manual:1
yaw auto:0, manual:1
thrust auto:0, manual:1
The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 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.
System ID
Component ID
RC channel 1 value, in microseconds
RC channel 2 value, in microseconds
RC channel 3 value, in microseconds
RC channel 4 value, in microseconds
RC channel 5 value, in microseconds
RC channel 6 value, in microseconds
RC channel 7 value, in microseconds
RC channel 8 value, in microseconds
Metrics typically displayed on a HUD for fixed wing aircraft
Current airspeed in m/s
Current ground speed in m/s
Current heading in degrees, in compass units (0..360, 0=north)
Current throttle setting in integer percent, 0 to 100
Current altitude (MSL), in meters
Current climb rate in meters/second
Sent from simulation to autopilot. This packet is useful for high throughput
applications such as hardware in the loop simulations.
Timestamp (microseconds since UNIX epoch or microseconds since system boot)
Roll angle (rad)
Pitch angle (rad)
Yaw angle (rad)
Roll angular speed (rad/s)
Pitch angular speed (rad/s)
Yaw angular speed (rad/s)
Latitude, expressed as * 1E7
Longitude, expressed as * 1E7
Altitude in meters, expressed as * 1000 (millimeters)
Ground X Speed (Latitude), expressed as m/s * 100
Ground Y Speed (Longitude), expressed as m/s * 100
Ground Z Speed (Altitude), expressed as m/s * 100
X acceleration (mg)
Y acceleration (mg)
Z acceleration (mg)
Sent from autopilot to simulation. Hardware in the loop control outputs
Timestamp (microseconds since UNIX epoch or microseconds since system boot)
Control output -1 .. 1
Control output -1 .. 1
Control output -1 .. 1
Throttle 0 .. 1
Aux 1, -1 .. 1
Aux 2, -1 .. 1
Aux 3, -1 .. 1
Aux 4, -1 .. 1
System mode (MAV_MODE)
Navigation mode (MAV_NAV_MODE)
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.
Timestamp (microseconds since UNIX epoch or microseconds since system boot)
RC channel 1 value, in microseconds
RC channel 2 value, in microseconds
RC channel 3 value, in microseconds
RC channel 4 value, in microseconds
RC channel 5 value, in microseconds
RC channel 6 value, in microseconds
RC channel 7 value, in microseconds
RC channel 8 value, in microseconds
RC channel 9 value, in microseconds
RC channel 10 value, in microseconds
RC channel 11 value, in microseconds
RC channel 12 value, in microseconds
Receive signal strength indicator, 0: 0%, 255: 100%
Optical flow from a flow sensor (e.g. optical mouse sensor)
Timestamp (UNIX)
Sensor ID
Flow in pixels in x-sensor direction
Flow in pixels in y-sensor direction
Optical flow quality / confidence. 0: bad, 255: maximum quality
Ground distance in meters
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.
Starting address of the debug variables
Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
Memory contents at specified address
Name
Timestamp
x
y
z
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.
Name of the debug variable
Floating point value
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.
Name of the debug variable
Signed integer value
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).
Severity of status, 0 = info message, 255 = critical fault
Status text message, without null termination character
Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.
index of debug variable
DEBUG value