diff --git a/ko/mavgen_c/example_c_udp.md b/ko/mavgen_c/example_c_udp.md
index 0e2146ada..e73aaee79 100644
--- a/ko/mavgen_c/example_c_udp.md
+++ b/ko/mavgen_c/example_c_udp.md
@@ -1,6 +1,6 @@
# MAVLink C UDP Example
-The [MAVLink UDP Example](https://github.com/mavlink/mavlink/tree/master/examples/linux) is a simple C example that sends some data to _QGroundControl_ using MAVLink over UDP.
+The [MAVLink UDP Example](https://github.com/mavlink/mavlink/tree/master/examples/c) is a simple C example that sends some data to _QGroundControl_ using MAVLink over UDP.
_QGroundControl_ responds with heartbeats and other messages, which are then printed by this program.
:::info
@@ -31,12 +31,12 @@ The following instructions show how to build and run the example.
You can put/generate the library wherever you like, but the build command below assumes they are located in directory named **include** below the MAVLink root directory.
:::
-2. Open a terminal and navigate to [examples/linux](https://github.com/mavlink/mavlink/tree/master/examples/linux)
+2. Open a terminal and navigate to [examples/c](https://github.com/mavlink/mavlink/tree/master/examples/c)
3. Compile with GCC using the following command:
```sh
- gcc -std=c99 -I ../../include/common -o mavlink_udp mavlink_udp.c
+ gcc -std=c99 -I ../../include/common -o mavlink_udp udp_example.c
```
::: info
@@ -64,7 +64,7 @@ The following instructions show how to build and run the example.
6. The example should start displaying the received data in the terminal:
```sh
- ~/github/mavlink/examples/linux$ ./mavlink_udp
+ ~/github/mavlink/examples/c$ ./mavlink_udp
Bytes Received: 17
Datagram: fe 09 00 ff 00 00 00 00 00 00 06 08 c0 04 03 19 87
Received packet: SYS: 255, COMP: 0, LEN: 9, MSG ID: 0
diff --git a/ko/messages/README.md b/ko/messages/README.md
new file mode 100644
index 000000000..79ef96f9c
--- /dev/null
+++ b/ko/messages/README.md
@@ -0,0 +1,66 @@
+
+
+# XML Definition Files & Dialects
+
+MAVLink definitions files can be found in [mavlink/message definitions](https://github.com/mavlink/mavlink/blob/master/message_definitions/).
+These can roughly be divided into:
+
+- [Standard definitions](#standard-definitions) - core definitions shared by many flight stacks
+- [Test definitions](#test-definitions) - definitions to support testing and validation
+- [Dialects](#dialects) - _protocol-_ and _vendor-specific_ messages, enums and commands
+
+## Standard Definitions
+
+The following XML definition files are considered standard/core (i.e. not dialects):
+
+- [minimal.xml](minimal.md) - the minimum set of entities (messages, enums, MAV_CMD) required to set up a MAVLink network.
+- [standard.xml](standard.md) - the standard set of entities that are implemented by almost all flight stacks (at least 2, in a compatible way).
+ This `includes` [minimal.xml](minimal.md).
+- [common.xml](common.md) - the set of entities that have been implemented in at least one core flight stack.
+ This `includes` [standard.xml](minimal.md)
+
+> **Note** We are still working towards moving the truly standard entities from **common.xml** to **standard.xml**
+> Currently you should include [common.xml](common.md)
+
+In addition:
+
+- [development.xml](development.md) - XML definitions that are _proposed_ for inclusion in the standard definitions.
+ These are work in progress.
+
+## Test Definitions
+
+The following definitions are used for testing and dialect validation:
+
+- [all.xml](all.md) - This includes all other XML files, and is used to verify that there are no ID clashes (and can potentially be used by GCS to communicate with any core dialect).
+- [test.xml](test.md) - Test XML definition file.
+
+## Dialects {#dialects}
+
+MAVLink _dialects_ are XML definition files that define _protocol-_ and _vendor-specific_ messages, enums and commands.
+
+> **Note** Vendor forks of MAVLink may contain XML entities that have not yet been pushed into the main repository (and will not be documented).
+
+Dialects may _include_ other MAVLink XML files, which may in turn contain other XML files (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)).
+A typical pattern is for a dialect to include [common.xml](../messages/common.md) (containing the _MAVLink standard definitions_), extending it with vendor or protocol specific messages.
+
+The dialect definitions are:
+
+- [cubepilot.xml](cubepilot.md)
+- [python_array_test.xml](python_array_test.md)
+- [ardupilotmega.xml](ardupilotmega.md)
+- [common.xml](common.md)
+- [development.xml](development.md)
+- [matrixpilot.xml](matrixpilot.md)
+- [ASLUAV.xml](ASLUAV.md)
+- [csAirLink.xml](csAirLink.md)
+- [all.xml](all.md)
+- [storm32.xml](storm32.md)
+- [icarous.xml](icarous.md)
+- [test.xml](test.md)
+- [AVSSUAS.xml](AVSSUAS.md)
+- [uAvionix.xml](uAvionix.md)
+- [minimal.xml](minimal.md)
+- [paparazzi.xml](paparazzi.md)
+- [standard.xml](standard.md)
+- [ualberta.xml](ualberta.md)
+- [loweheiser.xml](loweheiser.md)
diff --git a/ko/messages/all.md b/ko/messages/all.md
index 65e1f74b5..f9b7f2971 100644
--- a/ko/messages/all.md
+++ b/ko/messages/all.md
@@ -2,7 +2,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:
@@ -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).
diff --git a/ko/messages/ardupilotmega.md b/ko/messages/ardupilotmega.md
index 4ee999dbd..5f4564453 100644
--- a/ko/messages/ardupilotmega.md
+++ b/ko/messages/ardupilotmega.md
@@ -32,6 +32,7 @@ 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)
@@ -39,15 +40,17 @@ span.warning {
| 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}
+
+**DEPRECATED:** Replaced By [MAG_CAL_REPORT](#MAG_CAL_REPORT), Accel Parameters, and Gyro Parameters (2022-02)
Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.
@@ -733,6 +736,32 @@ Write registers reply.
| 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.
@@ -866,9 +895,7 @@ Read configured OSD parameter reply.
| max_value | `float` | | OSD parameter maximum value. |
| increment | `float` | | OSD parameter increment. |
-### OBSTACLE_DISTANCE_3D (11037) — [WIP] {#OBSTACLE_DISTANCE_3D}
-
-**WORK IN PROGRESS**: Do not use in stable production environments (it may change).
+### OBSTACLE_DISTANCE_3D (11037) {#OBSTACLE_DISTANCE_3D}
Obstacle located as a 3D vector.
@@ -914,6 +941,71 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
| 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}
@@ -935,6 +1027,7 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
| --------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------- | ----------- |
| 0 | [HEADING_TYPE_COURSE_OVER_GROUND](#HEADING_TYPE_COURSE_OVER_GROUND) | |
| 1 | [HEADING_TYPE_HEADING](#HEADING_TYPE_HEADING) | |
+| 2 | [HEADING_TYPE_DEFAULT](#HEADING_TYPE_DEFAULT) | |
### SCRIPTING_CMD {#SCRIPTING_CMD}
@@ -945,6 +1038,19 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
| 2 | [SCRIPTING_CMD_STOP](#SCRIPTING_CMD_STOP) | Stop execution of scripts. |
| 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 |
+| ----------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+| 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. |
+| 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. |
+| 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. |
+| 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. |
+| 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. |
+| 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. |
+| 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. |
+| 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 |
@@ -970,10 +1076,12 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
(Bitmask) Flags in [RALLY_POINT](#RALLY_POINT) message.
-| Value | Name | Description |
-| ------------------------------ | ---------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
-| 1 | [FAVORABLE_WIND](#FAVORABLE_WIND) | Flag set when requiring favorable winds for landing. |
-| 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. |
+| Value | Name | Description |
+| ------------------------------ | ----------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+| 1 | [FAVORABLE_WIND](#FAVORABLE_WIND) | Flag set when requiring favorable winds for landing. |
+| 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. |
+| 4 | [ALT_FRAME_VALID](#ALT_FRAME_VALID) | True if the following altitude frame value is valid. |
+| 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}
@@ -1281,6 +1389,7 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
| 256 | [EKF_PRED_POS_HORIZ_REL](#EKF_PRED_POS_HORIZ_REL) | Set if EKF's predicted horizontal position (relative) estimate is good. |
| 512 | [EKF_PRED_POS_HORIZ_ABS](#EKF_PRED_POS_HORIZ_ABS) | Set if EKF's predicted horizontal position (absolute) estimate is good. |
| 1024 | [EKF_UNINITIALIZED](#EKF_UNINITIALIZED) | Set if EKF has never been healthy. |
+| 32768 | [EKF_GPS_GLITCHING](#EKF_GPS_GLITCHING) | Set if EKF believes the GPS input data is faulty. |
### PID_TUNING_AXIS {#PID_TUNING_AXIS}
@@ -1839,8 +1948,8 @@ Scripting command as NAV command with wait for completion.
| 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 | |
### MAV_CMD_NAV_ATTITUDE_TIME (42703) {#MAV_CMD_NAV_ATTITUDE_TIME}
@@ -1879,7 +1988,7 @@ Change target altitude at a given rate. This slews the vehicle at a controllable
| ----------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------- | ----- |
| 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 | | |
@@ -1898,3 +2007,17 @@ Change to target heading at a given rate, overriding previous heading/s. This sl
| 5 | Empty | | |
| 6 | Empty | | |
| 7 | Empty | | |
+
+### 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 | |
diff --git a/ko/messages/common.md b/ko/messages/common.md
index 1221297b0..1ee61b4c2 100644
--- a/ko/messages/common.md
+++ b/ko/messages/common.md
@@ -4,7 +4,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).
diff --git a/ko/messages/loweheiser.md b/ko/messages/loweheiser.md
new file mode 100644
index 000000000..411dd0e77
--- /dev/null
+++ b/ko/messages/loweheiser.md
@@ -0,0 +1,88 @@
+
+
+# Dialect: loweheiser
+
+> **Warning** This topic documents the version of the dialect file in the [mavlink/mavlink](https://github.com/mavlink/mavlink) Github repository, which may not be up to date with the file in the source repository (it is up to the dialect owner to push changes when needed).
+> The source repo should be listed in the comments at the top of the XML definition file listed below (but may not be).
+
+This topic is a human-readable form of the XML definition file: [loweheiser.xml](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/loweheiser.xml).
+
+
+
+> **Note**
+>
+> - MAVLink 2 [extension fields](../guide/define_xml_element.md#message_extensions) are displayed in blue.
+> - Entities from dialects are displayed only as headings (with link to original)
+
+
+
+## MAVLink Include Files
+
+- [minimal.xml](../messages/minimal.md)
+
+## 목차
+
+| Type | Defined | Included |
+| -------------------------- | ------- | -------- |
+| [Messages](#messages) | 1 | 2 |
+| [Enums](#enumerated-types) | 0 | 6 |
+| [Commands](#mav_commands) | 1 | 0 |
+
+The following sections list all entities in the dialect (both included and defined in this file).
+
+## Messages
+
+### LOWEHEISER_GOV_EFI (10151) {#LOWEHEISER_GOV_EFI}
+
+Composite EFI and Governor data from Loweheiser equipment. This message is created by the EFI unit based on its own data and data received from a governor attached to that EFI unit.
+
+| Field Name | Type | Units | Description |
+| ------------------------------------------------------------------------------------------ | ---------- | ----- | --------------------------------------------------------------------------------------------------------------------------------------- |
+| volt_batt | `float` | V | Generator Battery voltage. |
+| curr_batt | `float` | A | Generator Battery current. |
+| curr_gen | `float` | A | Current being produced by generator. |
+| curr_rot | `float` | A | Load current being consumed by the UAV (sum of curr_gen and curr_batt) |
+| fuel_level | `float` | l | Generator fuel remaining in litres. |
+| throttle | `float` | % | Throttle Output. |
+| runtime | `uint32_t` | s | Seconds this generator has run since it was rebooted. |
+| until_maintenance | `int32_t` | s | Seconds until this generator requires maintenance. A negative value indicates maintenance is past due. |
+| rectifier_temp | `float` | degC | The Temperature of the rectifier. |
+| generator_temp | `float` | degC | The temperature of the mechanical motor, fuel cell core or generator. |
+| efi_batt | `float` | V | EFI Supply Voltage. |
+| efi_rpm | `float` | rpm | Motor RPM. |
+| efi_pw | `float` | ms | Injector pulse-width in miliseconds. |
+| efi_fuel_flow | `float` | | Fuel flow rate in litres/hour. |
+| efi_fuel_consumed | `float` | l | Fuel consumed. |
+| efi_baro | `float` | kPa | Atmospheric pressure. |
+| efi_mat | `float` | degC | Manifold Air Temperature. |
+| efi_clt | `float` | degC | Cylinder Head Temperature. |
+| efi_tps | `float` | % | Throttle Position. |
+| efi_exhaust_gas_temperature | `float` | degC | Exhaust gas temperature. |
+| efi_index | `uint8_t` | | EFI index.
Messages with same value are from the same source (instance). |
+| generator_status | `uint16_t` | | Generator status. |
+| efi_status | `uint16_t` | | EFI status. |
+
+## Enumerated Types
+
+## Commands (MAV_CMD) {#mav_commands}
+
+### MAV_CMD_LOWEHEISER_SET_STATE (10151) {#MAV_CMD_LOWEHEISER_SET_STATE}
+
+Set Loweheiser desired states
+
+| Param (Label) | Description |
+| -------------------------------- | ------------------------------------------------------------------------------------------------------------------ |
+| 1 | EFI Index |
+| 2 | Desired Engine/EFI State (0: Power Off, 1:Running) |
+| 3 | Desired Governor State (0:manual throttle, 1:Governed throttle) |
+| 4 | Manual throttle level, 0% - 100% |
+| 5 | Electronic Start up (0:Off, 1:On) |
+| 6 | Empty |
+| 7 | Empty |
diff --git a/ko/messages/storm32.md b/ko/messages/storm32.md
index ae02f543d..d8e880dbd 100644
--- a/ko/messages/storm32.md
+++ b/ko/messages/storm32.md
@@ -35,9 +35,9 @@ span.warning {
| Type | Defined | Included |
| -------------------------- | ------- | -------- |
-| [Messages](#messages) | 8 | 307 |
-| [Enums](#enumerated-types) | 8 | 204 |
-| [Commands](#mav_commands) | 198 | 0 |
+| [Messages](#messages) | 8 | 315 |
+| [Enums](#enumerated-types) | 8 | 205 |
+| [Commands](#mav_commands) | 200 | 0 |
The following sections list all entities in the dialect (both included and defined in this file).
diff --git a/zh/mavgen_c/example_c_udp.md b/zh/mavgen_c/example_c_udp.md
index ccfae11fb..7042d610e 100644
--- a/zh/mavgen_c/example_c_udp.md
+++ b/zh/mavgen_c/example_c_udp.md
@@ -1,6 +1,6 @@
# MAVLink C UDP 示例
-The [MAVLink UDP Example](https://github.com/mavlink/mavlink/tree/master/examples/linux) is a simple C example that sends some data to _QGroundControl_ using MAVLink over UDP.
+The [MAVLink UDP Example](https://github.com/mavlink/mavlink/tree/master/examples/c) is a simple C example that sends some data to _QGroundControl_ using MAVLink over UDP.
_QGroundControl_ responds with heartbeats and other messages, which are then printed by this program.
:::info
@@ -31,12 +31,12 @@ These instructions were tested on a clean _Ubuntu LTS 20.04_ installation using
You can put/generate the library wherever you like, but the build command below assumes they are located in directory named **include** below the MAVLink root directory.
:::
-2. Open a terminal and navigate to [examples/linux](https://github.com/mavlink/mavlink/tree/master/examples/linux)
+2. Open a terminal and navigate to [examples/c](https://github.com/mavlink/mavlink/tree/master/examples/c)
3. 使用下列命令编译GCC:
```sh
- gcc -std=c99 -I ../../include/common -o mavlink_udp mavlink_udp.c
+ gcc -std=c99 -I ../../include/common -o mavlink_udp udp_example.c
```
::: info
@@ -64,7 +64,7 @@ These instructions were tested on a clean _Ubuntu LTS 20.04_ installation using
6. 例子应该开始显示终端收到的数据:
```sh
- ~/github/mavlink/examples/linux$ ./mavlink_udp
+ ~/github/mavlink/examples/c$ ./mavlink_udp
Bytes Received: 17
Datagram: fe 09 00 ff 00 00 00 00 00 00 06 08 c0 04 03 19 87
Received packet: SYS: 255, COMP: 0, LEN: 9, MSG ID: 0
diff --git a/zh/messages/README.md b/zh/messages/README.md
new file mode 100644
index 000000000..79ef96f9c
--- /dev/null
+++ b/zh/messages/README.md
@@ -0,0 +1,66 @@
+
+
+# XML Definition Files & Dialects
+
+MAVLink definitions files can be found in [mavlink/message definitions](https://github.com/mavlink/mavlink/blob/master/message_definitions/).
+These can roughly be divided into:
+
+- [Standard definitions](#standard-definitions) - core definitions shared by many flight stacks
+- [Test definitions](#test-definitions) - definitions to support testing and validation
+- [Dialects](#dialects) - _protocol-_ and _vendor-specific_ messages, enums and commands
+
+## Standard Definitions
+
+The following XML definition files are considered standard/core (i.e. not dialects):
+
+- [minimal.xml](minimal.md) - the minimum set of entities (messages, enums, MAV_CMD) required to set up a MAVLink network.
+- [standard.xml](standard.md) - the standard set of entities that are implemented by almost all flight stacks (at least 2, in a compatible way).
+ This `includes` [minimal.xml](minimal.md).
+- [common.xml](common.md) - the set of entities that have been implemented in at least one core flight stack.
+ This `includes` [standard.xml](minimal.md)
+
+> **Note** We are still working towards moving the truly standard entities from **common.xml** to **standard.xml**
+> Currently you should include [common.xml](common.md)
+
+In addition:
+
+- [development.xml](development.md) - XML definitions that are _proposed_ for inclusion in the standard definitions.
+ These are work in progress.
+
+## Test Definitions
+
+The following definitions are used for testing and dialect validation:
+
+- [all.xml](all.md) - This includes all other XML files, and is used to verify that there are no ID clashes (and can potentially be used by GCS to communicate with any core dialect).
+- [test.xml](test.md) - Test XML definition file.
+
+## Dialects {#dialects}
+
+MAVLink _dialects_ are XML definition files that define _protocol-_ and _vendor-specific_ messages, enums and commands.
+
+> **Note** Vendor forks of MAVLink may contain XML entities that have not yet been pushed into the main repository (and will not be documented).
+
+Dialects may _include_ other MAVLink XML files, which may in turn contain other XML files (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)).
+A typical pattern is for a dialect to include [common.xml](../messages/common.md) (containing the _MAVLink standard definitions_), extending it with vendor or protocol specific messages.
+
+The dialect definitions are:
+
+- [cubepilot.xml](cubepilot.md)
+- [python_array_test.xml](python_array_test.md)
+- [ardupilotmega.xml](ardupilotmega.md)
+- [common.xml](common.md)
+- [development.xml](development.md)
+- [matrixpilot.xml](matrixpilot.md)
+- [ASLUAV.xml](ASLUAV.md)
+- [csAirLink.xml](csAirLink.md)
+- [all.xml](all.md)
+- [storm32.xml](storm32.md)
+- [icarous.xml](icarous.md)
+- [test.xml](test.md)
+- [AVSSUAS.xml](AVSSUAS.md)
+- [uAvionix.xml](uAvionix.md)
+- [minimal.xml](minimal.md)
+- [paparazzi.xml](paparazzi.md)
+- [standard.xml](standard.md)
+- [ualberta.xml](ualberta.md)
+- [loweheiser.xml](loweheiser.md)
diff --git a/zh/messages/all.md b/zh/messages/all.md
index 8d9d5d522..4255d0071 100644
--- a/zh/messages/all.md
+++ b/zh/messages/all.md
@@ -2,7 +2,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:
@@ -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).
diff --git a/zh/messages/ardupilotmega.md b/zh/messages/ardupilotmega.md
index 00461882b..460b25f7e 100644
--- a/zh/messages/ardupilotmega.md
+++ b/zh/messages/ardupilotmega.md
@@ -32,6 +32,7 @@ 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)
@@ -39,15 +40,17 @@ span.warning {
| 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).
## 消息
-### SENSOR_OFFSETS (150) {#SENSOR_OFFSETS}
+### SENSOR_OFFSETS (150) — [DEP] {#SENSOR_OFFSETS}
+
+**DEPRECATED:** Replaced By [MAG_CAL_REPORT](#MAG_CAL_REPORT), Accel Parameters, and Gyro Parameters (2022-02)
Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.
@@ -733,6 +736,32 @@ Write registers reply.
| 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 | 值 | 描述 |
+| ------------------------------------- | -------------- | --------------------------------------------------------------------------------- | ---------------------------------------------- |
+| 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 | 值 | 描述 |
+| -------------------------------- | -------------- | --------------------------------------------------------------------------------- | --------------------------------------------- |
+| 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.
@@ -866,9 +895,7 @@ Read configured OSD parameter reply.
| max_value | `float` | | OSD parameter maximum value. |
| increment | `float` | | OSD parameter increment. |
-### OBSTACLE_DISTANCE_3D (11037) — [WIP] {#OBSTACLE_DISTANCE_3D}
-
-**WORK IN PROGRESS**: Do not use in stable production environments (it may change).
+### OBSTACLE_DISTANCE_3D (11037) {#OBSTACLE_DISTANCE_3D}
Obstacle located as a 3D vector.
@@ -914,6 +941,71 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
| 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 | 描述 |
+| ------------ | ------------- | ----- | ---------------------------------------------------------------------------------------- |
+| 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 | 描述 |
+| ------------ | ------------- | ----- | ---------------------------------------------------------------------------------------- |
+| 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 | 描述 |
+| ------------ | ------------- | ----- | ---------------------------------------------------------------------------------------- |
+| 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 | 描述 |
+| ------------ | ------------- | ----- | ---------------------------------------------------------------------------------------- |
+| 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 | 描述 |
+| ------------ | ------------- | ----- | ---------------------------------------------------------------------------------------- |
+| 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}
@@ -935,6 +1027,7 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
| --------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------- | -- |
| 0 | [HEADING_TYPE_COURSE_OVER_GROUND](#HEADING_TYPE_COURSE_OVER_GROUND) | |
| 1 | [HEADING_TYPE_HEADING](#HEADING_TYPE_HEADING) | |
+| 2 | [HEADING_TYPE_DEFAULT](#HEADING_TYPE_DEFAULT) | |
### SCRIPTING_CMD {#SCRIPTING_CMD}
@@ -945,6 +1038,19 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
| 2 | [SCRIPTING_CMD_STOP](#SCRIPTING_CMD_STOP) | Stop execution of scripts. |
| 3 | [SCRIPTING_CMD_STOP_AND_RESTART](#SCRIPTING_CMD_STOP_AND_RESTART) | Stop execution of scripts and restart. |
+### SECURE_COMMAND_OP {#SECURE_COMMAND_OP}
+
+| 值 | Name | 描述 |
+| ----------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+| 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. |
+| 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. |
+| 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. |
+| 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. |
+| 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. |
+| 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. |
+| 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. |
+| 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}
| 值 | Name | 描述 |
@@ -970,10 +1076,12 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
(Bitmask) Flags in [RALLY_POINT](#RALLY_POINT) message.
-| 值 | Name | 描述 |
-| ------------------------------ | ---------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
-| 1 | [FAVORABLE_WIND](#FAVORABLE_WIND) | Flag set when requiring favorable winds for landing. |
-| 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. |
+| 值 | Name | 描述 |
+| ------------------------------ | ----------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
+| 1 | [FAVORABLE_WIND](#FAVORABLE_WIND) | Flag set when requiring favorable winds for landing. |
+| 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. |
+| 4 | [ALT_FRAME_VALID](#ALT_FRAME_VALID) | True if the following altitude frame value is valid. |
+| 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}
@@ -1281,6 +1389,7 @@ The MCU status, giving MCU temperature and voltage. The min and max voltages are
| 256 | [EKF_PRED_POS_HORIZ_REL](#EKF_PRED_POS_HORIZ_REL) | Set if EKF's predicted horizontal position (relative) estimate is good. |
| 512 | [EKF_PRED_POS_HORIZ_ABS](#EKF_PRED_POS_HORIZ_ABS) | Set if EKF's predicted horizontal position (absolute) estimate is good. |
| 1024 | [EKF_UNINITIALIZED](#EKF_UNINITIALIZED) | Set if EKF has never been healthy. |
+| 32768 | [EKF_GPS_GLITCHING](#EKF_GPS_GLITCHING) | Set if EKF believes the GPS input data is faulty. |
### PID_TUNING_AXIS {#PID_TUNING_AXIS}
@@ -1839,8 +1948,8 @@ Scripting command as NAV command with wait for completion.
| 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 | |
### MAV_CMD_NAV_ATTITUDE_TIME (42703) {#MAV_CMD_NAV_ATTITUDE_TIME}
@@ -1879,7 +1988,7 @@ Change target altitude at a given rate. This slews the vehicle at a controllable
| ----------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ---------------------- | ----- |
| 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 | | |
@@ -1898,3 +2007,17 @@ Change to target heading at a given rate, overriding previous heading/s. This sl
| 5 | Empty | | |
| 6 | Empty | | |
| 7 | Empty | | |
+
+### 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) | 描述 | 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 | |
diff --git a/zh/messages/common.md b/zh/messages/common.md
index d8e21d6f5..8cfe043d0 100644
--- a/zh/messages/common.md
+++ b/zh/messages/common.md
@@ -4,7 +4,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).
diff --git a/zh/messages/loweheiser.md b/zh/messages/loweheiser.md
new file mode 100644
index 000000000..42e6b36d6
--- /dev/null
+++ b/zh/messages/loweheiser.md
@@ -0,0 +1,88 @@
+
+
+# Dialect: loweheiser
+
+> **Warning** This topic documents the version of the dialect file in the [mavlink/mavlink](https://github.com/mavlink/mavlink) Github repository, which may not be up to date with the file in the source repository (it is up to the dialect owner to push changes when needed).
+> The source repo should be listed in the comments at the top of the XML definition file listed below (but may not be).
+
+This topic is a human-readable form of the XML definition file: [loweheiser.xml](https://github.com/mavlink/mavlink/blob/master/message_definitions/v1.0/loweheiser.xml).
+
+
+
+> **Note**
+>
+> - MAVLink 2 [extension fields](../guide/define_xml_element.md#message_extensions) are displayed in blue.
+> - Entities from dialects are displayed only as headings (with link to original)
+
+
+
+## MAVLink Include Files
+
+- [minimal.xml](../messages/minimal.md)
+
+## 概览
+
+| Type | Defined | Included |
+| -------------------------- | ------- | -------- |
+| [Messages](#messages) | 1 | 2 |
+| [Enums](#enumerated-types) | 0 | 6 |
+| [Commands](#mav_commands) | 1 | 0 |
+
+The following sections list all entities in the dialect (both included and defined in this file).
+
+## 消息
+
+### LOWEHEISER_GOV_EFI (10151) {#LOWEHEISER_GOV_EFI}
+
+Composite EFI and Governor data from Loweheiser equipment. This message is created by the EFI unit based on its own data and data received from a governor attached to that EFI unit.
+
+| Field Name | Type | Units | 描述 |
+| ------------------------------------------------------------------------------------------ | ---------- | ----- | --------------------------------------------------------------------------------------------------------------------------------------- |
+| volt_batt | `float` | V | Generator Battery voltage. |
+| curr_batt | `float` | A | Generator Battery current. |
+| curr_gen | `float` | A | Current being produced by generator. |
+| curr_rot | `float` | A | Load current being consumed by the UAV (sum of curr_gen and curr_batt) |
+| fuel_level | `float` | l | Generator fuel remaining in litres. |
+| 油门 | `float` | % | Throttle Output. |
+| runtime | `uint32_t` | s | Seconds this generator has run since it was rebooted. |
+| until_maintenance | `int32_t` | s | Seconds until this generator requires maintenance. A negative value indicates maintenance is past due. |
+| rectifier_temp | `float` | degC | The Temperature of the rectifier. |
+| generator_temp | `float` | degC | The temperature of the mechanical motor, fuel cell core or generator. |
+| efi_batt | `float` | V | EFI Supply Voltage. |
+| efi_rpm | `float` | rpm | Motor RPM. |
+| efi_pw | `float` | ms | Injector pulse-width in miliseconds. |
+| efi_fuel_flow | `float` | | Fuel flow rate in litres/hour. |
+| efi_fuel_consumed | `float` | l | Fuel consumed. |
+| efi_baro | `float` | kPa | Atmospheric pressure. |
+| efi_mat | `float` | degC | Manifold Air Temperature. |
+| efi_clt | `float` | degC | Cylinder Head Temperature. |
+| efi_tps | `float` | % | Throttle Position. |
+| efi_exhaust_gas_temperature | `float` | degC | Exhaust gas temperature. |
+| efi_index | `uint8_t` | | EFI index.
Messages with same value are from the same source (instance). |
+| generator_status | `uint16_t` | | Generator status. |
+| efi_status | `uint16_t` | | EFI status. |
+
+## Enumerated Types
+
+## Commands (MAV_CMD) {#mav_commands}
+
+### MAV_CMD_LOWEHEISER_SET_STATE (10151) {#MAV_CMD_LOWEHEISER_SET_STATE}
+
+Set Loweheiser desired states
+
+| Param (Label) | 描述 |
+| -------------------------------- | ------------------------------------------------------------------------------------------------------------------ |
+| 1 | EFI Index |
+| 2 | Desired Engine/EFI State (0: Power Off, 1:Running) |
+| 3 | Desired Governor State (0:manual throttle, 1:Governed throttle) |
+| 4 | Manual throttle level, 0% - 100% |
+| 5 | Electronic Start up (0:Off, 1:On) |
+| 6 | Empty |
+| 7 | Empty |
diff --git a/zh/messages/storm32.md b/zh/messages/storm32.md
index 8af426bac..34618c9de 100644
--- a/zh/messages/storm32.md
+++ b/zh/messages/storm32.md
@@ -35,9 +35,9 @@ span.warning {
| Type | Defined | Included |
| -------------------------- | ------- | -------- |
-| [Messages](#messages) | 8 | 307 |
-| [Enums](#enumerated-types) | 8 | 204 |
-| [Commands](#mav_commands) | 198 | 0 |
+| [Messages](#messages) | 8 | 315 |
+| [Enums](#enumerated-types) | 8 | 205 |
+| [Commands](#mav_commands) | 200 | 0 |
The following sections list all entities in the dialect (both included and defined in this file).