Skip to content

Commit

Permalink
MAVLink messages update Fri Nov 29 23:51:33 UTC 2024
Browse files Browse the repository at this point in the history
  • Loading branch information
PX4BuildBot committed Nov 29, 2024
1 parent 6b80f9d commit b11302b
Show file tree
Hide file tree
Showing 6 changed files with 256 additions and 18 deletions.
1 change: 1 addition & 0 deletions en/messages/index.md → en/messages/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -62,3 +62,4 @@ The dialect definitions are:
- [paparazzi.xml](paparazzi.md)
- [standard.xml](standard.md)
- [ualberta.xml](ualberta.md)
- [loweheiser.xml](loweheiser.md)
8 changes: 4 additions & 4 deletions en/messages/all.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

# Dialect: all

This dialect is intended to `include` all other [dialects](../messages/index.md) in the [mavlink/mavlink](https://github.com/mavlink/mavlink) repository (including [external dialects](https://github.com/mavlink/mavlink/tree/master/external/dialects#mavlink-external-dialects)).
This dialect is intended to `include` all other [dialects](../messages/README.md) in the [mavlink/mavlink](https://github.com/mavlink/mavlink) repository (including [external dialects](https://github.com/mavlink/mavlink/tree/master/external/dialects#mavlink-external-dialects)).

Dialects that are in **all.xml** are guaranteed to not have clashes in messages, enums, enum ids, and MAV_CMDs.
This ensure that:
Expand Down Expand Up @@ -57,9 +57,9 @@ span.warning {

Type | Defined | Included
--- | --- | ---
[Messages](#messages) | 0 | 364
[Enums](#enumerated-types) | 0 | 235
[Commands](#mav_commands) | 216 | 0
[Messages](#messages) | 0 | 372
[Enums](#enumerated-types) | 0 | 236
[Commands](#mav_commands) | 218 | 0

The following sections list all entities in the dialect (both included and defined in this file).

Expand Down
166 changes: 156 additions & 10 deletions en/messages/ardupilotmega.md
Original file line number Diff line number Diff line change
Expand Up @@ -33,22 +33,25 @@ span.warning {
- [common.xml](../messages/common.md)
- [uAvionix.xml](../messages/uAvionix.md)
- [icarous.xml](../messages/icarous.md)
- [loweheiser.xml](../messages/loweheiser.md)
- [cubepilot.xml](../messages/cubepilot.md)
- [csAirLink.xml](../messages/csAirLink.md)

## Summary

Type | Defined | Included
--- | --- | ---
[Messages](#messages) | 65 | 242
[Enums](#enumerated-types) | 45 | 159
[Commands](#mav_commands) | 195 | 0
[Messages](#messages) | 72 | 243
[Enums](#enumerated-types) | 46 | 159
[Commands](#mav_commands) | 197 | 0

The following sections list all entities in the dialect (both included and defined in this file).

## Messages

### SENSOR_OFFSETS (150) {#SENSOR_OFFSETS}
### SENSOR_OFFSETS (150) — [DEP] {#SENSOR_OFFSETS}

<span class="warning">**DEPRECATED:** Replaced By [MAG_CAL_REPORT](#MAG_CAL_REPORT), Accel Parameters, and Gyro Parameters (2022-02)</span>

Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.

Expand Down Expand Up @@ -786,6 +789,34 @@ request_id | `uint32_t` | Request ID - copied from request.
result | `uint8_t` | 0 for success, anything else is failure code.


### SECURE_COMMAND (11004) {#SECURE_COMMAND}

Send a secure command. Data should be signed with a private key corresponding with a public key known to the recipient. Signature should be over the concatenation of the sequence number (little-endian format), the operation (little-endian format) the data and the session key. For [SECURE_COMMAND_GET_SESSION_KEY](#SECURE_COMMAND_GET_SESSION_KEY) the session key should be zero length. The data array consists of the data followed by the signature. The sum of the data_length and the sig_length cannot be more than 220. The format of the data is command specific.

Field Name | Type | Values | Description
--- | --- | --- | ---
target_system | `uint8_t` | | System ID.
target_component | `uint8_t` | | Component ID.
sequence | `uint32_t` | | Sequence ID for tagging reply.
operation | `uint32_t` | [SECURE_COMMAND_OP](#SECURE_COMMAND_OP) | Operation being requested.
data_length | `uint8_t` | | Data length.
sig_length | `uint8_t` | | Signature length.
data | `uint8_t[220]` | | Signed data.


### SECURE_COMMAND_REPLY (11005) {#SECURE_COMMAND_REPLY}

Reply from secure command.

Field Name | Type | Values | Description
--- | --- | --- | ---
sequence | `uint32_t` | | Sequence ID from request.
operation | `uint32_t` | [SECURE_COMMAND_OP](#SECURE_COMMAND_OP) | Operation that was requested.
result | `uint8_t` | [MAV_RESULT](#MAV_RESULT) | Result of command.
data_length | `uint8_t` | | Data length.
data | `uint8_t[220]` | | Reply data.


### ADAP_TUNING (11010) {#ADAP_TUNING}

Adaptive Controller tuning information.
Expand Down Expand Up @@ -929,9 +960,7 @@ max_value | `float` | | OSD parameter maximum value.
increment | `float` | | OSD parameter increment.


### OBSTACLE_DISTANCE_3D (11037) — [WIP] {#OBSTACLE_DISTANCE_3D}

<span class="warning">**WORK IN PROGRESS**: Do not use in stable production environments (it may change).</span>
### OBSTACLE_DISTANCE_3D (11037) {#OBSTACLE_DISTANCE_3D}

Obstacle located as a 3D vector.

Expand Down Expand Up @@ -980,6 +1009,76 @@ MCU_voltage_min | `uint16_t` | mV | MCU voltage minimum
MCU_voltage_max | `uint16_t` | mV | MCU voltage maximum


### ESC_TELEMETRY_13_TO_16 (11040) {#ESC_TELEMETRY_13_TO_16}

ESC Telemetry Data for ESCs 13 to 16, matching data sent by BLHeli ESCs.

Field Name | Type | Units | Description
--- | --- | --- | ---
temperature | `uint8_t[4]` | degC | Temperature.
voltage | `uint16_t[4]` | cV | Voltage.
current | `uint16_t[4]` | cA | Current.
totalcurrent | `uint16_t[4]` | mAh | Total current.
rpm | `uint16_t[4]` | rpm | RPM (eRPM).
count | `uint16_t[4]` | | count of telemetry packets received (wraps at 65535).


### ESC_TELEMETRY_17_TO_20 (11041) {#ESC_TELEMETRY_17_TO_20}

ESC Telemetry Data for ESCs 17 to 20, matching data sent by BLHeli ESCs.

Field Name | Type | Units | Description
--- | --- | --- | ---
temperature | `uint8_t[4]` | degC | Temperature.
voltage | `uint16_t[4]` | cV | Voltage.
current | `uint16_t[4]` | cA | Current.
totalcurrent | `uint16_t[4]` | mAh | Total current.
rpm | `uint16_t[4]` | rpm | RPM (eRPM).
count | `uint16_t[4]` | | count of telemetry packets received (wraps at 65535).


### ESC_TELEMETRY_21_TO_24 (11042) {#ESC_TELEMETRY_21_TO_24}

ESC Telemetry Data for ESCs 21 to 24, matching data sent by BLHeli ESCs.

Field Name | Type | Units | Description
--- | --- | --- | ---
temperature | `uint8_t[4]` | degC | Temperature.
voltage | `uint16_t[4]` | cV | Voltage.
current | `uint16_t[4]` | cA | Current.
totalcurrent | `uint16_t[4]` | mAh | Total current.
rpm | `uint16_t[4]` | rpm | RPM (eRPM).
count | `uint16_t[4]` | | count of telemetry packets received (wraps at 65535).


### ESC_TELEMETRY_25_TO_28 (11043) {#ESC_TELEMETRY_25_TO_28}

ESC Telemetry Data for ESCs 25 to 28, matching data sent by BLHeli ESCs.

Field Name | Type | Units | Description
--- | --- | --- | ---
temperature | `uint8_t[4]` | degC | Temperature.
voltage | `uint16_t[4]` | cV | Voltage.
current | `uint16_t[4]` | cA | Current.
totalcurrent | `uint16_t[4]` | mAh | Total current.
rpm | `uint16_t[4]` | rpm | RPM (eRPM).
count | `uint16_t[4]` | | count of telemetry packets received (wraps at 65535).


### ESC_TELEMETRY_29_TO_32 (11044) {#ESC_TELEMETRY_29_TO_32}

ESC Telemetry Data for ESCs 29 to 32, matching data sent by BLHeli ESCs.

Field Name | Type | Units | Description
--- | --- | --- | ---
temperature | `uint8_t[4]` | degC | Temperature.
voltage | `uint16_t[4]` | cV | Voltage.
current | `uint16_t[4]` | cA | Current.
totalcurrent | `uint16_t[4]` | mAh | Total current.
rpm | `uint16_t[4]` | rpm | RPM (eRPM).
count | `uint16_t[4]` | | count of telemetry packets received (wraps at 65535).


## Enumerated Types

### ACCELCAL_VEHICLE_POS {#ACCELCAL_VEHICLE_POS}
Expand All @@ -1001,6 +1100,7 @@ Value | Name | Description
--- | --- | ---
<a id='HEADING_TYPE_COURSE_OVER_GROUND'></a>0 | [HEADING_TYPE_COURSE_OVER_GROUND](#HEADING_TYPE_COURSE_OVER_GROUND) |
<a id='HEADING_TYPE_HEADING'></a>1 | [HEADING_TYPE_HEADING](#HEADING_TYPE_HEADING) |
<a id='HEADING_TYPE_DEFAULT'></a>2 | [HEADING_TYPE_DEFAULT](#HEADING_TYPE_DEFAULT) |

### SCRIPTING_CMD {#SCRIPTING_CMD}

Expand All @@ -1011,6 +1111,19 @@ Value | Name | Description
<a id='SCRIPTING_CMD_STOP'></a>2 | [SCRIPTING_CMD_STOP](#SCRIPTING_CMD_STOP) | Stop execution of scripts.
<a id='SCRIPTING_CMD_STOP_AND_RESTART'></a>3 | [SCRIPTING_CMD_STOP_AND_RESTART](#SCRIPTING_CMD_STOP_AND_RESTART) | Stop execution of scripts and restart.

### SECURE_COMMAND_OP {#SECURE_COMMAND_OP}

Value | Name | Description
--- | --- | ---
<a id='SECURE_COMMAND_GET_SESSION_KEY'></a>0 | [SECURE_COMMAND_GET_SESSION_KEY](#SECURE_COMMAND_GET_SESSION_KEY) | Get an 8 byte session key which is used for remote secure updates which operate on flight controller data such as bootloader public keys. Return data will be 8 bytes on success. The session key remains valid until either the flight controller reboots or another [SECURE_COMMAND_GET_SESSION_KEY](#SECURE_COMMAND_GET_SESSION_KEY) is run.
<a id='SECURE_COMMAND_GET_REMOTEID_SESSION_KEY'></a>1 | [SECURE_COMMAND_GET_REMOTEID_SESSION_KEY](#SECURE_COMMAND_GET_REMOTEID_SESSION_KEY) | Get an 8 byte session key which is used for remote secure updates which operate on RemoteID module data. Return data will be 8 bytes on success. The session key remains valid until either the remote ID module reboots or another [SECURE_COMMAND_GET_REMOTEID_SESSION_KEY](#SECURE_COMMAND_GET_REMOTEID_SESSION_KEY) is run.
<a id='SECURE_COMMAND_REMOVE_PUBLIC_KEYS'></a>2 | [SECURE_COMMAND_REMOVE_PUBLIC_KEYS](#SECURE_COMMAND_REMOVE_PUBLIC_KEYS) | Remove range of public keys from the bootloader. Command data consists of two bytes, first byte if index of first public key to remove. Second byte is the number of keys to remove. If all keys are removed then secure boot is disabled and insecure firmware can be loaded.
<a id='SECURE_COMMAND_GET_PUBLIC_KEYS'></a>3 | [SECURE_COMMAND_GET_PUBLIC_KEYS](#SECURE_COMMAND_GET_PUBLIC_KEYS) | Get current public keys from the bootloader. Command data consists of two bytes, first byte is index of first public key to fetch, 2nd byte is number of keys to fetch. Total data needs to fit in data portion of reply (max 6 keys for 32 byte keys). Reply data has the index of the first key in the first byte, followed by the keys. Returned keys may be less than the number of keys requested if there are less keys installed than requested.
<a id='SECURE_COMMAND_SET_PUBLIC_KEYS'></a>4 | [SECURE_COMMAND_SET_PUBLIC_KEYS](#SECURE_COMMAND_SET_PUBLIC_KEYS) | Set current public keys in the bootloader. Data consists of a one byte public key index followed by the public keys. With 32 byte keys this allows for up to 6 keys to be set in one request. Keys outside of the range that is being set will remain unchanged.
<a id='SECURE_COMMAND_GET_REMOTEID_CONFIG'></a>5 | [SECURE_COMMAND_GET_REMOTEID_CONFIG](#SECURE_COMMAND_GET_REMOTEID_CONFIG) | Get config data for remote ID module. This command should be sent to the component ID of the flight controller which will forward it to the RemoteID module either over mavlink or DroneCAN. Data format is specific to the RemoteID implementation, see RemoteID firmware documentation for details.
<a id='SECURE_COMMAND_SET_REMOTEID_CONFIG'></a>6 | [SECURE_COMMAND_SET_REMOTEID_CONFIG](#SECURE_COMMAND_SET_REMOTEID_CONFIG) | Set config data for remote ID module. This command should be sent to the component ID of the flight controller which will forward it to the RemoteID module either over mavlink or DroneCAN. Data format is specific to the RemoteID implementation, see RemoteID firmware documentation for details.
<a id='SECURE_COMMAND_FLASH_BOOTLOADER'></a>7 | [SECURE_COMMAND_FLASH_BOOTLOADER](#SECURE_COMMAND_FLASH_BOOTLOADER) | Flash bootloader from local storage. Data is the filename to use for the bootloader. This is intended to be used with MAVFtp to upload a new bootloader to a microSD before flashing.

### LIMITS_STATE {#LIMITS_STATE}

Value | Name | Description
Expand Down Expand Up @@ -1040,6 +1153,8 @@ Value | Name | Description
--- | --- | ---
<a id='FAVORABLE_WIND'></a>1 | [FAVORABLE_WIND](#FAVORABLE_WIND) | Flag set when requiring favorable winds for landing.
<a id='LAND_IMMEDIATELY'></a>2 | [LAND_IMMEDIATELY](#LAND_IMMEDIATELY) | Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land.
<a id='ALT_FRAME_VALID'></a>4 | [ALT_FRAME_VALID](#ALT_FRAME_VALID) | True if the following altitude frame value is valid.
<a id='ALT_FRAME'></a>24 | [ALT_FRAME](#ALT_FRAME) | 2 bit value representing altitude frame. 0: absolute, 1: relative home, 2: relative origin, 3: relative terrain

### CAMERA_STATUS_TYPES {#CAMERA_STATUS_TYPES}

Expand Down Expand Up @@ -1347,6 +1462,7 @@ Value | Name | Description
<a id='EKF_PRED_POS_HORIZ_REL'></a>256 | [EKF_PRED_POS_HORIZ_REL](#EKF_PRED_POS_HORIZ_REL) | Set if EKF's predicted horizontal position (relative) estimate is good.
<a id='EKF_PRED_POS_HORIZ_ABS'></a>512 | [EKF_PRED_POS_HORIZ_ABS](#EKF_PRED_POS_HORIZ_ABS) | Set if EKF's predicted horizontal position (absolute) estimate is good.
<a id='EKF_UNINITIALIZED'></a>1024 | [EKF_UNINITIALIZED](#EKF_UNINITIALIZED) | Set if EKF has never been healthy.
<a id='EKF_GPS_GLITCHING'></a>32768 | [EKF_GPS_GLITCHING](#EKF_GPS_GLITCHING) | Set if EKF believes the GPS input data is faulty.

### PID_TUNING_AXIS {#PID_TUNING_AXIS}

Expand Down Expand Up @@ -1931,8 +2047,8 @@ Param (Label) | Description | Units
2 (timeout) | timeout for operation in seconds. Zero means no timeout (0 to 255) | s
3 (arg1) | argument1. |
4 (arg2) | argument2. |
5 | Empty |
6 | Empty |
5 (arg3) | argument3. |
6 (arg4) | argument4. |
7 | Empty |


Expand Down Expand Up @@ -1974,7 +2090,7 @@ Param (Label) | Description | Values | Units
--- | --- | --- | ---
1 | Empty | |
2 | Empty | |
3 (alt rate-of-change) | Rate of change, toward new altitude. 0 for maximum rate change. Positive numbers only, as negative numbers will not converge on the new target alt. | min: 0 | m/s/s
3 (alt rate-of-change) | Rate of change, toward new altitude. 0 for maximum rate change. Positive numbers only, as negative numbers will not converge on the new target alt. | min: 0 | m/s
4 | Empty | |
5 | Empty | |
6 | Empty | |
Expand All @@ -1996,3 +2112,33 @@ Param (Label) | Description | Values | Units
7 | Empty | |


### MAV_CMD_EXTERNAL_POSITION_ESTIMATE (43003) {#MAV_CMD_EXTERNAL_POSITION_ESTIMATE}

Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link.

Param (Label) | Description | Units
--- | --- | ---
1 (transmission_time) | Timestamp that this message was sent as a time in the transmitters time domain. The sender should wrap this time back to zero based on required timing accuracy for the application and the limitations of a 32 bit float. For example, wrapping at 10 hours would give approximately 1ms accuracy. Recipient must handle time wrap in any timing jitter correction applied to this field. Wrap rollover time should not be at not more than 250 seconds, which would give approximately 10 microsecond accuracy. | s
2 (processing_time) | The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. Set to zero if not known. | s
3 (accuracy) | estimated one standard deviation accuracy of the measurement. Set to NaN if not known. |
4 | Empty |
5 (Latitude) | Latitude |
6 (Longitude) | Longitude |
7 (Altitude) | Altitude, not used. Should be sent as NaN. May be supported in a future version of this message. | m


### MAV_CMD_SET_HAGL (43005) {#MAV_CMD_SET_HAGL}

Provide a value for height above ground level. This can be used for things like fixed wing and VTOL landing.

Param (Label) | Description | Units
--- | --- | ---
1 (hagl) | Height above ground level. | m
2 (accuracy) | estimated one standard deviation accuracy of the measurement. Set to NaN if not known. | m
3 (timeout) | Timeout for this data. The flight controller should only consider this data valid within the timeout window. | s
4 | Empty |
5 | Empty |
6 | Empty |
7 | Empty |


2 changes: 1 addition & 1 deletion en/messages/common.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

The MAVLink *common* message set contains *standard* definitions that are managed by the MAVLink project.
The definitions cover functionality that is considered useful to most ground control stations and autopilots.
MAVLink-compatible systems are expected to use these definitions where possible (if an appropriate message exists) rather than rolling out variants in their own [dialects](../messages/index.md).
MAVLink-compatible systems are expected to use these definitions where possible (if an appropriate message exists) rather than rolling out variants in their own [dialects](../messages/README.md).

The original definitions are defined in [common.xml](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/common.xml).

Expand Down
Loading

0 comments on commit b11302b

Please sign in to comment.