diff --git a/en/messages/ASLUAV.md b/en/messages/ASLUAV.md index 556481846..8c2489c3c 100644 --- a/en/messages/ASLUAV.md +++ b/en/messages/ASLUAV.md @@ -34,9 +34,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 17 | 226 -[Enums](#enumerated-types) | 2 | 144 -[Commands](#mav_commands) | 166 | 0 +[Messages](#messages) | 17 | 229 +[Enums](#enumerated-types) | 2 | 146 +[Commands](#mav_commands) | 167 | 0 The following sections list all entities in the dialect (both included and defined in this file). diff --git a/en/messages/AVSSUAS.md b/en/messages/AVSSUAS.md index 72510778c..48d9f2bdf 100644 --- a/en/messages/AVSSUAS.md +++ b/en/messages/AVSSUAS.md @@ -38,9 +38,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 4 | 226 -[Enums](#enumerated-types) | 3 | 144 -[Commands](#mav_commands) | 171 | 0 +[Messages](#messages) | 4 | 229 +[Enums](#enumerated-types) | 3 | 146 +[Commands](#mav_commands) | 172 | 0 The following sections list all entities in the dialect (both included and defined in this file). diff --git a/en/messages/ardupilotmega.md b/en/messages/ardupilotmega.md index e53a1ec6f..296328142 100644 --- a/en/messages/ardupilotmega.md +++ b/en/messages/ardupilotmega.md @@ -43,9 +43,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 72 | 243 -[Enums](#enumerated-types) | 46 | 159 -[Commands](#mav_commands) | 197 | 0 +[Messages](#messages) | 72 | 246 +[Enums](#enumerated-types) | 46 | 161 +[Commands](#mav_commands) | 198 | 0 The following sections list all entities in the dialect (both included and defined in this file). diff --git a/en/messages/common.md b/en/messages/common.md index 07e7dea44..8eeb13c33 100644 --- a/en/messages/common.md +++ b/en/messages/common.md @@ -37,9 +37,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 224 | 2 -[Enums](#enumerated-types) | 138 | 6 -[Commands](#mav_commands) | 164 | 0 +[Messages](#messages) | 227 | 2 +[Enums](#enumerated-types) | 140 | 6 +[Commands](#mav_commands) | 165 | 0 The following sections list all entities in the dialect (both included and defined in this file). @@ -3691,6 +3691,52 @@ sequence_oldest_available | `uint16_t` | | Oldest Sequence number that is still reason | `uint8_t` | [MAV_EVENT_ERROR_REASON](#MAV_EVENT_ERROR_REASON) | Error reason. +### AVAILABLE_MODES (435) {#AVAILABLE_MODES} + +Get information about a particular flight modes. + +The message can be enumerated or requested for a particular mode using [MAV_CMD_REQUEST_MESSAGE](#MAV_CMD_REQUEST_MESSAGE). +Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. +The modes must be available/settable for the current vehicle/frame type. +Each mode should only be emitted once (even if it is both standard and custom). +Note that the current mode should be emitted in [CURRENT_MODE](#CURRENT_MODE), and that if the mode list can change then [AVAILABLE_MODES_MONITOR](#AVAILABLE_MODES_MONITOR) must be emitted on first change and subsequently streamed. + +Field Name | Type | Values | Description +--- | --- | --- | --- +number_modes | `uint8_t` | | The total number of available modes for the current vehicle type. +mode_index | `uint8_t` | | The current mode index within number_modes, indexed from 1. The index is not guaranteed to be persistent, and may change between reboots or if the set of modes change. +standard_mode | `uint8_t` | [MAV_STANDARD_MODE](#MAV_STANDARD_MODE) | Standard mode. +custom_mode | `uint32_t` | | A bitfield for use for autopilot-specific flags +properties | `uint32_t` | [MAV_MODE_PROPERTY](#MAV_MODE_PROPERTY) | Mode properties. +mode_name | `char[35]` | | Name of custom mode, with null termination character. Should be omitted for standard modes. + + +### CURRENT_MODE (436) {#CURRENT_MODE} + +Get the current mode. + +This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). +It may be requested using [MAV_CMD_REQUEST_MESSAGE](#MAV_CMD_REQUEST_MESSAGE). + +Field Name | Type | Values | Description +--- | --- | --- | --- +standard_mode | `uint8_t` | [MAV_STANDARD_MODE](#MAV_STANDARD_MODE) | Standard mode. +custom_mode | `uint32_t` | | A bitfield for use for autopilot-specific flags +intended_custom_mode | `uint32_t` | invalid:0 | The custom_mode of the mode that was last commanded by the user (for example, with [MAV_CMD_DO_SET_STANDARD_MODE](#MAV_CMD_DO_SET_STANDARD_MODE), [MAV_CMD_DO_SET_MODE](#MAV_CMD_DO_SET_MODE) or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied + + +### AVAILABLE_MODES_MONITOR (437) {#AVAILABLE_MODES_MONITOR} + +A change to the sequence number indicates that the set of [AVAILABLE_MODES](#AVAILABLE_MODES) has changed. + +A receiver must re-request all available modes whenever the sequence number changes. +This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. + +Field Name | Type | Description +--- | --- | --- +seq | `uint8_t` | Sequence number. The value iterates sequentially whenever [AVAILABLE_MODES](#AVAILABLE_MODES) changes (e.g. support for a new mode is added/removed dynamically). + + ### ILLUMINATOR_STATUS (440) {#ILLUMINATOR_STATUS} Illuminator status @@ -5989,6 +6035,34 @@ Value | Name | Description 2 | [ILLUMINATOR_ERROR_FLAGS_OVER_TEMPERATURE_SHUTDOWN](#ILLUMINATOR_ERROR_FLAGS_OVER_TEMPERATURE_SHUTDOWN) | Illuminator over temperature shutdown error. 4 | [ILLUMINATOR_ERROR_FLAGS_THERMISTOR_FAILURE](#ILLUMINATOR_ERROR_FLAGS_THERMISTOR_FAILURE) | Illuminator thermistor failure. +### MAV_STANDARD_MODE {#MAV_STANDARD_MODE} + +Standard modes with a well understood meaning across flight stacks and vehicle types. + +For example, most flight stack have the concept of a "return" or "RTL" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. +Modes may be set using [MAV_CMD_DO_SET_STANDARD_MODE](#MAV_CMD_DO_SET_STANDARD_MODE). + +Value | Name | Description +--- | --- | --- +0 | [MAV_STANDARD_MODE_NON_STANDARD](#MAV_STANDARD_MODE_NON_STANDARD) | Non standard mode.
This may be used when reporting the mode if the current flight mode is not a standard mode. +1 | [MAV_STANDARD_MODE_POSITION_HOLD](#MAV_STANDARD_MODE_POSITION_HOLD) | Position mode (manual).
Position-controlled and stabilized manual mode.
When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces.
This mode can only be set by vehicles that can hold a fixed position.
Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces.
Hybrid MC/FW ("VTOL") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles.
Fixed-wing (FW) vehicles must not support this mode.
Other vehicle types must not support this mode (this may be revisited through the PR process). +2 | [MAV_STANDARD_MODE_ORBIT](#MAV_STANDARD_MODE_ORBIT) | Orbit (manual).
Position-controlled and stabilized manual mode.
The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction.
Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated.
Flight stacks may support the [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) for changing the orbit parameters.
MC and FW vehicles may support this mode.
Hybrid MC/FW ("VTOL") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration.
Other vehicle types must not support this mode (this may be revisited through the PR process). +3 | [MAV_STANDARD_MODE_CRUISE](#MAV_STANDARD_MODE_CRUISE) | Cruise mode (manual).
Position-controlled and stabilized manual mode.
When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces.
Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces.
Hybrid MC/FW ("VTOL") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles.
Multicopter (MC) vehicles must not support this mode.
Other vehicle types must not support this mode (this may be revisited through the PR process). +4 | [MAV_STANDARD_MODE_ALTITUDE_HOLD](#MAV_STANDARD_MODE_ALTITUDE_HOLD) | Altitude hold (manual).
Altitude-controlled and stabilized manual mode.
When sticks are released vehicles return to their level-flight orientation and hold their altitude.
MC vehicles continue with existing momentum and may move with wind (or other external forces).
FW vehicles continue with current heading, but may be moved off-track by wind.
Hybrid MC/FW ("VTOL") vehicles behave according to their current configuration/mode (FW or MC).
Other vehicle types must not support this mode (this may be revisited through the PR process). +5 | [MAV_STANDARD_MODE_SAFE_RECOVERY](#MAV_STANDARD_MODE_SAFE_RECOVERY) | Safe recovery mode (auto).
Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle.
This mode is more commonly referred to as RTL and/or or Smart RTL.
The precise return location, flight path, and landing behaviour depend on vehicle configuration and type.
For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent. +6 | [MAV_STANDARD_MODE_MISSION](#MAV_STANDARD_MODE_MISSION) | Mission mode (automatic).
Automatic mode that executes MAVLink missions.
Missions are executed from the current waypoint as soon as the mode is enabled. +7 | [MAV_STANDARD_MODE_LAND](#MAV_STANDARD_MODE_LAND) | Land mode (auto).
Automatic mode that lands the vehicle at the current location.
The precise landing behaviour depends on vehicle configuration and type. +8 | [MAV_STANDARD_MODE_TAKEOFF](#MAV_STANDARD_MODE_TAKEOFF) | Takeoff mode (auto).
Automatic takeoff mode.
The precise takeoff behaviour depends on vehicle configuration and type. + +### MAV_MODE_PROPERTY {#MAV_MODE_PROPERTY} + +(Bitmask) Mode properties. + +Value | Name | Description +--- | --- | --- +1 | [MAV_MODE_PROPERTY_ADVANCED](#MAV_MODE_PROPERTY_ADVANCED) | If set, this mode is an advanced mode.
For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not.
A GCS can optionally use this flag to configure the UI for its intended users. +2 | [MAV_MODE_PROPERTY_NOT_USER_SELECTABLE](#MAV_MODE_PROPERTY_NOT_USER_SELECTABLE) | If set, this mode should not be added to the list of selectable modes.
The mode might still be selected by the FC directly (for example as part of a failsafe). + ### MAV_AUTOPILOT — \[from: [minimal](../messages/minimal.md#MAV_AUTOPILOT)\] {#MAV_AUTOPILOT} Micro air vehicle / autopilot classes. This identifies the individual model. @@ -7510,6 +7584,23 @@ Param (Label) | Description | Values | Units 7 | Empty | | +### MAV_CMD_DO_SET_STANDARD_MODE (262) {#MAV_CMD_DO_SET_STANDARD_MODE} + +Enable the specified standard MAVLink mode. + +If the mode is not supported the vehicle should ACK with [MAV_RESULT_FAILED](#MAV_RESULT_FAILED). + +Param (Label) | Description | Values +--- | --- | --- +1 (Standard Mode) | The mode to set. | [MAV_STANDARD_MODE](#MAV_STANDARD_MODE) +2 | | +3 | | +4 | | +5 | | +6 | | +7 | | + + ### MAV_CMD_MISSION_START (300) {#MAV_CMD_MISSION_START} start running a mission diff --git a/en/messages/cubepilot.md b/en/messages/cubepilot.md index 1c902ce6a..59efdf8cc 100644 --- a/en/messages/cubepilot.md +++ b/en/messages/cubepilot.md @@ -37,9 +37,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 5 | 226 -[Enums](#enumerated-types) | 0 | 144 -[Commands](#mav_commands) | 164 | 0 +[Messages](#messages) | 5 | 229 +[Enums](#enumerated-types) | 0 | 146 +[Commands](#mav_commands) | 165 | 0 The following sections list all entities in the dialect (both included and defined in this file). diff --git a/en/messages/development.md b/en/messages/development.md index 939a2e022..d7c2c2f30 100644 --- a/en/messages/development.md +++ b/en/messages/development.md @@ -36,8 +36,8 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 15 | 226 -[Enums](#enumerated-types) | 13 | 144 +[Messages](#messages) | 12 | 229 +[Enums](#enumerated-types) | 11 | 146 [Commands](#mav_commands) | 172 | 0 The following sections list all entities in the dialect (both included and defined in this file). @@ -186,57 +186,6 @@ count | `uint8_t` | | | Total number of RC channels being received. This can be channels ++ | `int16_t[32]` | | min:-4096 max:4096 | RC channels.
Channel values are in centered 13 bit format. Range is -4096 to 4096, center is 0. Conversion to PWM is x * 5/32 + 1500.
Channels with indexes equal or above count should be set to 0, to benefit from MAVLink's trailing-zero trimming. -### AVAILABLE_MODES (435) — [WIP] {#AVAILABLE_MODES} - -**WORK IN PROGRESS**: Do not use in stable production environments (it may change). - -Get information about a particular flight modes. - -The message can be enumerated or requested for a particular mode using [MAV_CMD_REQUEST_MESSAGE](#MAV_CMD_REQUEST_MESSAGE). -Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. -The modes must be available/settable for the current vehicle/frame type. -Each modes should only be emitted once (even if it is both standard and custom). - -Field Name | Type | Values | Description ---- | --- | --- | --- -number_modes | `uint8_t` | | The total number of available modes for the current vehicle type. -mode_index | `uint8_t` | | The current mode index within number_modes, indexed from 1. -standard_mode | `uint8_t` | [MAV_STANDARD_MODE](#MAV_STANDARD_MODE) | Standard mode. -custom_mode | `uint32_t` | | A bitfield for use for autopilot-specific flags -properties | `uint32_t` | [MAV_MODE_PROPERTY](#MAV_MODE_PROPERTY) | Mode properties. -mode_name | `char[35]` | | Name of custom mode, with null termination character. Should be omitted for standard modes. - - -### CURRENT_MODE (436) — [WIP] {#CURRENT_MODE} - -**WORK IN PROGRESS**: Do not use in stable production environments (it may change). - -Get the current mode. - -This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). -It may be requested using [MAV_CMD_REQUEST_MESSAGE](#MAV_CMD_REQUEST_MESSAGE). - -Field Name | Type | Values | Description ---- | --- | --- | --- -standard_mode | `uint8_t` | [MAV_STANDARD_MODE](#MAV_STANDARD_MODE) | Standard mode. -custom_mode | `uint32_t` | | A bitfield for use for autopilot-specific flags -intended_custom_mode | `uint32_t` | invalid:0 | The custom_mode of the mode that was last commanded by the user (for example, with [MAV_CMD_DO_SET_STANDARD_MODE](#MAV_CMD_DO_SET_STANDARD_MODE), [MAV_CMD_DO_SET_MODE](#MAV_CMD_DO_SET_MODE) or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied - - -### AVAILABLE_MODES_MONITOR (437) — [WIP] {#AVAILABLE_MODES_MONITOR} - -**WORK IN PROGRESS**: Do not use in stable production environments (it may change). - -A change to the sequence number indicates that the set of [AVAILABLE_MODES](#AVAILABLE_MODES) has changed. - -A receiver must re-request all available modes whenever the sequence number changes. -This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. - -Field Name | Type | Description ---- | --- | --- -seq | `uint8_t` | Sequence number. The value iterates sequentially whenever [AVAILABLE_MODES](#AVAILABLE_MODES) changes (e.g. support for a new mode is added/removed dynamically). - - ### GNSS_INTEGRITY (441) — [WIP] {#GNSS_INTEGRITY} **WORK IN PROGRESS**: Do not use in stable production environments (it may change). @@ -328,38 +277,6 @@ Value | Name | Description 0 | [AIRSPEED_SENSOR_UNHEALTHY](#AIRSPEED_SENSOR_UNHEALTHY) | Airspeed sensor is unhealthy 1 | [AIRSPEED_SENSOR_USING](#AIRSPEED_SENSOR_USING) | True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. -### MAV_STANDARD_MODE — [WIP] {#MAV_STANDARD_MODE} - -**WORK IN PROGRESS**: Do not use in stable production environments (it may change). - -Standard modes with a well understood meaning across flight stacks and vehicle types. - -For example, most flight stack have the concept of a "return" or "RTL" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. -Modes may be set using [MAV_CMD_DO_SET_STANDARD_MODE](#MAV_CMD_DO_SET_STANDARD_MODE). - -Value | Name | Description ---- | --- | --- -0 | [MAV_STANDARD_MODE_NON_STANDARD](#MAV_STANDARD_MODE_NON_STANDARD) | Non standard mode.
This may be used when reporting the mode if the current flight mode is not a standard mode. -1 | [MAV_STANDARD_MODE_POSITION_HOLD](#MAV_STANDARD_MODE_POSITION_HOLD) | Position mode (manual).
Position-controlled and stabilized manual mode.
When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces.
This mode can only be set by vehicles that can hold a fixed position.
Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces.
Hybrid MC/FW ("VTOL") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles.
Fixed-wing (FW) vehicles must not support this mode.
Other vehicle types must not support this mode (this may be revisited through the PR process). -2 | [MAV_STANDARD_MODE_ORBIT](#MAV_STANDARD_MODE_ORBIT) | Orbit (manual).
Position-controlled and stabilized manual mode.
The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction.
Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated.
Flight stacks may support the [MAV_CMD_DO_ORBIT](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT) for changing the orbit parameters.
MC and FW vehicles may support this mode.
Hybrid MC/FW ("VTOL") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration.
Other vehicle types must not support this mode (this may be revisited through the PR process). -3 | [MAV_STANDARD_MODE_CRUISE](#MAV_STANDARD_MODE_CRUISE) | Cruise mode (manual).
Position-controlled and stabilized manual mode.
When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces.
Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces.
Hybrid MC/FW ("VTOL") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles.
Multicopter (MC) vehicles must not support this mode.
Other vehicle types must not support this mode (this may be revisited through the PR process). -4 | [MAV_STANDARD_MODE_ALTITUDE_HOLD](#MAV_STANDARD_MODE_ALTITUDE_HOLD) | Altitude hold (manual).
Altitude-controlled and stabilized manual mode.
When sticks are released vehicles return to their level-flight orientation and hold their altitude.
MC vehicles continue with existing momentum and may move with wind (or other external forces).
FW vehicles continue with current heading, but may be moved off-track by wind.
Hybrid MC/FW ("VTOL") vehicles behave according to their current configuration/mode (FW or MC).
Other vehicle types must not support this mode (this may be revisited through the PR process). -5 | [MAV_STANDARD_MODE_SAFE_RECOVERY](#MAV_STANDARD_MODE_SAFE_RECOVERY) | Safe recovery mode (auto).
Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle.
This mode is more commonly referred to as RTL and/or or Smart RTL.
The precise return location, flight path, and landing behaviour depend on vehicle configuration and type.
For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent. -6 | [MAV_STANDARD_MODE_MISSION](#MAV_STANDARD_MODE_MISSION) | Mission mode (automatic).
Automatic mode that executes MAVLink missions.
Missions are executed from the current waypoint as soon as the mode is enabled. -7 | [MAV_STANDARD_MODE_LAND](#MAV_STANDARD_MODE_LAND) | Land mode (auto).
Automatic mode that lands the vehicle at the current location.
The precise landing behaviour depends on vehicle configuration and type. -8 | [MAV_STANDARD_MODE_TAKEOFF](#MAV_STANDARD_MODE_TAKEOFF) | Takeoff mode (auto).
Automatic takeoff mode.
The precise takeoff behaviour depends on vehicle configuration and type. - -### MAV_MODE_PROPERTY — [WIP] {#MAV_MODE_PROPERTY} - -**WORK IN PROGRESS**: Do not use in stable production environments (it may change). - -(Bitmask) Mode properties. - -Value | Name | Description ---- | --- | --- -1 | [MAV_MODE_PROPERTY_ADVANCED](#MAV_MODE_PROPERTY_ADVANCED) | If set, this mode is an advanced mode.
For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not.
A GCS can optionally use this flag to configure the UI for its intended users. -2 | [MAV_MODE_PROPERTY_NOT_USER_SELECTABLE](#MAV_MODE_PROPERTY_NOT_USER_SELECTABLE) | If set, this mode should not be added to the list of selectable modes.
The mode might still be selected by the FC directly (for example as part of a failsafe). - ### MAV_BATTERY_STATUS_FLAGS — [WIP] {#MAV_BATTERY_STATUS_FLAGS} **WORK IN PROGRESS**: Do not use in stable production environments (it may change). @@ -552,25 +469,6 @@ Param (Label) | Description | Values 7 | WIP: upgrade progress report rate (can be used for more granular control). | -### MAV_CMD_DO_SET_STANDARD_MODE (262) — [WIP] {#MAV_CMD_DO_SET_STANDARD_MODE} - -**WORK IN PROGRESS**: Do not use in stable production environments (it may change). - -Enable the specified standard MAVLink mode. - -If the mode is not supported the vehicle should ACK with [MAV_RESULT_FAILED](#MAV_RESULT_FAILED). - -Param (Label) | Description | Values ---- | --- | --- -1 (Standard Mode) | The mode to set. | [MAV_STANDARD_MODE](#MAV_STANDARD_MODE) -2 | | -3 | | -4 | | -5 | | -6 | | -7 | | - - ### MAV_CMD_SET_AT_S_PARAM (550) — [WIP] {#MAV_CMD_SET_AT_S_PARAM} **WORK IN PROGRESS**: Do not use in stable production environments (it may change). diff --git a/en/messages/dialects.md b/en/messages/dialects.md index e5f5d2ade..a1d8445e3 100644 --- a/en/messages/dialects.md +++ b/en/messages/dialects.md @@ -17,18 +17,18 @@ Dialects are not managed by this project! The dialect definitions are: -- [cubepilot.xml](cubepilot.md) -- [ardupilotmega.xml](ardupilotmega.md) - [matrixpilot.xml](matrixpilot.md) -- [ASLUAV.xml](ASLUAV.md) - [csAirLink.xml](csAirLink.md) -- [storm32.xml](storm32.md) -- [icarous.xml](icarous.md) -- [AVSSUAS.xml](AVSSUAS.md) - [uAvionix.xml](uAvionix.md) - [paparazzi.xml](paparazzi.md) -- [ualberta.xml](ualberta.md) - [loweheiser.xml](loweheiser.md) +- [ardupilotmega.xml](ardupilotmega.md) +- [icarous.xml](icarous.md) +- [storm32.xml](storm32.md) +- [ualberta.xml](ualberta.md) +- [ASLUAV.xml](ASLUAV.md) +- [AVSSUAS.xml](AVSSUAS.md) +- [cubepilot.xml](cubepilot.md) Note that dialects may `include` [MAVLink-Standard Definitions](index.md) or other dialects. Up to 5 levels of XML file nesting are allowed - see `MAXIMUM_INCLUDE_FILE_NESTING` in [mavgen.py](https://github.com/ArduPilot/pymavlink/blob/master/generator/mavgen.py#L44). diff --git a/en/messages/matrixpilot.md b/en/messages/matrixpilot.md index 03dad6341..8ca785df5 100644 --- a/en/messages/matrixpilot.md +++ b/en/messages/matrixpilot.md @@ -34,9 +34,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 27 | 226 -[Enums](#enumerated-types) | 1 | 144 -[Commands](#mav_commands) | 165 | 0 +[Messages](#messages) | 27 | 229 +[Enums](#enumerated-types) | 1 | 146 +[Commands](#mav_commands) | 166 | 0 The following sections list all entities in the dialect (both included and defined in this file). diff --git a/en/messages/paparazzi.md b/en/messages/paparazzi.md index 50a36e97f..f5a5c01af 100644 --- a/en/messages/paparazzi.md +++ b/en/messages/paparazzi.md @@ -36,9 +36,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 5 | 226 -[Enums](#enumerated-types) | 0 | 144 -[Commands](#mav_commands) | 164 | 0 +[Messages](#messages) | 5 | 229 +[Enums](#enumerated-types) | 0 | 146 +[Commands](#mav_commands) | 165 | 0 The following sections list all entities in the dialect (both included and defined in this file). diff --git a/en/messages/python_array_test.md b/en/messages/python_array_test.md index e52dd852d..2779ae51a 100644 --- a/en/messages/python_array_test.md +++ b/en/messages/python_array_test.md @@ -34,9 +34,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 8 | 226 -[Enums](#enumerated-types) | 0 | 144 -[Commands](#mav_commands) | 164 | 0 +[Messages](#messages) | 8 | 229 +[Enums](#enumerated-types) | 0 | 146 +[Commands](#mav_commands) | 165 | 0 The following sections list all entities in the dialect (both included and defined in this file). diff --git a/en/messages/storm32.md b/en/messages/storm32.md index 0ca005fc3..0b50e78f9 100644 --- a/en/messages/storm32.md +++ b/en/messages/storm32.md @@ -38,9 +38,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 8 | 315 -[Enums](#enumerated-types) | 8 | 205 -[Commands](#mav_commands) | 200 | 0 +[Messages](#messages) | 8 | 318 +[Enums](#enumerated-types) | 8 | 207 +[Commands](#mav_commands) | 201 | 0 The following sections list all entities in the dialect (both included and defined in this file). diff --git a/en/messages/uAvionix.md b/en/messages/uAvionix.md index 2435b116a..a649e9c78 100644 --- a/en/messages/uAvionix.md +++ b/en/messages/uAvionix.md @@ -34,9 +34,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 3 | 226 -[Enums](#enumerated-types) | 8 | 144 -[Commands](#mav_commands) | 164 | 0 +[Messages](#messages) | 3 | 229 +[Enums](#enumerated-types) | 8 | 146 +[Commands](#mav_commands) | 165 | 0 The following sections list all entities in the dialect (both included and defined in this file). diff --git a/en/messages/ualberta.md b/en/messages/ualberta.md index 6b1493ec2..e148efef7 100644 --- a/en/messages/ualberta.md +++ b/en/messages/ualberta.md @@ -34,9 +34,9 @@ span.warning { Type | Defined | Included --- | --- | --- -[Messages](#messages) | 3 | 226 -[Enums](#enumerated-types) | 3 | 144 -[Commands](#mav_commands) | 164 | 0 +[Messages](#messages) | 3 | 229 +[Enums](#enumerated-types) | 3 | 146 +[Commands](#mav_commands) | 165 | 0 The following sections list all entities in the dialect (both included and defined in this file).