diff --git a/message_definitions/v1.0/common.xml b/message_definitions/v1.0/common.xml
index 1f6e6c77aff..ba3fe4af947 100644
--- a/message_definitions/v1.0/common.xml
+++ b/message_definitions/v1.0/common.xml
@@ -23,7 +23,7 @@
- Flags to report failure cases over the high latency telemtry.
+ Flags to report failure cases over the high latency telemetry.
GPS failure.
@@ -49,7 +49,7 @@
Battery failure/critical low battery.
- RC receiver failure/no rc connection.
+ RC receiver failure/no RC connection.
Offboard link failure.
@@ -170,7 +170,7 @@
0x8000 motor outputs / control
- 0x10000 rc receiver
+ 0x10000 RC receiver
0x20000 2nd 3D gyro
@@ -216,10 +216,10 @@
- Co-ordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles.
-
+ Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles.
+
Global frames use the following naming conventions:
- - "GLOBAL": Global co-ordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default.
+ - "GLOBAL": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default.
The following modifiers may be used with "GLOBAL":
- "RELATIVE_ALT": Altitude is relative to the vehicle home position rather than MSL.
- "TERRAIN_ALT": Altitude is relative to ground level rather than MSL.
@@ -262,7 +262,7 @@
- Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/accelaration values.
+ Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values.
@@ -276,7 +276,7 @@
Global (WGS84) coordinate frame (scaled) with AGL altitude (altitude at ground level).
- FRD local tangent frame (x: Forward, y: Right, z: Down) with origin that travels with vehicle. The forward axis is aligned to the front of the vehicle in the horizontal plane.
+ FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.
@@ -378,6 +378,7 @@
Velocity limiting active to prevent breach
+
All fence types
@@ -397,9 +398,10 @@
- Enumeration of possible mount operation modes
+
+ Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages.
- Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization
+ Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization
Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory.
@@ -417,10 +419,9 @@
Gimbal tracks system with specified system ID
- Gimbal tracks home location
+ Gimbal tracks home position
-
Gimbal device (low level) capability flags (bitmap).
@@ -457,7 +458,7 @@
Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available).
- Gimbal device supports yawing/panning infinetely (e.g. using slip disk).
+ Gimbal device supports yawing/panning infinitely (e.g. using slip disk).
Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME.
@@ -520,7 +521,7 @@
Flags for gimbal device (lower level) operation.
- Set to retracted safe position (no stabilization), takes presedence over all other flags.
+ Set to retracted safe position (no stabilization), takes precedence over all other flags.
Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation.
@@ -774,7 +775,7 @@
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
- Navigate to waypoint.
+ Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION).
Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)
Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)
0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.
@@ -1079,7 +1080,7 @@
Empty
- Change speed and/or throttle set points
+ Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change
Speed type of value set in param2 (such as airspeed, ground speed, and so on)
Speed (-1 indicates no change, -2 indicates return to default vehicle speed)
Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value)
@@ -1099,6 +1100,7 @@
Altitude
+
Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.
Parameter number
Parameter value
@@ -1223,7 +1225,7 @@
Empty
- Reposition the vehicle to a specific WGS84 global position.
+ Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead).
Ground speed, less than 0 (-1) for default
Bitmask of option flags.
Loiter radius for planes. Positive values only, direction is controlled by Yaw value. A value of zero or NaN is ignored.
@@ -1361,7 +1363,13 @@
Empty
- Mission command to enable the geofence
+
+ Enable the geofence.
+ This can be used in a mission or via the command protocol.
+ The persistence/lifetime of the setting is undefined.
+ Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission.
+ Flight stacks typically reset the setting to system defaults on reboot.
+
enable? (0=disable, 1=enable, 2=disable_floor_only)
Fence types to enable or disable as a bitmask. A value of 0 indicates that all fences should be enabled or disabled. This parameter is ignored if param 1 has the value 2
Empty
@@ -1441,6 +1449,7 @@
Empty
+
Mission command to control a camera or antenna mount, using a quaternion as reference.
quaternion param q1, w (1 in null-rotation)
quaternion param q2, x (0 in null-rotation)
@@ -1488,7 +1497,6 @@
Empty
Empty
Empty
- Empty
Empty
Empty
@@ -1552,6 +1560,7 @@
Reserved (set to 0)
WIP: ID (e.g. camera ID -1 for all IDs)
+
Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position.
MAV_GOTO_DO_HOLD: pause mission and either hold or move to specified position (depending on param2), MAV_GOTO_DO_CONTINUE: resume mission.
@@ -1870,8 +1879,8 @@
Landing gear position (Down: 0, Up: 1, NaN for no change)
-
-
+
+
@@ -1968,6 +1977,7 @@
Longitude
Reserved
+
Rally point. You can have multiple rally points defined.
@@ -2012,9 +2022,11 @@
Reserved (set to 0)
Reserved (set to 0)
+
+
Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.
Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.
Desired approach vector in compass heading. A negative value indicates the system can define the approach vector at will.
@@ -2025,6 +2037,7 @@
Altitude (MSL)
+
Control the payload deployment.
Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deployment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.
Reserved
@@ -2049,7 +2062,7 @@
Command to operate winch.
Winch instance number.
Action to perform.
- Length of cable to release (negative to wind).
+ Length of line to release (negative to wind).
Release rate (negative to wind).
Empty.
Empty.
@@ -2239,7 +2252,7 @@
Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.
- Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.
+ Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages.
Dependent on the autopilot
@@ -2683,14 +2696,17 @@
Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability.
- Autopilot supports MISSION float message type.
+ Autopilot supports the MISSION_ITEM float message type.
+ Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead.
+
Autopilot supports the new param float message type.
- This flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated).
- Autopilot supports MISSION_ITEM_INT scaled integer message type.
+ Autopilot supports MISSION_ITEM_INT scaled integer message type.
+ Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated).
+
Autopilot supports COMMAND_INT scaled integer message type.
@@ -3311,7 +3327,7 @@
Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS).
- Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE) (WIP).
+ Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE).
@@ -3323,7 +3339,7 @@
Stream is thermal imaging
- Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE). (WIP).
+ Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE).
@@ -3447,7 +3463,7 @@
- Result from PARAM_EXT_SET message (or a PARAM_SET within a transaction).
+ Result from PARAM_EXT_SET message.
Parameter value ACCEPTED and SET
@@ -3458,7 +3474,7 @@
Parameter failed to set
- Parameter value received but not yet set/accepted. A subsequent PARAM_ACK_TRANSACTION or PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating taht the the parameter was recieved and does not need to be resent.
+ Parameter value received but not yet set/accepted. A subsequent PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent.
@@ -3635,7 +3651,6 @@
Release parachute and kill motors.
-
Encoding of payload unknown.
@@ -4274,7 +4289,7 @@
Timestamp (time since system boot).
- to be removed / merged with SYSTEM_TIME
+ To be removed / merged with TIMESYNC
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. The ping microservice is documented at https://mavlink.io/en/services/ping.html
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
PING sequence
@@ -4330,7 +4345,7 @@
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.
-
+
System ID
Component ID
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
@@ -4339,32 +4354,32 @@
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.
+ NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate.
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
GPS fix type.
Latitude (WGS84, EGM96 ellipsoid)
Longitude (WGS84, EGM96 ellipsoid)
Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
- GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
- GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
- GPS ground speed. If unknown, set to: UINT16_MAX
- Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
- Number of satellites visible. If unknown, set to 255
+ GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
+ GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
+ GPS ground speed. If unknown, set to: UINT16_MAX
+ Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
+ Number of satellites visible. If unknown, set to UINT8_MAX
Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
Position uncertainty.
Altitude uncertainty.
- Speed uncertainty.
+ Speed uncertainty.
Heading / track uncertainty
- Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
+ Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
- 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.
+ 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_INT 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.
+ Direction of satellite, 0: 0 deg, 255: 360 deg.
Signal to noise ratio of satellite
@@ -4402,8 +4417,8 @@
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.
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
Absolute pressure (raw)
- Differential pressure 1 (raw, 0 if nonexistent)
- Differential pressure 2 (raw, 0 if nonexistent)
+ Differential pressure 1 (raw, 0 if nonexistent)
+ Differential pressure 2 (raw, 0 if nonexistent)
Raw Temperature measurement (raw)
@@ -4413,7 +4428,7 @@
Differential pressure 1
Absolute pressure temperature
- Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
+ Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).
@@ -4459,7 +4474,7 @@
Ground X Speed (Latitude, positive north)
Ground Y Speed (Longitude, positive east)
Ground Z Speed (Altitude, positive down)
- Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
+ Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to UINT16_MAX.
@@ -4608,7 +4623,7 @@
Mission type.
- Sets the GPS co-ordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor.
+ Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor.
System ID
Latitude (WGS84)
Longitude (WGS84)
@@ -4617,7 +4632,7 @@
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
- Publishes the GPS co-ordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message.
+ Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message.
Latitude (WGS84)
Longitude (WGS84)
Altitude (MSL). Positive for up.
@@ -4644,6 +4659,7 @@
Mission type.
+
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/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations.
System ID
@@ -4676,7 +4692,7 @@
Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
- The state of the fixed wing navigation and position controller.
+ The state of the navigation and position controller.
Current desired roll
Current desired pitch
Current desired heading
@@ -4753,7 +4769,7 @@
1 stream is enabled, 0 stream is stopped.
- 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
+ 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
The system to be controlled.
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-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.
@@ -5028,7 +5044,7 @@
RC channel 10 value
RC channel 11 value
RC channel 12 value
- Receive signal strength indicator in device-dependent units/scale. Values: [0-254], 255: invalid/unknown.
+ Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown.
Sent from autopilot to simulation. Hardware in the loop control outputs (replacement for HIL_CONTROLS)
@@ -5192,7 +5208,7 @@
Count of error corrected radio packets (since boot).
- File transfer message
+ File transfer protocol message: https://mavlink.io/en/services/ftp.html.
Network ID (0 for broadcast)
System ID (0 for broadcast)
Component ID (0 for broadcast)
@@ -5210,20 +5226,20 @@
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.
+ NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate.
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
Latitude (WGS84)
Longitude (WGS84)
Altitude (MSL). Positive for up.
- GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
- GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
- GPS ground speed. If unknown, set to: 65535
+ GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
+ GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
+ GPS ground speed. If unknown, set to: UINT16_MAX
GPS velocity in north direction in earth-fixed NED frame
GPS velocity in east direction in earth-fixed NED frame
GPS velocity in down direction in earth-fixed NED frame
- Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
- Number of satellites visible. If unknown, set to 255
+ Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
+ Number of satellites visible. If unknown, set to UINT8_MAX
GPS ID (zero indexed). Used for multiple GPS inputs
Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
@@ -5241,7 +5257,7 @@
Temperature
Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
Time since the distance was sampled.
- Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
+ Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance.
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.
@@ -5275,7 +5291,7 @@
Y Magnetic field
Z Magnetic field
- Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).
+ Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).
Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0.
@@ -5289,7 +5305,7 @@
Log id
Total number of logs
High log number
- UTC timestamp of log since 1970, or 0 if not available
+ UTC timestamp of log since 1970, or 0 if not available
Size of the log (may be approximate)
@@ -5339,11 +5355,11 @@
Number of DGPS satellites
Age of DGPS info
- Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
+ Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
Position uncertainty.
Altitude uncertainty.
- Speed uncertainty.
+ Speed uncertainty.
Heading / track uncertainty
@@ -5406,7 +5422,7 @@
Y Magnetic field
Z Magnetic field
- Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).
+ Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C).
Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: https://mavlink.io/en/services/image_transmission.html.
@@ -5432,7 +5448,7 @@
Type of distance sensor.
Onboard ID of the sensor
Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
- Measurement variance. Max standard deviation is 6cm. 255 if unknown.
+ Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown.
Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
@@ -5476,7 +5492,7 @@
Differential pressure
Absolute pressure temperature
- Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
+ Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
Motion capture attitude and position
@@ -5527,7 +5543,7 @@
Differential pressure
Absolute pressure temperature
- Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
+ Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC.
Current motion information from a designated system
@@ -5555,7 +5571,7 @@
X position in local frame
Y position in local frame
Z position in local frame
- Airspeed, set to -1 if unknown
+ Airspeed, set to -1 if unknown
Variance of body velocity estimate
Variance in local position
The attitude, represented as Quaternion
@@ -5613,7 +5629,7 @@
Z Position of the landing target in MAV_FRAME
Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
Type of landing target
- Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
+ Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
@@ -5710,8 +5726,8 @@
Latitude (WGS84)
Longitude (WGS84)
Altitude (MSL). Positive for up.
- GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
- GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
+ GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
+ GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
GPS velocity in north direction in earth-fixed NED frame
GPS velocity in east direction in earth-fixed NED frame
GPS velocity in down direction in earth-fixed NED frame
@@ -5747,7 +5763,7 @@
airspeed setpoint
groundspeed
climb rate
- Number of satellites visible. If unknown, set to 255
+ Number of satellites visible. If unknown, set to UINT8_MAX
GPS Fix type.
Remaining battery (percentage)
Autopilot temperature (degrees C)
@@ -5779,7 +5795,7 @@
Maximum error vertical position since last message
Air temperature from airspeed sensor
Maximum climb rate magnitude since last message
- Battery level (-1 if field not provided).
+ Battery level (-1 if field not provided).
Current waypoint number
Bitmap of failure flags.
Field for custom payload.
@@ -5829,7 +5845,11 @@
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
- The interval between messages for a particular MAVLink message ID. This message is the response to the MAV_CMD_GET_MESSAGE_INTERVAL command. This interface replaces DATA_STREAM.
+
+ The interval between messages for a particular MAVLink message ID.
+ This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required).
+ It may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL.
+ This interface replaces DATA_STREAM.
The ID of the requested MAVLink message. v1.0 is limited to 254 messages.
The interval between two messages. A value of -1 indicates this stream is disabled, 0 indicates it is not available, > 0 indicates the interval at which it is sent.
@@ -5875,7 +5895,7 @@
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
+ 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
@@ -6023,7 +6043,7 @@
component ID of the target
sequence number (can wrap)
data length
- offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
+ offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists).
logged data
@@ -6032,7 +6052,7 @@
component ID of the target
sequence number (can wrap)
data length
- offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
+ offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists).
logged data
@@ -6151,7 +6171,7 @@
High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.
System ID
Component ID
- High level gimbal manager flags to use.
+ High level gimbal manager flags to use.
Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
X component of angular velocity, positive is rolling to the right, NaN to be ignored.
@@ -6250,7 +6270,7 @@
Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation.
System ID
Component ID
- High level gimbal manager flags to use.
+ High level gimbal manager flags to use.
Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
Pitch angle (positive: up, negative: down, NaN to be ignored).
Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).
@@ -6261,7 +6281,7 @@
High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case.
System ID
Component ID
- High level gimbal manager flags.
+ High level gimbal manager flags.
Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).
Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
@@ -6274,7 +6294,6 @@
Password. Blank for an open AP. MD5 hash when message is sent back as a response.
-
The location and information of an AIS vessel
Mobile Marine Service Identifier, 9 decimal digits
Latitude
@@ -6314,7 +6333,7 @@
Hardware unique 128-bit ID.
Software major version number.
Software minor version number.
- Version control system (VCS) revision identifier (e.g. git short commit hash). Zero if unknown.
+ Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown.
Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response.
@@ -6355,7 +6374,7 @@
Obstacle distances in front of the sensor, starting from the left in increment degrees to the right
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
Class id of the distance sensor type.
- Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.
+ Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.
Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.
Minimum distance the sensor can measure.
Maximum distance the sensor can measure.
@@ -6425,8 +6444,6 @@
1: Receiving session pending, 0: No receiving session pending.
-
-
RPM sensor data message.
Index of this RPM sensor (0-indexed)
Indicated rate
@@ -6448,7 +6465,7 @@
Next waypoint, latitude (WGS84)
Next waypoint, longitude (WGS84)
Next waypoint, altitude (WGS84)
- Time until next update. Set to 0 if unknown or in data driven mode.
+ Time until next update. Set to 0 if unknown or in data driven mode.
Flight state
Bitwise OR combination of the data available flags.
@@ -6519,7 +6536,7 @@
A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD.
System ID.
Component ID.
- bus number
+ Bus number
Frame length
Frame ID
Frame data
@@ -6552,12 +6569,12 @@
Winch status.
Timestamp (synced to UNIX time or since system boot).
- Length of line released. NaN if unknown
- Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown
- Tension on the line. NaN if unknown
- Voltage of the battery supplying the winch. NaN if unknown
- Current draw from the winch. NaN if unknown
- Temperature of the motor. INT16_MAX if unknown
+ Length of line released. NaN if unknown
+ Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown
+ Tension on the line. NaN if unknown
+ Voltage of the battery supplying the winch. NaN if unknown
+ Current draw from the winch. NaN if unknown
+ Temperature of the motor. INT16_MAX if unknown
Status flags
@@ -6662,7 +6679,7 @@
System ID (0 for broadcast).
Component ID (0 for broadcast).
Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
- This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length.
+ This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length.
Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9.
Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.