From b4f55d26d51fdc1ffbf9c9e0c39723cd40c51b59 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 29 Nov 2025 02:24:36 -0500
Subject: [PATCH 01/11] msp set alt test
---
docs/development/msp/msp_messages.json | 41 +++++++++++++++++++++
src/main/fc/fc_msp.c | 51 ++++++++++++++++++++++++++
src/main/msp/msp_protocol_v2_inav.h | 4 +-
src/main/navigation/navigation.h | 3 +-
4 files changed, 97 insertions(+), 2 deletions(-)
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index dde6d3ecef5..7b79f69767a 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -10829,6 +10829,47 @@
"notes": "Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).",
"description": "Sets a specific vertex (or center+radius for circular zones) for a Geozone."
},
+ "MSP2_INAV_SET_ALT_TARGET": {
+ "code": 8725,
+ "mspv": 2,
+ "variable_len": true,
+ "request": {
+ "payload": [
+ {
+ "name": "altitudeDatum",
+ "ctype": "uint8_t",
+ "desc": "Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved)",
+ "units": "",
+ "optional": true
+ },
+ {
+ "name": "altitudeTarget",
+ "ctype": "int32_t",
+ "desc": "Desired altitude target (`updateClimbRateToAltitudeController(…, ROC_TO_ALT_TARGET)`), datum as above",
+ "units": "cm",
+ "optional": true
+ }
+ ]
+ },
+ "reply": {
+ "payload": [
+ {
+ "name": "altitudeDatum",
+ "ctype": "uint8_t",
+ "desc": "Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM`",
+ "units": ""
+ },
+ {
+ "name": "altitudeTarget",
+ "ctype": "int32_t",
+ "desc": "Current altitude target (`posControl.desiredState.pos.z`)",
+ "units": "cm"
+ }
+ ]
+ },
+ "notes": "Empty request payload returns the current altitude target with datum. Sending a 5-byte payload sets a new target: 1 byte datum, 4 bytes altitude. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected).",
+ "description": "Get or set the active altitude hold target."
+ },
"MSP2_INAV_FULL_LOCAL_POSE": {
"code": 8736,
"mspv": 2,
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 54c225c78bc..4e387bb3493 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -4111,6 +4111,57 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
*ret = mspFcGeozoneVerteciesOutCommand(dst, src);
break;
#endif
+
+ case MSP2_INAV_SET_ALT_TARGET:
+ {
+ const navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags();
+ if (!(stateFlags & NAV_CTL_ALT) || (stateFlags & NAV_CTL_LAND) || navigationIsExecutingAnEmergencyLanding() || posControl.flags.estAltStatus == EST_NONE) {
+ *ret = MSP_RESULT_ERROR;
+ break;
+ }
+
+ if (dataSize == 0) {
+ sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM);
+ sbufWriteU32(dst, (uint32_t)lrintf(posControl.desiredState.pos.z));
+ *ret = MSP_RESULT_ACK;
+ break;
+ }
+
+ if (dataSize != (sizeof(int32_t) + sizeof(uint8_t))) {
+ *ret = MSP_RESULT_ERROR;
+ break;
+ }
+
+ const uint8_t datumFlag = sbufReadU8(src);
+ const int32_t targetAltitudeCm = (int32_t)sbufReadU32(src);
+
+ float targetAltitudeLocalCm;
+ switch ((geoAltitudeDatumFlag_e)datumFlag) {
+ case NAV_WP_TAKEOFF_DATUM:
+ targetAltitudeLocalCm = (float)targetAltitudeCm;
+ break;
+ case NAV_WP_MSL_DATUM:
+ if (!posControl.gpsOrigin.valid) {
+ *ret = MSP_RESULT_ERROR;
+ break;
+ }
+ targetAltitudeLocalCm = (float)(targetAltitudeCm - posControl.gpsOrigin.alt);
+ break;
+ case NAV_WP_TERRAIN_DATUM:
+ default:
+ *ret = MSP_RESULT_ERROR;
+ break;
+ }
+
+ if (*ret == MSP_RESULT_ERROR) {
+ break;
+ }
+
+ updateClimbRateToAltitudeController(0.0f, targetAltitudeLocalCm, ROC_TO_ALT_TARGET);
+ *ret = MSP_RESULT_ACK;
+ break;
+ }
+
#ifdef USE_SIMULATOR
case MSP_SIMULATOR:
tmp_u8 = sbufReadU8(src); // Get the Simulator MSP version
diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h
index b44aa539887..251401fafcb 100755
--- a/src/main/msp/msp_protocol_v2_inav.h
+++ b/src/main/msp/msp_protocol_v2_inav.h
@@ -123,4 +123,6 @@
#define MSP2_INAV_GEOZONE_VERTEX 0x2212
#define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213
-#define MSP2_INAV_FULL_LOCAL_POSE 0x2220
\ No newline at end of file
+#define MSP2_INAV_SET_ALT_TARGET 0x2215
+
+#define MSP2_INAV_FULL_LOCAL_POSE 0x2220
diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h
index ddc7e23e76d..f5b2b8c82a3 100644
--- a/src/main/navigation/navigation.h
+++ b/src/main/navigation/navigation.h
@@ -729,7 +729,8 @@ typedef enum {
typedef enum {
NAV_WP_TAKEOFF_DATUM,
- NAV_WP_MSL_DATUM
+ NAV_WP_MSL_DATUM,
+ NAV_WP_TERRAIN_DATUM
} geoAltitudeDatumFlag_e;
// geoSetOrigin stores the location provided in llh as a GPS origin in the
From 94dcc3fed9d8fcd271eb3c2d1fe85f59aba3dcc1 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 29 Nov 2025 11:31:18 -0500
Subject: [PATCH 02/11] add as logic condition
---
docs/development/msp/msp_messages.json | 4 +++-
src/main/fc/fc_msp.c | 26 +------------------------
src/main/navigation/navigation.c | 27 ++++++++++++++++++++++++++
src/main/navigation/navigation.h | 1 +
src/main/programming/logic_condition.c | 4 ++++
src/main/programming/logic_condition.h | 1 +
6 files changed, 37 insertions(+), 26 deletions(-)
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index 7b79f69767a..94758d8f197 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -10840,6 +10840,7 @@
"ctype": "uint8_t",
"desc": "Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved)",
"units": "",
+ "enum": "geoAltitudeDatumFlag_e",
"optional": true
},
{
@@ -10857,7 +10858,8 @@
"name": "altitudeDatum",
"ctype": "uint8_t",
"desc": "Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM`",
- "units": ""
+ "units": "",
+ "enum": "geoAltitudeDatumFlag_e"
},
{
"name": "altitudeTarget",
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 4e387bb3493..9f08d069104 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -4114,12 +4114,6 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
case MSP2_INAV_SET_ALT_TARGET:
{
- const navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags();
- if (!(stateFlags & NAV_CTL_ALT) || (stateFlags & NAV_CTL_LAND) || navigationIsExecutingAnEmergencyLanding() || posControl.flags.estAltStatus == EST_NONE) {
- *ret = MSP_RESULT_ERROR;
- break;
- }
-
if (dataSize == 0) {
sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM);
sbufWriteU32(dst, (uint32_t)lrintf(posControl.desiredState.pos.z));
@@ -4135,29 +4129,11 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
const uint8_t datumFlag = sbufReadU8(src);
const int32_t targetAltitudeCm = (int32_t)sbufReadU32(src);
- float targetAltitudeLocalCm;
- switch ((geoAltitudeDatumFlag_e)datumFlag) {
- case NAV_WP_TAKEOFF_DATUM:
- targetAltitudeLocalCm = (float)targetAltitudeCm;
- break;
- case NAV_WP_MSL_DATUM:
- if (!posControl.gpsOrigin.valid) {
- *ret = MSP_RESULT_ERROR;
- break;
- }
- targetAltitudeLocalCm = (float)(targetAltitudeCm - posControl.gpsOrigin.alt);
- break;
- case NAV_WP_TERRAIN_DATUM:
- default:
+ if (!navigationSetAltitudeTargetWithDatum((geoAltitudeDatumFlag_e)datumFlag, targetAltitudeCm)) {
*ret = MSP_RESULT_ERROR;
break;
}
- if (*ret == MSP_RESULT_ERROR) {
- break;
- }
-
- updateClimbRateToAltitudeController(0.0f, targetAltitudeLocalCm, ROC_TO_ALT_TARGET);
*ret = MSP_RESULT_ACK;
break;
}
diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c
index e7f0774925e..a3752233149 100644
--- a/src/main/navigation/navigation.c
+++ b/src/main/navigation/navigation.c
@@ -5201,6 +5201,33 @@ bool navigationIsControllingAltitude(void) {
return (stateFlags & NAV_CTL_ALT);
}
+bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int32_t targetAltitudeCm)
+{
+ const navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags();
+ if (!(stateFlags & NAV_CTL_ALT) || (stateFlags & NAV_CTL_LAND) || navigationIsExecutingAnEmergencyLanding() || posControl.flags.estAltStatus == EST_NONE) {
+ return false;
+ }
+
+ float targetAltitudeLocalCm;
+ switch (datumFlag) {
+ case NAV_WP_TAKEOFF_DATUM:
+ targetAltitudeLocalCm = (float)targetAltitudeCm;
+ break;
+ case NAV_WP_MSL_DATUM:
+ if (!posControl.gpsOrigin.valid) {
+ return false;
+ }
+ targetAltitudeLocalCm = (float)(targetAltitudeCm - posControl.gpsOrigin.alt);
+ break;
+ case NAV_WP_TERRAIN_DATUM:
+ default:
+ return false;
+ }
+
+ updateClimbRateToAltitudeController(0.0f, targetAltitudeLocalCm, ROC_TO_ALT_TARGET);
+ return true;
+}
+
bool navigationIsFlyingAutonomousMode(void)
{
navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags();
diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h
index f5b2b8c82a3..810fdc26ef8 100644
--- a/src/main/navigation/navigation.h
+++ b/src/main/navigation/navigation.h
@@ -780,6 +780,7 @@ bool isFixedWingAutoThrottleManuallyIncreased(void);
bool navigationIsFlyingAutonomousMode(void);
bool navigationIsExecutingAnEmergencyLanding(void);
bool navigationIsControllingAltitude(void);
+bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int32_t targetAltitudeCm);
/* Returns true if navConfig()->general.flags.rth_allow_landing is NAV_RTH_ALLOW_LANDING_ALWAYS
* or if it's NAV_RTH_ALLOW_LANDING_FAILSAFE and failsafe mode is active.
*/
diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c
index edba68b8e94..fa1712e1f7f 100644
--- a/src/main/programming/logic_condition.c
+++ b/src/main/programming/logic_condition.c
@@ -471,6 +471,10 @@ static int logicConditionCompute(
return true;
break;
+ case LOGIC_CONDITION_SET_ALTITUDE_TARGET:
+ return navigationSetAltitudeTargetWithDatum((geoAltitudeDatumFlag_e)operandA, operandB);
+ break;
+
case LOGIC_CONDITION_FLIGHT_AXIS_ANGLE_OVERRIDE:
if (operandA >= 0 && operandA <= 2) {
diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h
index 74ea96c98ee..e9d8eced5eb 100644
--- a/src/main/programming/logic_condition.h
+++ b/src/main/programming/logic_condition.h
@@ -86,6 +86,7 @@ typedef enum {
LOGIC_CONDITION_RESET_MAG_CALIBRATION = 54,
LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY = 55,
LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED = 56,
+ LOGIC_CONDITION_SET_ALTITUDE_TARGET = 57,
LOGIC_CONDITION_LAST
} logicOperation_e;
From 8f204761691afc77e938cedca3b8762008c87b20 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 29 Nov 2025 12:40:10 -0500
Subject: [PATCH 03/11] updated msp docs
---
docs/development/msp/inav_enums_ref.md | 11 +++++++----
docs/development/msp/msp_messages.checksum | 2 +-
docs/development/msp/msp_ref.md | 21 ++++++++++++++++++++-
docs/development/msp/rev | 2 +-
4 files changed, 29 insertions(+), 7 deletions(-)
diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md
index 9a4c64e6e39..b0941d90897 100644
--- a/docs/development/msp/inav_enums_ref.md
+++ b/docs/development/msp/inav_enums_ref.md
@@ -1385,7 +1385,7 @@
| `DEVHW_MS4525` | 49 | |
| `DEVHW_DLVR` | 50 | |
| `DEVHW_M25P16` | 51 | |
-| `DEVHW_W25N01G` | 52 | |
+| `DEVHW_W25N` | 52 | |
| `DEVHW_UG2864` | 53 | |
| `DEVHW_SDCARD` | 54 | |
| `DEVHW_IRLOCK` | 55 | |
@@ -1994,6 +1994,7 @@
|---|---:|---|
| `NAV_WP_TAKEOFF_DATUM` | 0 | |
| `NAV_WP_MSL_DATUM` | 1 | |
+| `NAV_WP_TERRAIN_DATUM` | 2 | |
---
## `geoOriginResetMode_e`
@@ -2843,6 +2844,7 @@
| `LOGIC_CONDITION_OPERAND_FLIGHT_MIN_GROUND_SPEED` | 46 | |
| `LOGIC_CONDITION_OPERAND_FLIGHT_HORIZONTAL_WIND_SPEED` | 47 | |
| `LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION` | 48 | |
+| `LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET` | 49 | |
---
## `logicOperation_e`
@@ -2908,7 +2910,8 @@
| `LOGIC_CONDITION_RESET_MAG_CALIBRATION` | 54 | |
| `LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY` | 55 | |
| `LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED` | 56 | |
-| `LOGIC_CONDITION_LAST` | 57 | |
+| `LOGIC_CONDITION_SET_ALTITUDE_TARGET` | 57 | |
+| `LOGIC_CONDITION_LAST` | 58 | |
---
## `logicWaypointOperands_e`
@@ -4740,7 +4743,7 @@
---
## `sdcardReceiveBlockStatus_e`
-> Source: ../../../src/main/drivers/sdcard/sdcard_spi.c
+> Source: ../../../src/main/drivers/sdcard/sdcard_sdio.c
| Enumerator | Value | Condition |
|---|---:|---|
@@ -4751,7 +4754,7 @@
---
## `sdcardReceiveBlockStatus_e`
-> Source: ../../../src/main/drivers/sdcard/sdcard_sdio.c
+> Source: ../../../src/main/drivers/sdcard/sdcard_spi.c
| Enumerator | Value | Condition |
|---|---:|---|
diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum
index 3c235d8aaf9..76a646c0358 100644
--- a/docs/development/msp/msp_messages.checksum
+++ b/docs/development/msp/msp_messages.checksum
@@ -1 +1 @@
-ca27e198f4405b721ad8a15719e15e5d
+b1b9c4b89d7285401e4d7d22ca0da717
diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md
index 97851bcec1f..0e837c0fae9 100644
--- a/docs/development/msp/msp_ref.md
+++ b/docs/development/msp/msp_ref.md
@@ -10,7 +10,8 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
For current generation code, see [documentation project](https://github.com/xznhj8129/msp_documentation) (temporary until official implementation)
-**JSON file rev: 2**
+**JSON file rev: 3
+**
**Warning: Verification needed, exercise caution until completely verified for accuracy and cleared, especially for integer signs. Source-based generation/validation is forthcoming. Refer to source for absolute certainty**
@@ -411,6 +412,7 @@ For current generation code, see [documentation project](https://github.com/xznh
[8721 - MSP2_INAV_SET_GEOZONE](#msp2_inav_set_geozone)
[8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex)
[8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex)
+[8725 - MSP2_INAV_SET_ALT_TARGET](#msp2_inav_set_alt_target)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
@@ -4492,6 +4494,23 @@ For current generation code, see [documentation project](https://github.com/xznh
**Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).
+## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)`
+**Description:** Get or set the active altitude hold target.
+
+**Request Payload:**
+|Field|C Type|Size (Bytes)|Units|Description|
+|---|---|---|---|---|
+| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved) |
+| `altitudeTarget` | `int32_t` | 4 | cm | Desired altitude target (`updateClimbRateToAltitudeController(…, ROC_TO_ALT_TARGET)`), datum as above |
+
+**Reply Payload:**
+|Field|C Type|Size (Bytes)|Units|Description|
+|---|---|---|---|---|
+| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM` |
+| `altitudeTarget` | `int32_t` | 4 | cm | Current altitude target (`posControl.desiredState.pos.z`) |
+
+**Notes:** Empty request payload returns the current altitude target with datum. Sending a 5-byte payload sets a new target: 1 byte datum, 4 bytes altitude. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected).
+
## `MSP2_INAV_FULL_LOCAL_POSE (8736 / 0x2220)`
**Description:** Provides estimates of current attitude, local NEU position, and velocity.
diff --git a/docs/development/msp/rev b/docs/development/msp/rev
index d8263ee9860..00750edc07d 100644
--- a/docs/development/msp/rev
+++ b/docs/development/msp/rev
@@ -1 +1 @@
-2
\ No newline at end of file
+3
From f2aa78009f7752936c04fa791b791bb1d3e4ce05 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 29 Nov 2025 14:04:19 -0500
Subject: [PATCH 04/11] add mavlink command
---
docs/development/msp/msp_messages.checksum | 2 +-
docs/development/msp/msp_messages.json | 76 +++++++++++++---------
docs/development/msp/msp_ref.md | 26 ++++++--
docs/development/msp/original_msp_ref.md | 1 -
src/main/fc/fc_msp.c | 2 +
src/main/telemetry/mavlink.c | 51 +++++++++++++--
6 files changed, 111 insertions(+), 47 deletions(-)
diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum
index 76a646c0358..13116c1d9ef 100644
--- a/docs/development/msp/msp_messages.checksum
+++ b/docs/development/msp/msp_messages.checksum
@@ -1 +1 @@
-b1b9c4b89d7285401e4d7d22ca0da717
+590fbe3daaa6de1cef98b521f9cf8ede
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index 94758d8f197..7a3d22f87e2 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -10833,44 +10833,56 @@
"code": 8725,
"mspv": 2,
"variable_len": true,
- "request": {
- "payload": [
- {
- "name": "altitudeDatum",
- "ctype": "uint8_t",
- "desc": "Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved)",
- "units": "",
- "enum": "geoAltitudeDatumFlag_e",
- "optional": true
+ "variants": {
+ "get": {
+ "description": "Get current altitude target",
+ "request": {
+ "payload": null
},
- {
- "name": "altitudeTarget",
- "ctype": "int32_t",
- "desc": "Desired altitude target (`updateClimbRateToAltitudeController(…, ROC_TO_ALT_TARGET)`), datum as above",
- "units": "cm",
- "optional": true
+ "reply": {
+ "payload": [
+ {
+ "name": "altitudeDatum",
+ "ctype": "uint8_t",
+ "desc": "Default internal reference altitude datum `NAV_WP_TAKEOFF_DATUM`",
+ "units": "",
+ "enum": "geoAltitudeDatumFlag_e"
+ },
+ {
+ "name": "altitudeTarget",
+ "ctype": "int32_t",
+ "desc": "Current altitude target (`posControl.desiredState.pos.z`)",
+ "units": "cm"
+ }
+ ]
}
- ]
- },
- "reply": {
- "payload": [
- {
- "name": "altitudeDatum",
- "ctype": "uint8_t",
- "desc": "Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM`",
- "units": "",
- "enum": "geoAltitudeDatumFlag_e"
+ },
+ "set": {
+ "description": "Set new altitude target",
+ "request": {
+ "payload": [
+ {
+ "name": "altitudeDatum",
+ "ctype": "uint8_t",
+ "desc": "Altitude reference datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (not implemented yet)",
+ "units": "",
+ "enum": "geoAltitudeDatumFlag_e"
+ },
+ {
+ "name": "altitudeTarget",
+ "ctype": "int32_t",
+ "desc": "Desired altitude target according to reference datum",
+ "units": "cm"
+ }
+ ]
},
- {
- "name": "altitudeTarget",
- "ctype": "int32_t",
- "desc": "Current altitude target (`posControl.desiredState.pos.z`)",
- "units": "cm"
+ "reply": {
+ "payload": null
}
- ]
+ }
},
"notes": "Empty request payload returns the current altitude target with datum. Sending a 5-byte payload sets a new target: 1 byte datum, 4 bytes altitude. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected).",
- "description": "Get or set the active altitude hold target."
+ "description": "Get or set the active altitude hold target using updateClimbRateToAltitudeController."
},
"MSP2_INAV_FULL_LOCAL_POSE": {
"code": 8736,
diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md
index 0e837c0fae9..b51d72d0473 100644
--- a/docs/development/msp/msp_ref.md
+++ b/docs/development/msp/msp_ref.md
@@ -4495,19 +4495,31 @@ For current generation code, see [documentation project](https://github.com/xznh
**Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).
## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)`
-**Description:** Get or set the active altitude hold target.
+**Description:** Get or set the active altitude hold target using updateClimbRateToAltitudeController.
+#### Variant: `get`
+
+**Description:** Get current altitude target
+
+**Request Payload:** **None**
-**Request Payload:**
+**Reply Payload:**
|Field|C Type|Size (Bytes)|Units|Description|
|---|---|---|---|---|
-| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved) |
-| `altitudeTarget` | `int32_t` | 4 | cm | Desired altitude target (`updateClimbRateToAltitudeController(…, ROC_TO_ALT_TARGET)`), datum as above |
+| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Default internal reference altitude datum `NAV_WP_TAKEOFF_DATUM` |
+| `altitudeTarget` | `int32_t` | 4 | cm | Current altitude target (`posControl.desiredState.pos.z`) |
+
+#### Variant: `set`
+
+**Description:** Set new altitude target
-**Reply Payload:**
+**Request Payload:**
|Field|C Type|Size (Bytes)|Units|Description|
|---|---|---|---|---|
-| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM` |
-| `altitudeTarget` | `int32_t` | 4 | cm | Current altitude target (`posControl.desiredState.pos.z`) |
+| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Altitude reference datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (not implemented yet) |
+| `altitudeTarget` | `int32_t` | 4 | cm | Desired altitude target according to reference datum |
+
+**Reply Payload:** **None**
+
**Notes:** Empty request payload returns the current altitude target with datum. Sending a 5-byte payload sets a new target: 1 byte datum, 4 bytes altitude. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected).
diff --git a/docs/development/msp/original_msp_ref.md b/docs/development/msp/original_msp_ref.md
index d635bbc6843..209ca629481 100644
--- a/docs/development/msp/original_msp_ref.md
+++ b/docs/development/msp/original_msp_ref.md
@@ -2,7 +2,6 @@
# WARNING: DEPRECATED, OBSOLETE, FULL OF ERRORS, DO NOT USE AS REFERENCE!!!
# (OBSOLETE) INAV MSP Messages reference
-**Warning: Work in progress**\
**Generated with Gemini 2.5 Pro Preview O3-25 on source code files**\
**Verification needed, exercise caution until completely verified for accuracy and cleared**\
**Refer to source for absolute certainty**
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 9f08d069104..1597b8f88b7 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -4112,6 +4112,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
break;
#endif
+#ifdef USE_BARO
case MSP2_INAV_SET_ALT_TARGET:
{
if (dataSize == 0) {
@@ -4137,6 +4138,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
*ret = MSP_RESULT_ACK;
break;
}
+#endif
#ifdef USE_SIMULATOR
case MSP_SIMULATOR:
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index d5084b32a62..717039aba12 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1157,7 +1157,6 @@ static bool handleIncoming_MISSION_REQUEST(void)
return false;
}
-
static bool handleIncoming_COMMAND_INT(void)
{
mavlink_command_int_t msg;
@@ -1226,6 +1225,51 @@ static bool handleIncoming_COMMAND_INT(void)
mavlinkSendMessage();
}
return true;
+#ifdef USE_BARO
+ } else if (msg.command == MAV_CMD_DO_CHANGE_ALTITUDE) {
+ const float altitudeMeters = msg.param1;
+ const uint8_t frame = (uint8_t)msg.frame;
+
+ geoAltitudeDatumFlag_e datum;
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ case MAV_FRAME_GLOBAL_INT:
+ datum = NAV_WP_MSL_DATUM;
+ break;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ case MAV_FRAME_LOCAL_NED:
+ case MAV_FRAME_LOCAL_OFFSET_NED:
+ case MAV_FRAME_BODY_NED:
+ case MAV_FRAME_BODY_FRD:
+ datum = NAV_WP_TAKEOFF_DATUM;
+ break;
+ case MAV_FRAME_GLOBAL_TERRAIN_ALT:
+ case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
+ default:
+ mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ msg.command,
+ MAV_RESULT_UNSUPPORTED,
+ 0,
+ 0,
+ mavRecvMsg.sysid,
+ mavRecvMsg.compid);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
+ const bool accepted = navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm);
+ mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ msg.command,
+ accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED,
+ 0,
+ 0,
+ mavRecvMsg.sysid,
+ mavRecvMsg.compid);
+ mavlinkSendMessage();
+ return true;
+#endif
}
return false;
}
@@ -1351,11 +1395,6 @@ static bool processMAVLinkIncomingTelemetry(void)
return handleIncoming_MISSION_ITEM();
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
return handleIncoming_MISSION_REQUEST_LIST();
-
- //TODO:
- //case MAVLINK_MSG_ID_COMMAND_LONG; //up to 7 float parameters
- //return handleIncoming_COMMAND_LONG();
-
case MAVLINK_MSG_ID_COMMAND_INT: //7 parameters: parameters 1-4, 7 are floats, and parameters 5,6 are scaled integers
return handleIncoming_COMMAND_INT();
case MAVLINK_MSG_ID_MISSION_REQUEST:
From 4d61538b9a7467805f665833530afbd0abfbd7f8 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 29 Nov 2025 14:08:01 -0500
Subject: [PATCH 05/11] narrow mavlink frames
---
src/main/telemetry/mavlink.c | 11 +++++------
1 file changed, 5 insertions(+), 6 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 717039aba12..13e6c0344b7 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1238,14 +1238,8 @@ static bool handleIncoming_COMMAND_INT(void)
break;
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
- case MAV_FRAME_LOCAL_NED:
- case MAV_FRAME_LOCAL_OFFSET_NED:
- case MAV_FRAME_BODY_NED:
- case MAV_FRAME_BODY_FRD:
datum = NAV_WP_TAKEOFF_DATUM;
break;
- case MAV_FRAME_GLOBAL_TERRAIN_ALT:
- case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
default:
mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
msg.command,
@@ -1395,6 +1389,11 @@ static bool processMAVLinkIncomingTelemetry(void)
return handleIncoming_MISSION_ITEM();
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
return handleIncoming_MISSION_REQUEST_LIST();
+
+ //TODO:
+ //case MAVLINK_MSG_ID_COMMAND_LONG; //up to 7 float parameters
+ //return handleIncoming_COMMAND_LONG();
+
case MAVLINK_MSG_ID_COMMAND_INT: //7 parameters: parameters 1-4, 7 are floats, and parameters 5,6 are scaled integers
return handleIncoming_COMMAND_INT();
case MAVLINK_MSG_ID_MISSION_REQUEST:
From eec54810e3ad0b8e150cae457a86d307fe69a323 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 29 Nov 2025 14:10:53 -0500
Subject: [PATCH 06/11] change msp msg name
---
docs/development/msp/msp_messages.checksum | 2 +-
docs/development/msp/msp_messages.json | 2 +-
docs/development/msp/msp_ref.md | 4 ++--
src/main/fc/fc_msp.c | 2 +-
src/main/msp/msp_protocol_v2_inav.h | 2 +-
5 files changed, 6 insertions(+), 6 deletions(-)
diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum
index 13116c1d9ef..d6c6f3d080f 100644
--- a/docs/development/msp/msp_messages.checksum
+++ b/docs/development/msp/msp_messages.checksum
@@ -1 +1 @@
-590fbe3daaa6de1cef98b521f9cf8ede
+d03d2a93006b50de49043e9da6d7403a
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index 7a3d22f87e2..a4d98d2cd48 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -10829,7 +10829,7 @@
"notes": "Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).",
"description": "Sets a specific vertex (or center+radius for circular zones) for a Geozone."
},
- "MSP2_INAV_SET_ALT_TARGET": {
+ "MSP2_INAV_SET_TARGET": {
"code": 8725,
"mspv": 2,
"variable_len": true,
diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md
index b51d72d0473..c4ffe82882e 100644
--- a/docs/development/msp/msp_ref.md
+++ b/docs/development/msp/msp_ref.md
@@ -412,7 +412,7 @@ For current generation code, see [documentation project](https://github.com/xznh
[8721 - MSP2_INAV_SET_GEOZONE](#msp2_inav_set_geozone)
[8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex)
[8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex)
-[8725 - MSP2_INAV_SET_ALT_TARGET](#msp2_inav_set_alt_target)
+[8725 - MSP2_INAV_SET_TARGET](#msp2_inav_set_target)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
@@ -4494,7 +4494,7 @@ For current generation code, see [documentation project](https://github.com/xznh
**Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).
-## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)`
+## `MSP2_INAV_SET_TARGET (8725 / 0x2215)`
**Description:** Get or set the active altitude hold target using updateClimbRateToAltitudeController.
#### Variant: `get`
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 1597b8f88b7..5ee51d80f30 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -4113,7 +4113,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
#endif
#ifdef USE_BARO
- case MSP2_INAV_SET_ALT_TARGET:
+ case MSP2_INAV_SET_TARGET:
{
if (dataSize == 0) {
sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM);
diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h
index 251401fafcb..7d4387bdfbf 100755
--- a/src/main/msp/msp_protocol_v2_inav.h
+++ b/src/main/msp/msp_protocol_v2_inav.h
@@ -123,6 +123,6 @@
#define MSP2_INAV_GEOZONE_VERTEX 0x2212
#define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213
-#define MSP2_INAV_SET_ALT_TARGET 0x2215
+#define MSP2_INAV_SET_TARGET 0x2215
#define MSP2_INAV_FULL_LOCAL_POSE 0x2220
From 125efbbd40b9000df17f02ba118e6e8ce8148a1d Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 29 Nov 2025 14:12:29 -0500
Subject: [PATCH 07/11] Revert "change msp msg name"
This reverts commit eec54810e3ad0b8e150cae457a86d307fe69a323.
---
docs/development/msp/msp_messages.checksum | 2 +-
docs/development/msp/msp_messages.json | 2 +-
docs/development/msp/msp_ref.md | 4 ++--
src/main/fc/fc_msp.c | 2 +-
src/main/msp/msp_protocol_v2_inav.h | 2 +-
5 files changed, 6 insertions(+), 6 deletions(-)
diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum
index d6c6f3d080f..13116c1d9ef 100644
--- a/docs/development/msp/msp_messages.checksum
+++ b/docs/development/msp/msp_messages.checksum
@@ -1 +1 @@
-d03d2a93006b50de49043e9da6d7403a
+590fbe3daaa6de1cef98b521f9cf8ede
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index a4d98d2cd48..7a3d22f87e2 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -10829,7 +10829,7 @@
"notes": "Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).",
"description": "Sets a specific vertex (or center+radius for circular zones) for a Geozone."
},
- "MSP2_INAV_SET_TARGET": {
+ "MSP2_INAV_SET_ALT_TARGET": {
"code": 8725,
"mspv": 2,
"variable_len": true,
diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md
index c4ffe82882e..b51d72d0473 100644
--- a/docs/development/msp/msp_ref.md
+++ b/docs/development/msp/msp_ref.md
@@ -412,7 +412,7 @@ For current generation code, see [documentation project](https://github.com/xznh
[8721 - MSP2_INAV_SET_GEOZONE](#msp2_inav_set_geozone)
[8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex)
[8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex)
-[8725 - MSP2_INAV_SET_TARGET](#msp2_inav_set_target)
+[8725 - MSP2_INAV_SET_ALT_TARGET](#msp2_inav_set_alt_target)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
@@ -4494,7 +4494,7 @@ For current generation code, see [documentation project](https://github.com/xznh
**Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).
-## `MSP2_INAV_SET_TARGET (8725 / 0x2215)`
+## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)`
**Description:** Get or set the active altitude hold target using updateClimbRateToAltitudeController.
#### Variant: `get`
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 5ee51d80f30..1597b8f88b7 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -4113,7 +4113,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
#endif
#ifdef USE_BARO
- case MSP2_INAV_SET_TARGET:
+ case MSP2_INAV_SET_ALT_TARGET:
{
if (dataSize == 0) {
sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM);
diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h
index 7d4387bdfbf..251401fafcb 100755
--- a/src/main/msp/msp_protocol_v2_inav.h
+++ b/src/main/msp/msp_protocol_v2_inav.h
@@ -123,6 +123,6 @@
#define MSP2_INAV_GEOZONE_VERTEX 0x2212
#define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213
-#define MSP2_INAV_SET_TARGET 0x2215
+#define MSP2_INAV_SET_ALT_TARGET 0x2215
#define MSP2_INAV_FULL_LOCAL_POSE 0x2220
From 849bcad5205306b147b1ec994be71e07a60bed10 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 29 Nov 2025 14:14:05 -0500
Subject: [PATCH 08/11] change msp msg name
---
docs/development/msp/msp_messages.checksum | 2 +-
docs/development/msp/msp_messages.json | 2 +-
docs/development/msp/msp_ref.md | 4 ++--
src/main/fc/fc_msp.c | 2 +-
src/main/msp/msp_protocol_v2_inav.h | 2 +-
5 files changed, 6 insertions(+), 6 deletions(-)
diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum
index 13116c1d9ef..f90eaa7b1bf 100644
--- a/docs/development/msp/msp_messages.checksum
+++ b/docs/development/msp/msp_messages.checksum
@@ -1 +1 @@
-590fbe3daaa6de1cef98b521f9cf8ede
+7601652331e47d41941de8efdcb0c1e7
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index 7a3d22f87e2..3710e411153 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -10829,7 +10829,7 @@
"notes": "Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).",
"description": "Sets a specific vertex (or center+radius for circular zones) for a Geozone."
},
- "MSP2_INAV_SET_ALT_TARGET": {
+ "MSP2_INAV_ALT_TARGET": {
"code": 8725,
"mspv": 2,
"variable_len": true,
diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md
index b51d72d0473..ba1e32ac9a2 100644
--- a/docs/development/msp/msp_ref.md
+++ b/docs/development/msp/msp_ref.md
@@ -412,7 +412,7 @@ For current generation code, see [documentation project](https://github.com/xznh
[8721 - MSP2_INAV_SET_GEOZONE](#msp2_inav_set_geozone)
[8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex)
[8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex)
-[8725 - MSP2_INAV_SET_ALT_TARGET](#msp2_inav_set_alt_target)
+[8725 - MSP2_INAV_ALT_TARGET](#msp2_inav_alt_target)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
@@ -4494,7 +4494,7 @@ For current generation code, see [documentation project](https://github.com/xznh
**Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).
-## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)`
+## `MSP2_INAV_ALT_TARGET (8725 / 0x2215)`
**Description:** Get or set the active altitude hold target using updateClimbRateToAltitudeController.
#### Variant: `get`
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 1597b8f88b7..5ed2f29d067 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -4113,7 +4113,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
#endif
#ifdef USE_BARO
- case MSP2_INAV_SET_ALT_TARGET:
+ case MSP2_INAV_ALT_TARGET:
{
if (dataSize == 0) {
sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM);
diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h
index 251401fafcb..217409f8422 100755
--- a/src/main/msp/msp_protocol_v2_inav.h
+++ b/src/main/msp/msp_protocol_v2_inav.h
@@ -123,6 +123,6 @@
#define MSP2_INAV_GEOZONE_VERTEX 0x2212
#define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213
-#define MSP2_INAV_SET_ALT_TARGET 0x2215
+#define MSP2_INAV_ALT_TARGET 0x2215
#define MSP2_INAV_FULL_LOCAL_POSE 0x2220
From 8917ada045bda853848e2590987b486a7c74e3f9 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Mon, 5 Jan 2026 10:44:21 -0500
Subject: [PATCH 09/11] add msg to msp.json
---
docs/development/msp/inav_enums.json | 3816 ++++++++++++++++++++
docs/development/msp/msp_messages.checksum | 2 +-
docs/development/msp/msp_messages.json | 26 +
docs/development/msp/msp_ref.md | 37 +-
docs/development/msp/rev | 2 +-
src/main/fc/fc_msp.c | 20 +-
src/main/msp/msp_protocol_v2_inav.h | 2 +-
7 files changed, 3862 insertions(+), 43 deletions(-)
create mode 100644 docs/development/msp/inav_enums.json
diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json
new file mode 100644
index 00000000000..f3f09b1a803
--- /dev/null
+++ b/docs/development/msp/inav_enums.json
@@ -0,0 +1,3816 @@
+{
+ "accelerationSensor_e": {
+ "_source": "../../../src/main/sensors/acceleration.h",
+ "ACC_NONE": "0",
+ "ACC_AUTODETECT": "1",
+ "ACC_MPU6000": "2",
+ "ACC_MPU6500": "3",
+ "ACC_MPU9250": "4",
+ "ACC_BMI160": "5",
+ "ACC_ICM20689": "6",
+ "ACC_BMI088": "7",
+ "ACC_ICM42605": "8",
+ "ACC_BMI270": "9",
+ "ACC_LSM6DXX": "10",
+ "ACC_FAKE": "11",
+ "ACC_MAX": "ACC_FAKE"
+ },
+ "accEvent_t": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "ACC_EVENT_NONE": "0",
+ "ACC_EVENT_HIGH": "1",
+ "ACC_EVENT_LOW": "2",
+ "ACC_EVENT_NEG_X": "3"
+ },
+ "adcChannel_e": {
+ "_source": "../../../src/main/drivers/adc.h",
+ "ADC_CHN_NONE": "0",
+ "ADC_CHN_1": "1",
+ "ADC_CHN_2": "2",
+ "ADC_CHN_3": "3",
+ "ADC_CHN_4": "4",
+ "ADC_CHN_5": "5",
+ "ADC_CHN_6": "6",
+ "ADC_CHN_MAX": "ADC_CHN_6",
+ "ADC_CHN_COUNT": ""
+ },
+ "adcFunction_e": {
+ "_source": "../../../src/main/drivers/adc.h",
+ "ADC_BATTERY": "0",
+ "ADC_RSSI": "1",
+ "ADC_CURRENT": "2",
+ "ADC_AIRSPEED": "3",
+ "ADC_FUNCTION_COUNT": "4"
+ },
+ "adjustmentFunction_e": {
+ "_source": "../../../src/main/fc/rc_adjustments.h",
+ "ADJUSTMENT_NONE": "0",
+ "ADJUSTMENT_RC_RATE": "1",
+ "ADJUSTMENT_RC_EXPO": "2",
+ "ADJUSTMENT_THROTTLE_EXPO": "3",
+ "ADJUSTMENT_PITCH_ROLL_RATE": "4",
+ "ADJUSTMENT_YAW_RATE": "5",
+ "ADJUSTMENT_PITCH_ROLL_P": "6",
+ "ADJUSTMENT_PITCH_ROLL_I": "7",
+ "ADJUSTMENT_PITCH_ROLL_D": "8",
+ "ADJUSTMENT_PITCH_ROLL_FF": "9",
+ "ADJUSTMENT_PITCH_P": "10",
+ "ADJUSTMENT_PITCH_I": "11",
+ "ADJUSTMENT_PITCH_D": "12",
+ "ADJUSTMENT_PITCH_FF": "13",
+ "ADJUSTMENT_ROLL_P": "14",
+ "ADJUSTMENT_ROLL_I": "15",
+ "ADJUSTMENT_ROLL_D": "16",
+ "ADJUSTMENT_ROLL_FF": "17",
+ "ADJUSTMENT_YAW_P": "18",
+ "ADJUSTMENT_YAW_I": "19",
+ "ADJUSTMENT_YAW_D": "20",
+ "ADJUSTMENT_YAW_FF": "21",
+ "ADJUSTMENT_RATE_PROFILE": "22",
+ "ADJUSTMENT_PITCH_RATE": "23",
+ "ADJUSTMENT_ROLL_RATE": "24",
+ "ADJUSTMENT_RC_YAW_EXPO": "25",
+ "ADJUSTMENT_MANUAL_RC_EXPO": "26",
+ "ADJUSTMENT_MANUAL_RC_YAW_EXPO": "27",
+ "ADJUSTMENT_MANUAL_PITCH_ROLL_RATE": "28",
+ "ADJUSTMENT_MANUAL_ROLL_RATE": "29",
+ "ADJUSTMENT_MANUAL_PITCH_RATE": "30",
+ "ADJUSTMENT_MANUAL_YAW_RATE": "31",
+ "ADJUSTMENT_NAV_FW_CRUISE_THR": "32",
+ "ADJUSTMENT_NAV_FW_PITCH2THR": "33",
+ "ADJUSTMENT_ROLL_BOARD_ALIGNMENT": "34",
+ "ADJUSTMENT_PITCH_BOARD_ALIGNMENT": "35",
+ "ADJUSTMENT_LEVEL_P": "36",
+ "ADJUSTMENT_LEVEL_I": "37",
+ "ADJUSTMENT_LEVEL_D": "38",
+ "ADJUSTMENT_POS_XY_P": "39",
+ "ADJUSTMENT_POS_XY_I": "40",
+ "ADJUSTMENT_POS_XY_D": "41",
+ "ADJUSTMENT_POS_Z_P": "42",
+ "ADJUSTMENT_POS_Z_I": "43",
+ "ADJUSTMENT_POS_Z_D": "44",
+ "ADJUSTMENT_HEADING_P": "45",
+ "ADJUSTMENT_VEL_XY_P": "46",
+ "ADJUSTMENT_VEL_XY_I": "47",
+ "ADJUSTMENT_VEL_XY_D": "48",
+ "ADJUSTMENT_VEL_Z_P": "49",
+ "ADJUSTMENT_VEL_Z_I": "50",
+ "ADJUSTMENT_VEL_Z_D": "51",
+ "ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE": "52",
+ "ADJUSTMENT_VTX_POWER_LEVEL": "53",
+ "ADJUSTMENT_TPA": "54",
+ "ADJUSTMENT_TPA_BREAKPOINT": "55",
+ "ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS": "56",
+ "ADJUSTMENT_FW_TPA_TIME_CONSTANT": "57",
+ "ADJUSTMENT_FW_LEVEL_TRIM": "58",
+ "ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX": "59",
+ "ADJUSTMENT_NAV_FW_ALT_CONTROL_RESPONSE": "60",
+ "ADJUSTMENT_FUNCTION_COUNT": "61"
+ },
+ "adjustmentMode_e": {
+ "_source": "../../../src/main/fc/rc_adjustments.h",
+ "ADJUSTMENT_MODE_STEP": "0",
+ "ADJUSTMENT_MODE_SELECT": "1"
+ },
+ "afatfsAppendFreeClusterPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_INITIAL": "0",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_FIND_FREESPACE": "0",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT1": "1",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT2": "2",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FILE_DIRECTORY": "3",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_COMPLETE": "4",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_FAILURE": "5"
+ },
+ "afatfsAppendSuperclusterPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_APPEND_SUPERCLUSTER_PHASE_INIT": "0",
+ "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FREEFILE_DIRECTORY": "1",
+ "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FAT": "2",
+ "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FILE_DIRECTORY": "3"
+ },
+ "afatfsCacheBlockState_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_CACHE_STATE_EMPTY": "0",
+ "AFATFS_CACHE_STATE_IN_SYNC": "1",
+ "AFATFS_CACHE_STATE_READING": "2",
+ "AFATFS_CACHE_STATE_WRITING": "3",
+ "AFATFS_CACHE_STATE_DIRTY": "4"
+ },
+ "afatfsClusterSearchCondition_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "CLUSTER_SEARCH_FREE_AT_BEGINNING_OF_FAT_SECTOR": "0",
+ "CLUSTER_SEARCH_FREE": "1",
+ "CLUSTER_SEARCH_OCCUPIED": "2"
+ },
+ "afatfsDeleteFilePhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_DELETE_FILE_DELETE_DIRECTORY_ENTRY": "0",
+ "AFATFS_DELETE_FILE_DEALLOCATE_CLUSTERS": "1"
+ },
+ "afatfsError_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_ERROR_NONE": "0",
+ "AFATFS_ERROR_GENERIC": "1",
+ "AFATFS_ERROR_BAD_MBR": "2",
+ "AFATFS_ERROR_BAD_FILESYSTEM_HEADER": "3"
+ },
+ "afatfsExtendSubdirectoryPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_INITIAL": "0",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_ADD_FREE_CLUSTER": "0",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_WRITE_SECTORS": "1",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_SUCCESS": "2",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_FAILURE": "3"
+ },
+ "afatfsFATPattern_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FAT_PATTERN_UNTERMINATED_CHAIN": "0",
+ "AFATFS_FAT_PATTERN_TERMINATED_CHAIN": "1",
+ "AFATFS_FAT_PATTERN_FREE": "2"
+ },
+ "afatfsFileOperation_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FILE_OPERATION_NONE": "0",
+ "AFATFS_FILE_OPERATION_CREATE_FILE": "1",
+ "AFATFS_FILE_OPERATION_SEEK": "2",
+ "AFATFS_FILE_OPERATION_CLOSE": "3",
+ "AFATFS_FILE_OPERATION_TRUNCATE": "4",
+ "AFATFS_FILE_OPERATION_UNLINK": "5",
+ "AFATFS_FILE_OPERATION_APPEND_SUPERCLUSTER": [
+ "(6)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_FILE_OPERATION_LOCKED": [
+ "(7)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_FILE_OPERATION_APPEND_FREE_CLUSTER": "8",
+ "AFATFS_FILE_OPERATION_EXTEND_SUBDIRECTORY": "9"
+ },
+ "afatfsFilesystemState_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_FILESYSTEM_STATE_UNKNOWN": "0",
+ "AFATFS_FILESYSTEM_STATE_FATAL": "1",
+ "AFATFS_FILESYSTEM_STATE_INITIALIZATION": "2",
+ "AFATFS_FILESYSTEM_STATE_READY": "3"
+ },
+ "afatfsFileType_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FILE_TYPE_NONE": "0",
+ "AFATFS_FILE_TYPE_NORMAL": "1",
+ "AFATFS_FILE_TYPE_FAT16_ROOT_DIRECTORY": "2",
+ "AFATFS_FILE_TYPE_DIRECTORY": "3"
+ },
+ "afatfsFindClusterStatus_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FIND_CLUSTER_IN_PROGRESS": "0",
+ "AFATFS_FIND_CLUSTER_FOUND": "1",
+ "AFATFS_FIND_CLUSTER_FATAL": "2",
+ "AFATFS_FIND_CLUSTER_NOT_FOUND": "3"
+ },
+ "afatfsFreeSpaceSearchPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FREE_SPACE_SEARCH_PHASE_FIND_HOLE": "0",
+ "AFATFS_FREE_SPACE_SEARCH_PHASE_GROW_HOLE": "1"
+ },
+ "afatfsInitializationPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_INITIALIZATION_READ_MBR": "0",
+ "AFATFS_INITIALIZATION_READ_VOLUME_ID": "1",
+ "AFATFS_INITIALIZATION_FREEFILE_CREATE": [
+ "(2)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_CREATING": [
+ "(3)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_FAT_SEARCH": [
+ "(4)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_UPDATE_FAT": [
+ "(5)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY": [
+ "(6)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_LAST": [
+ "AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_DONE": ""
+ },
+ "afatfsOperationStatus_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_OPERATION_IN_PROGRESS": "0",
+ "AFATFS_OPERATION_SUCCESS": "1",
+ "AFATFS_OPERATION_FAILURE": "2"
+ },
+ "afatfsSaveDirectoryEntryMode_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_SAVE_DIRECTORY_NORMAL": "0",
+ "AFATFS_SAVE_DIRECTORY_FOR_CLOSE": "1",
+ "AFATFS_SAVE_DIRECTORY_DELETED": "2"
+ },
+ "afatfsSeek_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_SEEK_SET": "0",
+ "AFATFS_SEEK_CUR": "1",
+ "AFATFS_SEEK_END": "2"
+ },
+ "afatfsTruncateFilePhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_TRUNCATE_FILE_INITIAL": "0",
+ "AFATFS_TRUNCATE_FILE_UPDATE_DIRECTORY": "0",
+ "AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_NORMAL": "1",
+ "AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_CONTIGUOUS": [
+ "(2)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_TRUNCATE_FILE_PREPEND_TO_FREEFILE": [
+ "(3)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_TRUNCATE_FILE_SUCCESS": "4"
+ },
+ "airmodeHandlingType_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "STICK_CENTER": "0",
+ "THROTTLE_THRESHOLD": "1",
+ "STICK_CENTER_ONCE": "2"
+ },
+ "angle_index_t": {
+ "_source": "../../../src/main/common/axis.h",
+ "AI_ROLL": "0",
+ "AI_PITCH": "1"
+ },
+ "armingFlag_e": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "ARMED": "(1 << 2)",
+ "WAS_EVER_ARMED": "(1 << 3)",
+ "SIMULATOR_MODE_HITL": "(1 << 4)",
+ "SIMULATOR_MODE_SITL": "(1 << 5)",
+ "ARMING_DISABLED_GEOZONE": "(1 << 6)",
+ "ARMING_DISABLED_FAILSAFE_SYSTEM": "(1 << 7)",
+ "ARMING_DISABLED_NOT_LEVEL": "(1 << 8)",
+ "ARMING_DISABLED_SENSORS_CALIBRATING": "(1 << 9)",
+ "ARMING_DISABLED_SYSTEM_OVERLOADED": "(1 << 10)",
+ "ARMING_DISABLED_NAVIGATION_UNSAFE": "(1 << 11)",
+ "ARMING_DISABLED_COMPASS_NOT_CALIBRATED": "(1 << 12)",
+ "ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED": "(1 << 13)",
+ "ARMING_DISABLED_ARM_SWITCH": "(1 << 14)",
+ "ARMING_DISABLED_HARDWARE_FAILURE": "(1 << 15)",
+ "ARMING_DISABLED_BOXFAILSAFE": "(1 << 16)",
+ "ARMING_DISABLED_RC_LINK": "(1 << 18)",
+ "ARMING_DISABLED_THROTTLE": "(1 << 19)",
+ "ARMING_DISABLED_CLI": "(1 << 20)",
+ "ARMING_DISABLED_CMS_MENU": "(1 << 21)",
+ "ARMING_DISABLED_OSD_MENU": "(1 << 22)",
+ "ARMING_DISABLED_ROLLPITCH_NOT_CENTERED": "(1 << 23)",
+ "ARMING_DISABLED_SERVO_AUTOTRIM": "(1 << 24)",
+ "ARMING_DISABLED_OOM": "(1 << 25)",
+ "ARMING_DISABLED_INVALID_SETTING": "(1 << 26)",
+ "ARMING_DISABLED_PWM_OUTPUT_ERROR": "(1 << 27)",
+ "ARMING_DISABLED_NO_PREARM": "(1 << 28)",
+ "ARMING_DISABLED_DSHOT_BEEPER": "(1 << 29)",
+ "ARMING_DISABLED_LANDING_DETECTED": "(1 << 30)",
+ "ARMING_DISABLED_ALL_FLAGS": "(ARMING_DISABLED_GEOZONE | ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING | ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE | ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED | ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE | ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING | ARMING_DISABLED_PWM_OUTPUT_ERROR | ARMING_DISABLED_NO_PREARM | ARMING_DISABLED_DSHOT_BEEPER | ARMING_DISABLED_LANDING_DETECTED)"
+ },
+ "axis_e": {
+ "_source": "../../../src/main/common/axis.h",
+ "X": "0",
+ "Y": "1",
+ "Z": "2"
+ },
+ "barometerState_e": {
+ "_source": "../../../src/main/sensors/barometer.c",
+ "BAROMETER_NEEDS_SAMPLES": "0",
+ "BAROMETER_NEEDS_CALCULATION": "1"
+ },
+ "baroSensor_e": {
+ "_source": "../../../src/main/sensors/barometer.h",
+ "BARO_NONE": "0",
+ "BARO_AUTODETECT": "1",
+ "BARO_BMP085": "2",
+ "BARO_MS5611": "3",
+ "BARO_BMP280": "4",
+ "BARO_MS5607": "5",
+ "BARO_LPS25H": "6",
+ "BARO_SPL06": "7",
+ "BARO_BMP388": "8",
+ "BARO_DPS310": "9",
+ "BARO_B2SMPB": "10",
+ "BARO_MSP": "11",
+ "BARO_FAKE": "12",
+ "BARO_MAX": "BARO_FAKE"
+ },
+ "batCapacityUnit_e": {
+ "_source": "../../../src/main/sensors/battery_config_structs.h",
+ "BAT_CAPACITY_UNIT_MAH": "0",
+ "BAT_CAPACITY_UNIT_MWH": "1"
+ },
+ "batteryState_e": {
+ "_source": "../../../src/main/sensors/battery.h",
+ "BATTERY_OK": "0",
+ "BATTERY_WARNING": "1",
+ "BATTERY_CRITICAL": "2",
+ "BATTERY_NOT_PRESENT": "3"
+ },
+ "batVoltageSource_e": {
+ "_source": "../../../src/main/sensors/battery_config_structs.h",
+ "BAT_VOLTAGE_RAW": "0",
+ "BAT_VOLTAGE_SAG_COMP": "1"
+ },
+ "baudRate_e": {
+ "_source": "../../../src/main/io/serial.h",
+ "BAUD_AUTO": "0",
+ "BAUD_1200": "1",
+ "BAUD_2400": "2",
+ "BAUD_4800": "3",
+ "BAUD_9600": "4",
+ "BAUD_19200": "5",
+ "BAUD_38400": "6",
+ "BAUD_57600": "7",
+ "BAUD_115200": "8",
+ "BAUD_230400": "9",
+ "BAUD_250000": "10",
+ "BAUD_460800": "11",
+ "BAUD_921600": "12",
+ "BAUD_1000000": "13",
+ "BAUD_1500000": "14",
+ "BAUD_2000000": "15",
+ "BAUD_2470000": "16",
+ "BAUD_MIN": "BAUD_AUTO",
+ "BAUD_MAX": "BAUD_2470000"
+ },
+ "beeperMode_e": {
+ "_source": "../../../src/main/io/beeper.h",
+ "BEEPER_SILENCE": "0",
+ "BEEPER_RUNTIME_CALIBRATION_DONE": "1",
+ "BEEPER_HARDWARE_FAILURE": "2",
+ "BEEPER_RX_LOST": "3",
+ "BEEPER_RX_LOST_LANDING": "4",
+ "BEEPER_DISARMING": "5",
+ "BEEPER_ARMING": "6",
+ "BEEPER_ARMING_GPS_FIX": "7",
+ "BEEPER_BAT_CRIT_LOW": "8",
+ "BEEPER_BAT_LOW": "9",
+ "BEEPER_GPS_STATUS": "10",
+ "BEEPER_RX_SET": "11",
+ "BEEPER_ACTION_SUCCESS": "12",
+ "BEEPER_ACTION_FAIL": "13",
+ "BEEPER_READY_BEEP": "14",
+ "BEEPER_MULTI_BEEPS": "15",
+ "BEEPER_DISARM_REPEAT": "16",
+ "BEEPER_ARMED": "17",
+ "BEEPER_SYSTEM_INIT": "18",
+ "BEEPER_USB": "19",
+ "BEEPER_LAUNCH_MODE_ENABLED": "20",
+ "BEEPER_LAUNCH_MODE_LOW_THROTTLE": "21",
+ "BEEPER_LAUNCH_MODE_IDLE_START": "22",
+ "BEEPER_CAM_CONNECTION_OPEN": "23",
+ "BEEPER_CAM_CONNECTION_CLOSE": "24",
+ "BEEPER_ALL": "25",
+ "BEEPER_PREFERENCE": "26"
+ },
+ "biquadFilterType_e": {
+ "_source": "../../../src/main/common/filter.h",
+ "FILTER_LPF": "0",
+ "FILTER_NOTCH": "1"
+ },
+ "blackboxBufferReserveStatus_e": {
+ "_source": "../../../src/main/blackbox/blackbox_io.h",
+ "BLACKBOX_RESERVE_SUCCESS": "0",
+ "BLACKBOX_RESERVE_TEMPORARY_FAILURE": "1",
+ "BLACKBOX_RESERVE_PERMANENT_FAILURE": "2"
+ },
+ "blackboxFeatureMask_e": {
+ "_source": "../../../src/main/blackbox/blackbox.h",
+ "BLACKBOX_FEATURE_NAV_ACC": "1 << 0",
+ "BLACKBOX_FEATURE_NAV_POS": "1 << 1",
+ "BLACKBOX_FEATURE_NAV_PID": "1 << 2",
+ "BLACKBOX_FEATURE_MAG": "1 << 3",
+ "BLACKBOX_FEATURE_ACC": "1 << 4",
+ "BLACKBOX_FEATURE_ATTITUDE": "1 << 5",
+ "BLACKBOX_FEATURE_RC_DATA": "1 << 6",
+ "BLACKBOX_FEATURE_RC_COMMAND": "1 << 7",
+ "BLACKBOX_FEATURE_MOTORS": "1 << 8",
+ "BLACKBOX_FEATURE_GYRO_RAW": "1 << 9",
+ "BLACKBOX_FEATURE_GYRO_PEAKS_ROLL": "1 << 10",
+ "BLACKBOX_FEATURE_GYRO_PEAKS_PITCH": "1 << 11",
+ "BLACKBOX_FEATURE_GYRO_PEAKS_YAW": "1 << 12",
+ "BLACKBOX_FEATURE_SERVOS": "1 << 13"
+ },
+ "bmi270Register_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_bmi270.c",
+ "BMI270_REG_CHIP_ID": "0",
+ "BMI270_REG_ERR_REG": "2",
+ "BMI270_REG_STATUS": "3",
+ "BMI270_REG_ACC_DATA_X_LSB": "12",
+ "BMI270_REG_GYR_DATA_X_LSB": "18",
+ "BMI270_REG_SENSORTIME_0": "24",
+ "BMI270_REG_SENSORTIME_1": "25",
+ "BMI270_REG_SENSORTIME_2": "26",
+ "BMI270_REG_EVENT": "27",
+ "BMI270_REG_INT_STATUS_0": "28",
+ "BMI270_REG_INT_STATUS_1": "29",
+ "BMI270_REG_INTERNAL_STATUS": "33",
+ "BMI270_REG_TEMPERATURE_LSB": "34",
+ "BMI270_REG_TEMPERATURE_MSB": "35",
+ "BMI270_REG_FIFO_LENGTH_LSB": "36",
+ "BMI270_REG_FIFO_LENGTH_MSB": "37",
+ "BMI270_REG_FIFO_DATA": "38",
+ "BMI270_REG_ACC_CONF": "64",
+ "BMI270_REG_ACC_RANGE": "65",
+ "BMI270_REG_GYRO_CONF": "66",
+ "BMI270_REG_GYRO_RANGE": "67",
+ "BMI270_REG_AUX_CONF": "68",
+ "BMI270_REG_FIFO_DOWNS": "69",
+ "BMI270_REG_FIFO_WTM_0": "70",
+ "BMI270_REG_FIFO_WTM_1": "71",
+ "BMI270_REG_FIFO_CONFIG_0": "72",
+ "BMI270_REG_FIFO_CONFIG_1": "73",
+ "BMI270_REG_SATURATION": "74",
+ "BMI270_REG_INT1_IO_CTRL": "83",
+ "BMI270_REG_INT2_IO_CTRL": "84",
+ "BMI270_REG_INT_LATCH": "85",
+ "BMI270_REG_INT1_MAP_FEAT": "86",
+ "BMI270_REG_INT2_MAP_FEAT": "87",
+ "BMI270_REG_INT_MAP_DATA": "88",
+ "BMI270_REG_INIT_CTRL": "89",
+ "BMI270_REG_INIT_DATA": "94",
+ "BMI270_REG_ACC_SELF_TEST": "109",
+ "BMI270_REG_GYR_SELF_TEST_AXES": "110",
+ "BMI270_REG_PWR_CONF": "124",
+ "BMI270_REG_PWR_CTRL": "125",
+ "BMI270_REG_CMD": "126"
+ },
+ "bootLogEventCode_e": {
+ "_source": "../../../src/main/drivers/logging_codes.h",
+ "BOOT_EVENT_CONFIG_LOADED": "0",
+ "BOOT_EVENT_SYSTEM_INIT_DONE": "1",
+ "BOOT_EVENT_PWM_INIT_DONE": "2",
+ "BOOT_EVENT_EXTRA_BOOT_DELAY": "3",
+ "BOOT_EVENT_SENSOR_INIT_DONE": "4",
+ "BOOT_EVENT_GPS_INIT_DONE": "5",
+ "BOOT_EVENT_LEDSTRIP_INIT_DONE": "6",
+ "BOOT_EVENT_TELEMETRY_INIT_DONE": "7",
+ "BOOT_EVENT_SYSTEM_READY": "8",
+ "BOOT_EVENT_GYRO_DETECTION": "9",
+ "BOOT_EVENT_ACC_DETECTION": "10",
+ "BOOT_EVENT_BARO_DETECTION": "11",
+ "BOOT_EVENT_MAG_DETECTION": "12",
+ "BOOT_EVENT_RANGEFINDER_DETECTION": "13",
+ "BOOT_EVENT_MAG_INIT_FAILED": "14",
+ "BOOT_EVENT_HMC5883L_READ_OK_COUNT": "15",
+ "BOOT_EVENT_HMC5883L_READ_FAILED": "16",
+ "BOOT_EVENT_HMC5883L_SATURATION": "17",
+ "BOOT_EVENT_TIMER_CH_SKIPPED": "18",
+ "BOOT_EVENT_TIMER_CH_MAPPED": "19",
+ "BOOT_EVENT_PITOT_DETECTION": "20",
+ "BOOT_EVENT_TEMP_SENSOR_DETECTION": "21",
+ "BOOT_EVENT_1WIRE_DETECTION": "22",
+ "BOOT_EVENT_HARDWARE_IO_CONFLICT": "23",
+ "BOOT_EVENT_OPFLOW_DETECTION": "24",
+ "BOOT_EVENT_CODE_COUNT": "25"
+ },
+ "bootLogFlags_e": {
+ "_source": "../../../src/main/drivers/logging_codes.h",
+ "BOOT_EVENT_FLAGS_NONE": "0",
+ "BOOT_EVENT_FLAGS_WARNING": "1 << 0",
+ "BOOT_EVENT_FLAGS_ERROR": "1 << 1",
+ "BOOT_EVENT_FLAGS_PARAM16": "1 << 14",
+ "BOOT_EVENT_FLAGS_PARAM32": "1 << 15"
+ },
+ "boxId_e": {
+ "_source": "../../../src/main/fc/rc_modes.h",
+ "BOXARM": "0",
+ "BOXANGLE": "1",
+ "BOXHORIZON": "2",
+ "BOXNAVALTHOLD": "3",
+ "BOXHEADINGHOLD": "4",
+ "BOXHEADFREE": "5",
+ "BOXHEADADJ": "6",
+ "BOXCAMSTAB": "7",
+ "BOXNAVRTH": "8",
+ "BOXNAVPOSHOLD": "9",
+ "BOXMANUAL": "10",
+ "BOXBEEPERON": "11",
+ "BOXLEDLOW": "12",
+ "BOXLIGHTS": "13",
+ "BOXNAVLAUNCH": "14",
+ "BOXOSD": "15",
+ "BOXTELEMETRY": "16",
+ "BOXBLACKBOX": "17",
+ "BOXFAILSAFE": "18",
+ "BOXNAVWP": "19",
+ "BOXAIRMODE": "20",
+ "BOXHOMERESET": "21",
+ "BOXGCSNAV": "22",
+ "BOXSURFACE": "24",
+ "BOXFLAPERON": "25",
+ "BOXTURNASSIST": "26",
+ "BOXAUTOTRIM": "27",
+ "BOXAUTOTUNE": "28",
+ "BOXCAMERA1": "29",
+ "BOXCAMERA2": "30",
+ "BOXCAMERA3": "31",
+ "BOXOSDALT1": "32",
+ "BOXOSDALT2": "33",
+ "BOXOSDALT3": "34",
+ "BOXNAVCOURSEHOLD": "35",
+ "BOXBRAKING": "36",
+ "BOXUSER1": "37",
+ "BOXUSER2": "38",
+ "BOXFPVANGLEMIX": "39",
+ "BOXLOITERDIRCHN": "40",
+ "BOXMSPRCOVERRIDE": "41",
+ "BOXPREARM": "42",
+ "BOXTURTLE": "43",
+ "BOXNAVCRUISE": "44",
+ "BOXAUTOLEVEL": "45",
+ "BOXPLANWPMISSION": "46",
+ "BOXSOARING": "47",
+ "BOXUSER3": "48",
+ "BOXUSER4": "49",
+ "BOXCHANGEMISSION": "50",
+ "BOXBEEPERMUTE": "51",
+ "BOXMULTIFUNCTION": "52",
+ "BOXMIXERPROFILE": "53",
+ "BOXMIXERTRANSITION": "54",
+ "BOXANGLEHOLD": "55",
+ "BOXGIMBALTLOCK": "56",
+ "BOXGIMBALRLOCK": "57",
+ "BOXGIMBALCENTER": "58",
+ "BOXGIMBALHTRK": "59",
+ "CHECKBOX_ITEM_COUNT": "60"
+ },
+ "busIndex_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "BUSINDEX_1": "0",
+ "BUSINDEX_2": "1",
+ "BUSINDEX_3": "2",
+ "BUSINDEX_4": "3"
+ },
+ "busSpeed_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "BUS_SPEED_INITIALIZATION": "0",
+ "BUS_SPEED_SLOW": "1",
+ "BUS_SPEED_STANDARD": "2",
+ "BUS_SPEED_FAST": "3",
+ "BUS_SPEED_ULTRAFAST": "4"
+ },
+ "busType_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "BUSTYPE_ANY": "0",
+ "BUSTYPE_NONE": "0",
+ "BUSTYPE_I2C": "1",
+ "BUSTYPE_SPI": "2",
+ "BUSTYPE_SDIO": "3"
+ },
+ "channelType_t": {
+ "_source": "../../../src/main/drivers/timer.h",
+ "TYPE_FREE": "0",
+ "TYPE_PWMINPUT": "1",
+ "TYPE_PPMINPUT": "2",
+ "TYPE_PWMOUTPUT_MOTOR": "3",
+ "TYPE_PWMOUTPUT_FAST": "4",
+ "TYPE_PWMOUTPUT_SERVO": "5",
+ "TYPE_SOFTSERIAL_RX": "6",
+ "TYPE_SOFTSERIAL_TX": "7",
+ "TYPE_SOFTSERIAL_RXTX": "8",
+ "TYPE_SOFTSERIAL_AUXTIMER": "9",
+ "TYPE_ADC": "10",
+ "TYPE_SERIAL_RX": "11",
+ "TYPE_SERIAL_TX": "12",
+ "TYPE_SERIAL_RXTX": "13",
+ "TYPE_TIMER": "14"
+ },
+ "climbRateToAltitudeControllerMode_e": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "ROC_TO_ALT_CURRENT": "0",
+ "ROC_TO_ALT_CONSTANT": "1",
+ "ROC_TO_ALT_TARGET": "2"
+ },
+ "colorComponent_e": {
+ "_source": "../../../src/main/common/color.h",
+ "RGB_RED": "0",
+ "RGB_GREEN": "1",
+ "RGB_BLUE": "2"
+ },
+ "colorId_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "COLOR_BLACK": "0",
+ "COLOR_WHITE": "1",
+ "COLOR_RED": "2",
+ "COLOR_ORANGE": "3",
+ "COLOR_YELLOW": "4",
+ "COLOR_LIME_GREEN": "5",
+ "COLOR_GREEN": "6",
+ "COLOR_MINT_GREEN": "7",
+ "COLOR_CYAN": "8",
+ "COLOR_LIGHT_BLUE": "9",
+ "COLOR_BLUE": "10",
+ "COLOR_DARK_VIOLET": "11",
+ "COLOR_MAGENTA": "12",
+ "COLOR_DEEP_PINK": "13"
+ },
+ "crsfActiveAntenna_e": {
+ "_source": "../../../src/main/telemetry/crsf.c",
+ "CRSF_ACTIVE_ANTENNA1": "0",
+ "CRSF_ACTIVE_ANTENNA2": "1"
+ },
+ "crsfAddress_e": {
+ "_source": "../../../src/main/rx/crsf.h",
+ "CRSF_ADDRESS_BROADCAST": "0",
+ "CRSF_ADDRESS_USB": "16",
+ "CRSF_ADDRESS_TBS_CORE_PNP_PRO": "128",
+ "CRSF_ADDRESS_RESERVED1": "138",
+ "CRSF_ADDRESS_CURRENT_SENSOR": "192",
+ "CRSF_ADDRESS_GPS": "194",
+ "CRSF_ADDRESS_TBS_BLACKBOX": "196",
+ "CRSF_ADDRESS_FLIGHT_CONTROLLER": "200",
+ "CRSF_ADDRESS_RESERVED2": "202",
+ "CRSF_ADDRESS_RACE_TAG": "204",
+ "CRSF_ADDRESS_RADIO_TRANSMITTER": "234",
+ "CRSF_ADDRESS_CRSF_RECEIVER": "236",
+ "CRSF_ADDRESS_CRSF_TRANSMITTER": "238"
+ },
+ "crsfFrameType_e": {
+ "_source": "../../../src/main/rx/crsf.h",
+ "CRSF_FRAMETYPE_GPS": "2",
+ "CRSF_FRAMETYPE_VARIO_SENSOR": "7",
+ "CRSF_FRAMETYPE_BATTERY_SENSOR": "8",
+ "CRSF_FRAMETYPE_BAROMETER_ALTITUDE": "9",
+ "CRSF_FRAMETYPE_LINK_STATISTICS": "20",
+ "CRSF_FRAMETYPE_RC_CHANNELS_PACKED": "22",
+ "CRSF_FRAMETYPE_ATTITUDE": "30",
+ "CRSF_FRAMETYPE_FLIGHT_MODE": "33",
+ "CRSF_FRAMETYPE_DEVICE_PING": "40",
+ "CRSF_FRAMETYPE_DEVICE_INFO": "41",
+ "CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY": "43",
+ "CRSF_FRAMETYPE_PARAMETER_READ": "44",
+ "CRSF_FRAMETYPE_PARAMETER_WRITE": "45",
+ "CRSF_FRAMETYPE_COMMAND": "50",
+ "CRSF_FRAMETYPE_MSP_REQ": "122",
+ "CRSF_FRAMETYPE_MSP_RESP": "123",
+ "CRSF_FRAMETYPE_MSP_WRITE": "124",
+ "CRSF_FRAMETYPE_DISPLAYPORT_CMD": "125"
+ },
+ "crsfFrameTypeIndex_e": {
+ "_source": "../../../src/main/telemetry/crsf.c",
+ "CRSF_FRAME_START_INDEX": "0",
+ "CRSF_FRAME_ATTITUDE_INDEX": "CRSF_FRAME_START_INDEX",
+ "CRSF_FRAME_BATTERY_SENSOR_INDEX": "",
+ "CRSF_FRAME_FLIGHT_MODE_INDEX": "",
+ "CRSF_FRAME_GPS_INDEX": "",
+ "CRSF_FRAME_VARIO_SENSOR_INDEX": "",
+ "CRSF_FRAME_BAROMETER_ALTITUDE_INDEX": "",
+ "CRSF_SCHEDULE_COUNT_MAX": ""
+ },
+ "crsrRfMode_e": {
+ "_source": "../../../src/main/telemetry/crsf.c",
+ "CRSF_RF_MODE_4_HZ": "0",
+ "CRSF_RF_MODE_50_HZ": "1",
+ "CRSF_RF_MODE_150_HZ": "2"
+ },
+ "crsrRfPower_e": {
+ "_source": "../../../src/main/telemetry/crsf.c",
+ "CRSF_RF_POWER_0_mW": "0",
+ "CRSF_RF_POWER_10_mW": "1",
+ "CRSF_RF_POWER_25_mW": "2",
+ "CRSF_RF_POWER_100_mW": "3",
+ "CRSF_RF_POWER_500_mW": "4",
+ "CRSF_RF_POWER_1000_mW": "5",
+ "CRSF_RF_POWER_2000_mW": "6",
+ "CRSF_RF_POWER_250_mW": "7"
+ },
+ "currentSensor_e": {
+ "_source": "../../../src/main/sensors/battery_config_structs.h",
+ "CURRENT_SENSOR_NONE": "0",
+ "CURRENT_SENSOR_ADC": "1",
+ "CURRENT_SENSOR_VIRTUAL": "2",
+ "CURRENT_SENSOR_FAKE": "3",
+ "CURRENT_SENSOR_ESC": "4",
+ "CURRENT_SENSOR_SMARTPORT": "5",
+ "CURRENT_SENSOR_MAX": "CURRENT_SENSOR_SMARTPORT"
+ },
+ "devHardwareType_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "DEVHW_NONE": "0",
+ "DEVHW_MPU6000": "1",
+ "DEVHW_MPU6500": "2",
+ "DEVHW_BMI160": "3",
+ "DEVHW_BMI088_GYRO": "4",
+ "DEVHW_BMI088_ACC": "5",
+ "DEVHW_ICM20689": "6",
+ "DEVHW_ICM42605": "7",
+ "DEVHW_BMI270": "8",
+ "DEVHW_LSM6D": "9",
+ "DEVHW_MPU9250": "10",
+ "DEVHW_BMP085": "11",
+ "DEVHW_BMP280": "12",
+ "DEVHW_MS5611": "13",
+ "DEVHW_MS5607": "14",
+ "DEVHW_LPS25H": "15",
+ "DEVHW_SPL06": "16",
+ "DEVHW_BMP388": "17",
+ "DEVHW_DPS310": "18",
+ "DEVHW_B2SMPB": "19",
+ "DEVHW_HMC5883": "20",
+ "DEVHW_AK8963": "21",
+ "DEVHW_AK8975": "22",
+ "DEVHW_IST8310_0": "23",
+ "DEVHW_IST8310_1": "24",
+ "DEVHW_IST8308": "25",
+ "DEVHW_QMC5883": "26",
+ "DEVHW_QMC5883P": "27",
+ "DEVHW_MAG3110": "28",
+ "DEVHW_LIS3MDL": "29",
+ "DEVHW_RM3100": "30",
+ "DEVHW_VCM5883": "31",
+ "DEVHW_MLX90393": "32",
+ "DEVHW_LM75_0": "33",
+ "DEVHW_LM75_1": "34",
+ "DEVHW_LM75_2": "35",
+ "DEVHW_LM75_3": "36",
+ "DEVHW_LM75_4": "37",
+ "DEVHW_LM75_5": "38",
+ "DEVHW_LM75_6": "39",
+ "DEVHW_LM75_7": "40",
+ "DEVHW_DS2482": "41",
+ "DEVHW_MAX7456": "42",
+ "DEVHW_SRF10": "43",
+ "DEVHW_VL53L0X": "44",
+ "DEVHW_VL53L1X": "45",
+ "DEVHW_US42": "46",
+ "DEVHW_TOF10120_I2C": "47",
+ "DEVHW_TERARANGER_EVO_I2C": "48",
+ "DEVHW_MS4525": "49",
+ "DEVHW_DLVR": "50",
+ "DEVHW_M25P16": "51",
+ "DEVHW_W25N": "52",
+ "DEVHW_UG2864": "53",
+ "DEVHW_SDCARD": "54",
+ "DEVHW_IRLOCK": "55",
+ "DEVHW_PCF8574": "56"
+ },
+ "deviceFlags_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "DEVFLAGS_NONE": "0",
+ "DEVFLAGS_USE_RAW_REGISTERS": "(1 << 0)",
+ "DEVFLAGS_USE_MANUAL_DEVICE_SELECT": "(1 << 1)",
+ "DEVFLAGS_SPI_MODE_0": "(1 << 2)"
+ },
+ "displayCanvasBitmapOption_t": {
+ "_source": "../../../src/main/drivers/display_canvas.h",
+ "DISPLAY_CANVAS_BITMAP_OPT_INVERT_COLORS": "1 << 0",
+ "DISPLAY_CANVAS_BITMAP_OPT_SOLID_BACKGROUND": "1 << 1",
+ "DISPLAY_CANVAS_BITMAP_OPT_ERASE_TRANSPARENT": "1 << 2"
+ },
+ "displayCanvasColor_e": {
+ "_source": "../../../src/main/drivers/display_canvas.h",
+ "DISPLAY_CANVAS_COLOR_BLACK": "0",
+ "DISPLAY_CANVAS_COLOR_TRANSPARENT": "1",
+ "DISPLAY_CANVAS_COLOR_WHITE": "2",
+ "DISPLAY_CANVAS_COLOR_GRAY": "3"
+ },
+ "displayCanvasOutlineType_e": {
+ "_source": "../../../src/main/drivers/display_canvas.h",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_NONE": "0",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_TOP": "1 << 0",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_RIGHT": "1 << 1",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_BOTTOM": "1 << 2",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_LEFT": "1 << 3"
+ },
+ "displayportMspCommand_e": {
+ "_source": "../../../src/main/io/displayport_msp.h",
+ "MSP_DP_HEARTBEAT": "0",
+ "MSP_DP_RELEASE": "1",
+ "MSP_DP_CLEAR_SCREEN": "2",
+ "MSP_DP_WRITE_STRING": "3",
+ "MSP_DP_DRAW_SCREEN": "4",
+ "MSP_DP_OPTIONS": "5",
+ "MSP_DP_SYS": "6",
+ "MSP_DP_COUNT": "7"
+ },
+ "displayTransactionOption_e": {
+ "_source": "../../../src/main/drivers/display.h",
+ "DISPLAY_TRANSACTION_OPT_NONE": "0",
+ "DISPLAY_TRANSACTION_OPT_PROFILED": "1 << 0",
+ "DISPLAY_TRANSACTION_OPT_RESET_DRAWING": "1 << 1"
+ },
+ "displayWidgetType_e": {
+ "_source": "../../../src/main/drivers/display_widgets.h",
+ "DISPLAY_WIDGET_TYPE_AHI": "0",
+ "DISPLAY_WIDGET_TYPE_SIDEBAR": "1"
+ },
+ "DjiCraftNameElements_t": {
+ "_source": "../../../src/main/io/osd_dji_hd.c",
+ "DJI_OSD_CN_MESSAGES": "0",
+ "DJI_OSD_CN_THROTTLE": "1",
+ "DJI_OSD_CN_THROTTLE_AUTO_THR": "2",
+ "DJI_OSD_CN_AIR_SPEED": "3",
+ "DJI_OSD_CN_EFFICIENCY": "4",
+ "DJI_OSD_CN_DISTANCE": "5",
+ "DJI_OSD_CN_ADJUSTEMNTS": "6",
+ "DJI_OSD_CN_MAX_ELEMENTS": "7"
+ },
+ "dshotCommands_e": {
+ "_source": "../../../src/main/drivers/pwm_output.h",
+ "DSHOT_CMD_SPIN_DIRECTION_NORMAL": "20",
+ "DSHOT_CMD_SPIN_DIRECTION_REVERSED": "21"
+ },
+ "dumpFlags_e": {
+ "_source": "../../../src/main/fc/cli.c",
+ "DUMP_MASTER": "(1 << 0)",
+ "DUMP_CONTROL_PROFILE": "(1 << 1)",
+ "DUMP_BATTERY_PROFILE": "(1 << 2)",
+ "DUMP_MIXER_PROFILE": "(1 << 3)",
+ "DUMP_ALL": "(1 << 4)",
+ "DO_DIFF": "(1 << 5)",
+ "SHOW_DEFAULTS": "(1 << 6)",
+ "HIDE_UNUSED": "(1 << 7)"
+ },
+ "dynamicGyroNotchMode_e": {
+ "_source": "../../../src/main/sensors/gyro.h",
+ "DYNAMIC_NOTCH_MODE_2D": "0",
+ "DYNAMIC_NOTCH_MODE_3D": "1"
+ },
+ "emergLandState_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "EMERG_LAND_IDLE": "0",
+ "EMERG_LAND_IN_PROGRESS": "1",
+ "EMERG_LAND_HAS_LANDED": "2"
+ },
+ "escSensorFrameStatus_t": {
+ "_source": "../../../src/main/sensors/esc_sensor.c",
+ "ESC_SENSOR_FRAME_PENDING": "0",
+ "ESC_SENSOR_FRAME_COMPLETE": "1",
+ "ESC_SENSOR_FRAME_FAILED": "2"
+ },
+ "escSensorState_t": {
+ "_source": "../../../src/main/sensors/esc_sensor.c",
+ "ESC_SENSOR_WAIT_STARTUP": "0",
+ "ESC_SENSOR_READY": "1",
+ "ESC_SENSOR_WAITING": "2"
+ },
+ "failsafeChannelBehavior_e": {
+ "_source": "../../../src/main/flight/failsafe.c",
+ "FAILSAFE_CHANNEL_HOLD": "0",
+ "FAILSAFE_CHANNEL_NEUTRAL": "1"
+ },
+ "failsafePhase_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "FAILSAFE_IDLE": "0",
+ "FAILSAFE_RX_LOSS_DETECTED": "1",
+ "FAILSAFE_RX_LOSS_IDLE": "2",
+ "FAILSAFE_RETURN_TO_HOME": "3",
+ "FAILSAFE_LANDING": "4",
+ "FAILSAFE_LANDED": "5",
+ "FAILSAFE_RX_LOSS_MONITORING": "6",
+ "FAILSAFE_RX_LOSS_RECOVERED": "7"
+ },
+ "failsafeProcedure_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "FAILSAFE_PROCEDURE_AUTO_LANDING": "0",
+ "FAILSAFE_PROCEDURE_DROP_IT": "1",
+ "FAILSAFE_PROCEDURE_RTH": "2",
+ "FAILSAFE_PROCEDURE_NONE": "3"
+ },
+ "failsafeRxLinkState_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "FAILSAFE_RXLINK_DOWN": "0",
+ "FAILSAFE_RXLINK_UP": "1"
+ },
+ "failureMode_e": {
+ "_source": "../../../src/main/drivers/system.h",
+ "FAILURE_DEVELOPER": "0",
+ "FAILURE_MISSING_ACC": "1",
+ "FAILURE_ACC_INIT": "2",
+ "FAILURE_ACC_INCOMPATIBLE": "3",
+ "FAILURE_INVALID_EEPROM_CONTENTS": "4",
+ "FAILURE_FLASH_WRITE_FAILED": "5",
+ "FAILURE_GYRO_INIT_FAILED": "6",
+ "FAILURE_FLASH_READ_FAILED": "7"
+ },
+ "fatFilesystemType_e": {
+ "_source": "../../../src/main/io/asyncfatfs/fat_standard.h",
+ "FAT_FILESYSTEM_TYPE_INVALID": "0",
+ "FAT_FILESYSTEM_TYPE_FAT12": "1",
+ "FAT_FILESYSTEM_TYPE_FAT16": "2",
+ "FAT_FILESYSTEM_TYPE_FAT32": "3"
+ },
+ "features_e": {
+ "_source": "../../../src/main/fc/config.h",
+ "FEATURE_THR_VBAT_COMP": "1 << 0",
+ "FEATURE_VBAT": "1 << 1",
+ "FEATURE_TX_PROF_SEL": "1 << 2",
+ "FEATURE_BAT_PROFILE_AUTOSWITCH": "1 << 3",
+ "FEATURE_GEOZONE": "1 << 4",
+ "FEATURE_UNUSED_1": "1 << 5",
+ "FEATURE_SOFTSERIAL": "1 << 6",
+ "FEATURE_GPS": "1 << 7",
+ "FEATURE_UNUSED_3": "1 << 8",
+ "FEATURE_UNUSED_4": "1 << 9",
+ "FEATURE_TELEMETRY": "1 << 10",
+ "FEATURE_CURRENT_METER": "1 << 11",
+ "FEATURE_REVERSIBLE_MOTORS": "1 << 12",
+ "FEATURE_UNUSED_5": "1 << 13",
+ "FEATURE_UNUSED_6": "1 << 14",
+ "FEATURE_RSSI_ADC": "1 << 15",
+ "FEATURE_LED_STRIP": "1 << 16",
+ "FEATURE_DASHBOARD": "1 << 17",
+ "FEATURE_UNUSED_7": "1 << 18",
+ "FEATURE_BLACKBOX": "1 << 19",
+ "FEATURE_UNUSED_10": "1 << 20",
+ "FEATURE_TRANSPONDER": "1 << 21",
+ "FEATURE_AIRMODE": "1 << 22",
+ "FEATURE_SUPEREXPO_RATES": "1 << 23",
+ "FEATURE_VTX": "1 << 24",
+ "FEATURE_UNUSED_8": "1 << 25",
+ "FEATURE_UNUSED_9": "1 << 26",
+ "FEATURE_UNUSED_11": "1 << 27",
+ "FEATURE_PWM_OUTPUT_ENABLE": "1 << 28",
+ "FEATURE_OSD": "1 << 29",
+ "FEATURE_FW_LAUNCH": "1 << 30",
+ "FEATURE_FW_AUTOTRIM": "1 << 31"
+ },
+ "filterType_e": {
+ "_source": "../../../src/main/common/filter.h",
+ "FILTER_PT1": "0",
+ "FILTER_BIQUAD": "1",
+ "FILTER_PT2": "2",
+ "FILTER_PT3": "3",
+ "FILTER_LULU": "4"
+ },
+ "fixedWingLaunchEvent_t": {
+ "_source": "../../../src/main/navigation/navigation_fw_launch.c",
+ "FW_LAUNCH_EVENT_NONE": "0",
+ "FW_LAUNCH_EVENT_SUCCESS": "1",
+ "FW_LAUNCH_EVENT_GOTO_DETECTION": "2",
+ "FW_LAUNCH_EVENT_ABORT": "3",
+ "FW_LAUNCH_EVENT_THROTTLE_LOW": "4",
+ "FW_LAUNCH_EVENT_COUNT": "5"
+ },
+ "fixedWingLaunchMessage_t": {
+ "_source": "../../../src/main/navigation/navigation_fw_launch.c",
+ "FW_LAUNCH_MESSAGE_TYPE_NONE": "0",
+ "FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE": "1",
+ "FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE": "2",
+ "FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION": "3",
+ "FW_LAUNCH_MESSAGE_TYPE_IN_PROGRESS": "4",
+ "FW_LAUNCH_MESSAGE_TYPE_FINISHING": "5"
+ },
+ "fixedWingLaunchState_t": {
+ "_source": "../../../src/main/navigation/navigation_fw_launch.c",
+ "FW_LAUNCH_STATE_WAIT_THROTTLE": "0",
+ "FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT": "1",
+ "FW_LAUNCH_STATE_IDLE_MOTOR_DELAY": "2",
+ "FW_LAUNCH_STATE_MOTOR_IDLE": "3",
+ "FW_LAUNCH_STATE_WAIT_DETECTION": "4",
+ "FW_LAUNCH_STATE_DETECTED": "5",
+ "FW_LAUNCH_STATE_MOTOR_DELAY": "6",
+ "FW_LAUNCH_STATE_MOTOR_SPINUP": "7",
+ "FW_LAUNCH_STATE_IN_PROGRESS": "8",
+ "FW_LAUNCH_STATE_FINISH": "9",
+ "FW_LAUNCH_STATE_ABORTED": "10",
+ "FW_LAUNCH_STATE_FLYING": "11",
+ "FW_LAUNCH_STATE_COUNT": "12"
+ },
+ "flashPartitionType_e": {
+ "_source": "../../../src/main/drivers/flash.h",
+ "FLASH_PARTITION_TYPE_UNKNOWN": "0",
+ "FLASH_PARTITION_TYPE_PARTITION_TABLE": "1",
+ "FLASH_PARTITION_TYPE_FLASHFS": "2",
+ "FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT": "3",
+ "FLASH_PARTITION_TYPE_FIRMWARE": "4",
+ "FLASH_PARTITION_TYPE_CONFIG": "5",
+ "FLASH_PARTITION_TYPE_FULL_BACKUP": "6",
+ "FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META": "7",
+ "FLASH_PARTITION_TYPE_UPDATE_FIRMWARE": "8",
+ "FLASH_MAX_PARTITIONS": "9"
+ },
+ "flashType_e": {
+ "_source": "../../../src/main/drivers/flash.h",
+ "FLASH_TYPE_NOR": "0",
+ "FLASH_TYPE_NAND": "1"
+ },
+ "flight_dynamics_index_t": {
+ "_source": "../../../src/main/common/axis.h",
+ "FD_ROLL": "0",
+ "FD_PITCH": "1",
+ "FD_YAW": "2"
+ },
+ "flightModeFlags_e": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "ANGLE_MODE": "(1 << 0)",
+ "HORIZON_MODE": "(1 << 1)",
+ "HEADING_MODE": "(1 << 2)",
+ "NAV_ALTHOLD_MODE": "(1 << 3)",
+ "NAV_RTH_MODE": "(1 << 4)",
+ "NAV_POSHOLD_MODE": "(1 << 5)",
+ "HEADFREE_MODE": "(1 << 6)",
+ "NAV_LAUNCH_MODE": "(1 << 7)",
+ "MANUAL_MODE": "(1 << 8)",
+ "FAILSAFE_MODE": "(1 << 9)",
+ "AUTO_TUNE": "(1 << 10)",
+ "NAV_WP_MODE": "(1 << 11)",
+ "NAV_COURSE_HOLD_MODE": "(1 << 12)",
+ "FLAPERON": "(1 << 13)",
+ "TURN_ASSISTANT": "(1 << 14)",
+ "TURTLE_MODE": "(1 << 15)",
+ "SOARING_MODE": "(1 << 16)",
+ "ANGLEHOLD_MODE": "(1 << 17)",
+ "NAV_FW_AUTOLAND": "(1 << 18)",
+ "NAV_SEND_TO": "(1 << 19)"
+ },
+ "flightModeForTelemetry_e": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "FLM_MANUAL": "0",
+ "FLM_ACRO": "1",
+ "FLM_ACRO_AIR": "2",
+ "FLM_ANGLE": "3",
+ "FLM_HORIZON": "4",
+ "FLM_ALTITUDE_HOLD": "5",
+ "FLM_POSITION_HOLD": "6",
+ "FLM_RTH": "7",
+ "FLM_MISSION": "8",
+ "FLM_COURSE_HOLD": "9",
+ "FLM_CRUISE": "10",
+ "FLM_LAUNCH": "11",
+ "FLM_FAILSAFE": "12",
+ "FLM_ANGLEHOLD": "13",
+ "FLM_COUNT": "14"
+ },
+ "flyingPlatformType_e": {
+ "_source": "../../../src/main/flight/mixer.h",
+ "PLATFORM_MULTIROTOR": "0",
+ "PLATFORM_AIRPLANE": "1",
+ "PLATFORM_HELICOPTER": "2",
+ "PLATFORM_TRICOPTER": "3",
+ "PLATFORM_ROVER": "4",
+ "PLATFORM_BOAT": "5"
+ },
+ "fport2_control_frame_type_e": {
+ "_source": "../../../src/main/rx/fport2.c",
+ "CFT_RC": "255",
+ "CFT_OTA_START": "240",
+ "CFT_OTA_DATA": "241",
+ "CFT_OTA_STOP": "242"
+ },
+ "frame_state_e": {
+ "_source": "../../../src/main/rx/fport2.c",
+ "FS_CONTROL_FRAME_START": "0",
+ "FS_CONTROL_FRAME_TYPE": "1",
+ "FS_CONTROL_FRAME_DATA": "2",
+ "FS_DOWNLINK_FRAME_START": "3",
+ "FS_DOWNLINK_FRAME_DATA": "4"
+ },
+ "frame_type_e": {
+ "_source": "../../../src/main/rx/fport2.c",
+ "FT_CONTROL": "0",
+ "FT_DOWNLINK": "1"
+ },
+ "frskyOSDColor_e": {
+ "_source": "../../../src/main/io/frsky_osd.h",
+ "FRSKY_OSD_COLOR_BLACK": "0",
+ "FRSKY_OSD_COLOR_TRANSPARENT": "1",
+ "FRSKY_OSD_COLOR_WHITE": "2",
+ "FRSKY_OSD_COLOR_GRAY": "3"
+ },
+ "frskyOSDLineOutlineType_e": {
+ "_source": "../../../src/main/io/frsky_osd.h",
+ "FRSKY_OSD_OUTLINE_TYPE_NONE": "0",
+ "FRSKY_OSD_OUTLINE_TYPE_TOP": "1 << 0",
+ "FRSKY_OSD_OUTLINE_TYPE_RIGHT": "1 << 1",
+ "FRSKY_OSD_OUTLINE_TYPE_BOTTOM": "1 << 2",
+ "FRSKY_OSD_OUTLINE_TYPE_LEFT": "1 << 3"
+ },
+ "frskyOSDRecvState_e": {
+ "_source": "../../../src/main/io/frsky_osd.c",
+ "RECV_STATE_NONE": "0",
+ "RECV_STATE_SYNC": "1",
+ "RECV_STATE_LENGTH": "2",
+ "RECV_STATE_DATA": "3",
+ "RECV_STATE_CHECKSUM": "4",
+ "RECV_STATE_DONE": "5"
+ },
+ "frskyOSDTransactionOptions_e": {
+ "_source": "../../../src/main/io/frsky_osd.h",
+ "FRSKY_OSD_TRANSACTION_OPT_PROFILED": "1 << 0",
+ "FRSKY_OSD_TRANSACTION_OPT_RESET_DRAWING": "1 << 1"
+ },
+ "fw_autotune_rate_adjustment_e": {
+ "_source": "../../../src/main/flight/pid.h",
+ "FIXED": "0",
+ "LIMIT": "1",
+ "AUTO": "2"
+ },
+ "fwAutolandApproachDirection_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "FW_AUTOLAND_APPROACH_DIRECTION_LEFT": "0",
+ "FW_AUTOLAND_APPROACH_DIRECTION_RIGHT": "1"
+ },
+ "fwAutolandState_t": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "FW_AUTOLAND_STATE_IDLE": "0",
+ "FW_AUTOLAND_STATE_LOITER": "1",
+ "FW_AUTOLAND_STATE_DOWNWIND": "2",
+ "FW_AUTOLAND_STATE_BASE_LEG": "3",
+ "FW_AUTOLAND_STATE_FINAL_APPROACH": "4",
+ "FW_AUTOLAND_STATE_GLIDE": "5",
+ "FW_AUTOLAND_STATE_FLARE": "6"
+ },
+ "fwAutolandWaypoint_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "FW_AUTOLAND_WP_TURN": "0",
+ "FW_AUTOLAND_WP_FINAL_APPROACH": "1",
+ "FW_AUTOLAND_WP_LAND": "2",
+ "FW_AUTOLAND_WP_COUNT": "3"
+ },
+ "geoAltitudeConversionMode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "GEO_ALT_ABSOLUTE": "0",
+ "GEO_ALT_RELATIVE": "1"
+ },
+ "geoAltitudeDatumFlag_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_TAKEOFF_DATUM": "0",
+ "NAV_WP_MSL_DATUM": "1",
+ "NAV_WP_TERRAIN_DATUM": "2"
+ },
+ "geoOriginResetMode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "GEO_ORIGIN_SET": "0",
+ "GEO_ORIGIN_RESET_ALTITUDE": "1"
+ },
+ "geozoneActionState_e": {
+ "_source": "../../../src/main/navigation/navigation_geozone.c",
+ "GEOZONE_ACTION_STATE_NONE": "0",
+ "GEOZONE_ACTION_STATE_AVOIDING": "1",
+ "GEOZONE_ACTION_STATE_AVOIDING_UPWARD": "2",
+ "GEOZONE_ACTION_STATE_AVOIDING_ALTITUDE": "3",
+ "GEOZONE_ACTION_STATE_RETURN_TO_FZ": "4",
+ "GEOZONE_ACTION_STATE_FLYOUT_NFZ": "5",
+ "GEOZONE_ACTION_STATE_POSHOLD": "6",
+ "GEOZONE_ACTION_STATE_RTH": "7"
+ },
+ "geozoneMessageState_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "GEOZONE_MESSAGE_STATE_NONE": "0",
+ "GEOZONE_MESSAGE_STATE_NFZ": "1",
+ "GEOZONE_MESSAGE_STATE_LEAVING_FZ": "2",
+ "GEOZONE_MESSAGE_STATE_OUTSIDE_FZ": "3",
+ "GEOZONE_MESSAGE_STATE_ENTERING_NFZ": "4",
+ "GEOZONE_MESSAGE_STATE_AVOIDING_FB": "5",
+ "GEOZONE_MESSAGE_STATE_RETURN_TO_ZONE": "6",
+ "GEOZONE_MESSAGE_STATE_FLYOUT_NFZ": "7",
+ "GEOZONE_MESSAGE_STATE_AVOIDING_ALTITUDE_BREACH": "8",
+ "GEOZONE_MESSAGE_STATE_POS_HOLD": "9"
+ },
+ "ghstAddr_e": {
+ "_source": "../../../src/main/rx/ghst_protocol.h",
+ "GHST_ADDR_RADIO": "128",
+ "GHST_ADDR_TX_MODULE_SYM": "129",
+ "GHST_ADDR_TX_MODULE_ASYM": "136",
+ "GHST_ADDR_FC": "130",
+ "GHST_ADDR_GOGGLES": "131",
+ "GHST_ADDR_QUANTUM_TEE1": "132",
+ "GHST_ADDR_QUANTUM_TEE2": "133",
+ "GHST_ADDR_QUANTUM_GW1": "134",
+ "GHST_ADDR_5G_CLK": "135",
+ "GHST_ADDR_RX": "137"
+ },
+ "ghstDl_e": {
+ "_source": "../../../src/main/rx/ghst_protocol.h",
+ "GHST_DL_OPENTX_SYNC": "32",
+ "GHST_DL_LINK_STAT": "33",
+ "GHST_DL_VTX_STAT": "34",
+ "GHST_DL_PACK_STAT": "35",
+ "GHST_DL_GPS_PRIMARY": "37",
+ "GHST_DL_GPS_SECONDARY": "38"
+ },
+ "ghstFrameTypeIndex_e": {
+ "_source": "../../../src/main/telemetry/ghst.c",
+ "GHST_FRAME_START_INDEX": "0",
+ "GHST_FRAME_PACK_INDEX": "GHST_FRAME_START_INDEX",
+ "GHST_FRAME_GPS_PRIMARY_INDEX": "",
+ "GHST_FRAME_GPS_SECONDARY_INDEX": "",
+ "GHST_SCHEDULE_COUNT_MAX": ""
+ },
+ "ghstUl_e": {
+ "_source": "../../../src/main/rx/ghst_protocol.h",
+ "GHST_UL_RC_CHANS_HS4_FIRST": "16",
+ "GHST_UL_RC_CHANS_HS4_5TO8": "16",
+ "GHST_UL_RC_CHANS_HS4_9TO12": "17",
+ "GHST_UL_RC_CHANS_HS4_13TO16": "18",
+ "GHST_UL_RC_CHANS_HS4_RSSI": "19",
+ "GHST_UL_RC_CHANS_HS4_LAST": "31"
+ },
+ "gimbal_htk_mode_e": {
+ "_source": "../../../src/main/drivers/gimbal_common.h",
+ "GIMBAL_MODE_FOLLOW": "0",
+ "GIMBAL_MODE_TILT_LOCK": "(1<<0)",
+ "GIMBAL_MODE_ROLL_LOCK": "(1<<1)",
+ "GIMBAL_MODE_PAN_LOCK": "(1<<2)"
+ },
+ "gimbalDevType_e": {
+ "_source": "../../../src/main/drivers/gimbal_common.h",
+ "GIMBAL_DEV_UNSUPPORTED": "0",
+ "GIMBAL_DEV_SERIAL": "1",
+ "GIMBAL_DEV_UNKNOWN": "255"
+ },
+ "gimbalHeadtrackerState_e": {
+ "_source": "../../../src/main/io/gimbal_serial.h",
+ "WAITING_HDR1": "0",
+ "WAITING_HDR2": "1",
+ "WAITING_PAYLOAD": "2",
+ "WAITING_CRCH": "3",
+ "WAITING_CRCL": "4"
+ },
+ "gpsAutoBaud_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_AUTOBAUD_OFF": "0",
+ "GPS_AUTOBAUD_ON": "1"
+ },
+ "gpsAutoConfig_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_AUTOCONFIG_OFF": "0",
+ "GPS_AUTOCONFIG_ON": "1"
+ },
+ "gpsBaudRate_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_BAUDRATE_115200": "0",
+ "GPS_BAUDRATE_57600": "1",
+ "GPS_BAUDRATE_38400": "2",
+ "GPS_BAUDRATE_19200": "3",
+ "GPS_BAUDRATE_9600": "4",
+ "GPS_BAUDRATE_230400": "5",
+ "GPS_BAUDRATE_460800": "6",
+ "GPS_BAUDRATE_921600": "7",
+ "GPS_BAUDRATE_COUNT": "8"
+ },
+ "gpsDynModel_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_DYNMODEL_PEDESTRIAN": "0",
+ "GPS_DYNMODEL_AUTOMOTIVE": "1",
+ "GPS_DYNMODEL_AIR_1G": "2",
+ "GPS_DYNMODEL_AIR_2G": "3",
+ "GPS_DYNMODEL_AIR_4G": "4",
+ "GPS_DYNMODEL_SEA": "5",
+ "GPS_DYNMODEL_MOWER": "6"
+ },
+ "gpsFixChar_e": {
+ "_source": "../../../src/main/telemetry/hott.c",
+ "GPS_FIX_CHAR_NONE": "'-'",
+ "GPS_FIX_CHAR_2D": "'2'",
+ "GPS_FIX_CHAR_3D": "'3'",
+ "GPS_FIX_CHAR_DGPS": "'D'"
+ },
+ "gpsFixType_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_NO_FIX": "0",
+ "GPS_FIX_2D": "1",
+ "GPS_FIX_3D": "2"
+ },
+ "gpsProvider_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_UBLOX": "0",
+ "GPS_MSP": "1",
+ "GPS_FAKE": "2",
+ "GPS_PROVIDER_COUNT": "3"
+ },
+ "gpsState_e": {
+ "_source": "../../../src/main/io/gps_private.h",
+ "GPS_UNKNOWN": "0",
+ "GPS_INITIALIZING": "1",
+ "GPS_RUNNING": "2",
+ "GPS_LOST_COMMUNICATION": "3"
+ },
+ "gyroFilterMode_e": {
+ "_source": "../../../src/main/sensors/gyro.h",
+ "GYRO_FILTER_MODE_OFF": "0",
+ "GYRO_FILTER_MODE_STATIC": "1",
+ "GYRO_FILTER_MODE_DYNAMIC": "2",
+ "GYRO_FILTER_MODE_ADAPTIVE": "3"
+ },
+ "gyroHardwareLpf_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h",
+ "GYRO_HARDWARE_LPF_NORMAL": "0",
+ "GYRO_HARDWARE_LPF_OPTION_1": "1",
+ "GYRO_HARDWARE_LPF_OPTION_2": "2",
+ "GYRO_HARDWARE_LPF_EXPERIMENTAL": "3",
+ "GYRO_HARDWARE_LPF_COUNT": "4"
+ },
+ "gyroSensor_e": {
+ "_source": "../../../src/main/sensors/gyro.h",
+ "GYRO_NONE": "0",
+ "GYRO_AUTODETECT": "1",
+ "GYRO_MPU6000": "2",
+ "GYRO_MPU6500": "3",
+ "GYRO_MPU9250": "4",
+ "GYRO_BMI160": "5",
+ "GYRO_ICM20689": "6",
+ "GYRO_BMI088": "7",
+ "GYRO_ICM42605": "8",
+ "GYRO_BMI270": "9",
+ "GYRO_LSM6DXX": "10",
+ "GYRO_FAKE": "11"
+ },
+ "HardwareMotorTypes_e": {
+ "_source": "../../../src/main/drivers/pwm_esc_detect.h",
+ "MOTOR_UNKNOWN": "0",
+ "MOTOR_BRUSHED": "1",
+ "MOTOR_BRUSHLESS": "2"
+ },
+ "hardwareSensorStatus_e": {
+ "_source": "../../../src/main/sensors/diagnostics.h",
+ "HW_SENSOR_NONE": "0",
+ "HW_SENSOR_OK": "1",
+ "HW_SENSOR_UNAVAILABLE": "2",
+ "HW_SENSOR_UNHEALTHY": "3"
+ },
+ "headTrackerDevType_e": {
+ "_source": "../../../src/main/drivers/headtracker_common.h",
+ "HEADTRACKER_NONE": "0",
+ "HEADTRACKER_SERIAL": "1",
+ "HEADTRACKER_MSP": "2",
+ "HEADTRACKER_UNKNOWN": "255"
+ },
+ "hottEamAlarm1Flag_e": {
+ "_source": "../../../src/main/telemetry/hott.h",
+ "HOTT_EAM_ALARM1_FLAG_NONE": "0",
+ "HOTT_EAM_ALARM1_FLAG_MAH": "(1 << 0)",
+ "HOTT_EAM_ALARM1_FLAG_BATTERY_1": "(1 << 1)",
+ "HOTT_EAM_ALARM1_FLAG_BATTERY_2": "(1 << 2)",
+ "HOTT_EAM_ALARM1_FLAG_TEMPERATURE_1": "(1 << 3)",
+ "HOTT_EAM_ALARM1_FLAG_TEMPERATURE_2": "(1 << 4)",
+ "HOTT_EAM_ALARM1_FLAG_ALTITUDE": "(1 << 5)",
+ "HOTT_EAM_ALARM1_FLAG_CURRENT": "(1 << 6)",
+ "HOTT_EAM_ALARM1_FLAG_MAIN_VOLTAGE": "(1 << 7)"
+ },
+ "hottEamAlarm2Flag_e": {
+ "_source": "../../../src/main/telemetry/hott.h",
+ "HOTT_EAM_ALARM2_FLAG_NONE": "0",
+ "HOTT_EAM_ALARM2_FLAG_MS": "(1 << 0)",
+ "HOTT_EAM_ALARM2_FLAG_M3S": "(1 << 1)",
+ "HOTT_EAM_ALARM2_FLAG_ALTITUDE_DUPLICATE": "(1 << 2)",
+ "HOTT_EAM_ALARM2_FLAG_MS_DUPLICATE": "(1 << 3)",
+ "HOTT_EAM_ALARM2_FLAG_M3S_DUPLICATE": "(1 << 4)",
+ "HOTT_EAM_ALARM2_FLAG_UNKNOWN_1": "(1 << 5)",
+ "HOTT_EAM_ALARM2_FLAG_UNKNOWN_2": "(1 << 6)",
+ "HOTT_EAM_ALARM2_FLAG_ON_SIGN_OR_TEXT_ACTIVE": "(1 << 7)"
+ },
+ "hottState_e": {
+ "_source": "../../../src/main/telemetry/hott.c",
+ "HOTT_WAITING_FOR_REQUEST": "0",
+ "HOTT_RECEIVING_REQUEST": "1",
+ "HOTT_WAITING_FOR_TX_WINDOW": "2",
+ "HOTT_TRANSMITTING": "3",
+ "HOTT_ENDING_TRANSMISSION": "4"
+ },
+ "hsvColorComponent_e": {
+ "_source": "../../../src/main/common/color.h",
+ "HSV_HUE": "0",
+ "HSV_SATURATION": "1",
+ "HSV_VALUE": "2"
+ },
+ "I2CSpeed": {
+ "_source": "../../../src/main/drivers/bus_i2c.h",
+ "I2C_SPEED_100KHZ": "2",
+ "I2C_SPEED_200KHZ": "3",
+ "I2C_SPEED_400KHZ": "0",
+ "I2C_SPEED_800KHZ": "1"
+ },
+ "i2cState_t": {
+ "_source": "../../../src/main/drivers/bus_i2c_stm32f40x.c",
+ "I2C_STATE_STOPPED": "0",
+ "I2C_STATE_STOPPING": "1",
+ "I2C_STATE_STARTING": "2",
+ "I2C_STATE_STARTING_WAIT": "3",
+ "I2C_STATE_R_ADDR": "4",
+ "I2C_STATE_R_ADDR_WAIT": "5",
+ "I2C_STATE_R_REGISTER": "6",
+ "I2C_STATE_R_REGISTER_WAIT": "7",
+ "I2C_STATE_R_RESTARTING": "8",
+ "I2C_STATE_R_RESTARTING_WAIT": "9",
+ "I2C_STATE_R_RESTART_ADDR": "10",
+ "I2C_STATE_R_RESTART_ADDR_WAIT": "11",
+ "I2C_STATE_R_TRANSFER_EQ1": "12",
+ "I2C_STATE_R_TRANSFER_EQ2": "13",
+ "I2C_STATE_R_TRANSFER_GE2": "14",
+ "I2C_STATE_W_ADDR": "15",
+ "I2C_STATE_W_ADDR_WAIT": "16",
+ "I2C_STATE_W_REGISTER": "17",
+ "I2C_STATE_W_TRANSFER_WAIT": "18",
+ "I2C_STATE_W_TRANSFER": "19",
+ "I2C_STATE_NACK": "20",
+ "I2C_STATE_BUS_ERROR": "21"
+ },
+ "i2cTransferDirection_t": {
+ "_source": "../../../src/main/drivers/bus_i2c_stm32f40x.c",
+ "I2C_TXN_READ": "0",
+ "I2C_TXN_WRITE": "1"
+ },
+ "ibusCommand_e": {
+ "_source": "../../../src/main/telemetry/ibus_shared.c",
+ "IBUS_COMMAND_DISCOVER_SENSOR": "128",
+ "IBUS_COMMAND_SENSOR_TYPE": "144",
+ "IBUS_COMMAND_MEASUREMENT": "160"
+ },
+ "ibusSensorType1_e": {
+ "_source": "../../../src/main/telemetry/ibus_shared.h",
+ "IBUS_MEAS_TYPE1_INTV": "0",
+ "IBUS_MEAS_TYPE1_TEM": "1",
+ "IBUS_MEAS_TYPE1_MOT": "2",
+ "IBUS_MEAS_TYPE1_EXTV": "3",
+ "IBUS_MEAS_TYPE1_CELL": "4",
+ "IBUS_MEAS_TYPE1_BAT_CURR": "5",
+ "IBUS_MEAS_TYPE1_FUEL": "6",
+ "IBUS_MEAS_TYPE1_RPM": "7",
+ "IBUS_MEAS_TYPE1_CMP_HEAD": "8",
+ "IBUS_MEAS_TYPE1_CLIMB_RATE": "9",
+ "IBUS_MEAS_TYPE1_COG": "10",
+ "IBUS_MEAS_TYPE1_GPS_STATUS": "11",
+ "IBUS_MEAS_TYPE1_ACC_X": "12",
+ "IBUS_MEAS_TYPE1_ACC_Y": "13",
+ "IBUS_MEAS_TYPE1_ACC_Z": "14",
+ "IBUS_MEAS_TYPE1_ROLL": "15",
+ "IBUS_MEAS_TYPE1_PITCH": "16",
+ "IBUS_MEAS_TYPE1_YAW": "17",
+ "IBUS_MEAS_TYPE1_VERTICAL_SPEED": "18",
+ "IBUS_MEAS_TYPE1_GROUND_SPEED": "19",
+ "IBUS_MEAS_TYPE1_GPS_DIST": "20",
+ "IBUS_MEAS_TYPE1_ARMED": "21",
+ "IBUS_MEAS_TYPE1_FLIGHT_MODE": "22",
+ "IBUS_MEAS_TYPE1_PRES": "65",
+ "IBUS_MEAS_TYPE1_SPE": "126",
+ "IBUS_MEAS_TYPE1_GPS_LAT": "128",
+ "IBUS_MEAS_TYPE1_GPS_LON": "129",
+ "IBUS_MEAS_TYPE1_GPS_ALT": "130",
+ "IBUS_MEAS_TYPE1_ALT": "131",
+ "IBUS_MEAS_TYPE1_S84": "132",
+ "IBUS_MEAS_TYPE1_S85": "133",
+ "IBUS_MEAS_TYPE1_S86": "134",
+ "IBUS_MEAS_TYPE1_S87": "135",
+ "IBUS_MEAS_TYPE1_S88": "136",
+ "IBUS_MEAS_TYPE1_S89": "137",
+ "IBUS_MEAS_TYPE1_S8a": "138"
+ },
+ "ibusSensorType_e": {
+ "_source": "../../../src/main/telemetry/ibus_shared.h",
+ "IBUS_MEAS_TYPE_INTERNAL_VOLTAGE": "0",
+ "IBUS_MEAS_TYPE_TEMPERATURE": "1",
+ "IBUS_MEAS_TYPE_RPM": "2",
+ "IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE": "3",
+ "IBUS_MEAS_TYPE_HEADING": "4",
+ "IBUS_MEAS_TYPE_CURRENT": "5",
+ "IBUS_MEAS_TYPE_CLIMB": "6",
+ "IBUS_MEAS_TYPE_ACC_Z": "7",
+ "IBUS_MEAS_TYPE_ACC_Y": "8",
+ "IBUS_MEAS_TYPE_ACC_X": "9",
+ "IBUS_MEAS_TYPE_VSPEED": "10",
+ "IBUS_MEAS_TYPE_SPEED": "11",
+ "IBUS_MEAS_TYPE_DIST": "12",
+ "IBUS_MEAS_TYPE_ARMED": "13",
+ "IBUS_MEAS_TYPE_MODE": "14",
+ "IBUS_MEAS_TYPE_PRES": "65",
+ "IBUS_MEAS_TYPE_SPE": "126",
+ "IBUS_MEAS_TYPE_COG": "128",
+ "IBUS_MEAS_TYPE_GPS_STATUS": "129",
+ "IBUS_MEAS_TYPE_GPS_LON": "130",
+ "IBUS_MEAS_TYPE_GPS_LAT": "131",
+ "IBUS_MEAS_TYPE_ALT": "132",
+ "IBUS_MEAS_TYPE_S85": "133",
+ "IBUS_MEAS_TYPE_S86": "134",
+ "IBUS_MEAS_TYPE_S87": "135",
+ "IBUS_MEAS_TYPE_S88": "136",
+ "IBUS_MEAS_TYPE_S89": "137",
+ "IBUS_MEAS_TYPE_S8A": "138",
+ "IBUS_MEAS_TYPE_GALT": "249",
+ "IBUS_MEAS_TYPE_GPS": "253"
+ },
+ "ibusSensorValue_e": {
+ "_source": "../../../src/main/telemetry/ibus_shared.h",
+ "IBUS_MEAS_VALUE_NONE": "0",
+ "IBUS_MEAS_VALUE_TEMPERATURE": "1",
+ "IBUS_MEAS_VALUE_MOT": "2",
+ "IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE": "3",
+ "IBUS_MEAS_VALUE_CELL": "4",
+ "IBUS_MEAS_VALUE_CURRENT": "5",
+ "IBUS_MEAS_VALUE_FUEL": "6",
+ "IBUS_MEAS_VALUE_RPM": "7",
+ "IBUS_MEAS_VALUE_HEADING": "8",
+ "IBUS_MEAS_VALUE_CLIMB": "9",
+ "IBUS_MEAS_VALUE_COG": "10",
+ "IBUS_MEAS_VALUE_GPS_STATUS": "11",
+ "IBUS_MEAS_VALUE_ACC_X": "12",
+ "IBUS_MEAS_VALUE_ACC_Y": "13",
+ "IBUS_MEAS_VALUE_ACC_Z": "14",
+ "IBUS_MEAS_VALUE_ROLL": "15",
+ "IBUS_MEAS_VALUE_PITCH": "16",
+ "IBUS_MEAS_VALUE_YAW": "17",
+ "IBUS_MEAS_VALUE_VSPEED": "18",
+ "IBUS_MEAS_VALUE_SPEED": "19",
+ "IBUS_MEAS_VALUE_DIST": "20",
+ "IBUS_MEAS_VALUE_ARMED": "21",
+ "IBUS_MEAS_VALUE_MODE": "22",
+ "IBUS_MEAS_VALUE_PRES": "65",
+ "IBUS_MEAS_VALUE_SPE": "126",
+ "IBUS_MEAS_VALUE_GPS_LAT": "128",
+ "IBUS_MEAS_VALUE_GPS_LON": "129",
+ "IBUS_MEAS_VALUE_GALT4": "130",
+ "IBUS_MEAS_VALUE_ALT4": "131",
+ "IBUS_MEAS_VALUE_GALT": "132",
+ "IBUS_MEAS_VALUE_ALT": "133",
+ "IBUS_MEAS_VALUE_STATUS": "135",
+ "IBUS_MEAS_VALUE_GPS_LAT1": "136",
+ "IBUS_MEAS_VALUE_GPS_LON1": "137",
+ "IBUS_MEAS_VALUE_GPS_LAT2": "144",
+ "IBUS_MEAS_VALUE_GPS_LON2": "145",
+ "IBUS_MEAS_VALUE_GPS": "253"
+ },
+ "inputSource_e": {
+ "_source": "../../../src/main/flight/servos.h",
+ "INPUT_STABILIZED_ROLL": "0",
+ "INPUT_STABILIZED_PITCH": "1",
+ "INPUT_STABILIZED_YAW": "2",
+ "INPUT_STABILIZED_THROTTLE": "3",
+ "INPUT_RC_ROLL": "4",
+ "INPUT_RC_PITCH": "5",
+ "INPUT_RC_YAW": "6",
+ "INPUT_RC_THROTTLE": "7",
+ "INPUT_RC_CH5": "8",
+ "INPUT_RC_CH6": "9",
+ "INPUT_RC_CH7": "10",
+ "INPUT_RC_CH8": "11",
+ "INPUT_GIMBAL_PITCH": "12",
+ "INPUT_GIMBAL_ROLL": "13",
+ "INPUT_FEATURE_FLAPS": "14",
+ "INPUT_RC_CH9": "15",
+ "INPUT_RC_CH10": "16",
+ "INPUT_RC_CH11": "17",
+ "INPUT_RC_CH12": "18",
+ "INPUT_RC_CH13": "19",
+ "INPUT_RC_CH14": "20",
+ "INPUT_RC_CH15": "21",
+ "INPUT_RC_CH16": "22",
+ "INPUT_STABILIZED_ROLL_PLUS": "23",
+ "INPUT_STABILIZED_ROLL_MINUS": "24",
+ "INPUT_STABILIZED_PITCH_PLUS": "25",
+ "INPUT_STABILIZED_PITCH_MINUS": "26",
+ "INPUT_STABILIZED_YAW_PLUS": "27",
+ "INPUT_STABILIZED_YAW_MINUS": "28",
+ "INPUT_MAX": "29",
+ "INPUT_GVAR_0": "30",
+ "INPUT_GVAR_1": "31",
+ "INPUT_GVAR_2": "32",
+ "INPUT_GVAR_3": "33",
+ "INPUT_GVAR_4": "34",
+ "INPUT_GVAR_5": "35",
+ "INPUT_GVAR_6": "36",
+ "INPUT_GVAR_7": "37",
+ "INPUT_MIXER_TRANSITION": "38",
+ "INPUT_HEADTRACKER_PAN": "39",
+ "INPUT_HEADTRACKER_TILT": "40",
+ "INPUT_HEADTRACKER_ROLL": "41",
+ "INPUT_RC_CH17": "42",
+ "INPUT_RC_CH18": "43",
+ "INPUT_RC_CH19": "44",
+ "INPUT_RC_CH20": "45",
+ "INPUT_RC_CH21": "46",
+ "INPUT_RC_CH22": "47",
+ "INPUT_RC_CH23": "48",
+ "INPUT_RC_CH24": "49",
+ "INPUT_RC_CH25": "50",
+ "INPUT_RC_CH26": "51",
+ "INPUT_RC_CH27": "52",
+ "INPUT_RC_CH28": "53",
+ "INPUT_RC_CH29": "54",
+ "INPUT_RC_CH30": "55",
+ "INPUT_RC_CH31": "56",
+ "INPUT_RC_CH32": "57",
+ "INPUT_RC_CH33": "58",
+ "INPUT_RC_CH34": "59",
+ "INPUT_MIXER_SWITCH_HELPER": "60",
+ "INPUT_SOURCE_COUNT": "61"
+ },
+ "itermRelax_e": {
+ "_source": "../../../src/main/flight/pid.h",
+ "ITERM_RELAX_OFF": "0",
+ "ITERM_RELAX_RP": "1",
+ "ITERM_RELAX_RPY": "2"
+ },
+ "led_pin_pwm_mode_e": {
+ "_source": "../../../src/main/drivers/light_ws2811strip.h",
+ "LED_PIN_PWM_MODE_SHARED_LOW": "0",
+ "LED_PIN_PWM_MODE_SHARED_HIGH": "1",
+ "LED_PIN_PWM_MODE_LOW": "2",
+ "LED_PIN_PWM_MODE_HIGH": "3"
+ },
+ "ledBaseFunctionId_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_FUNCTION_COLOR": "0",
+ "LED_FUNCTION_FLIGHT_MODE": "1",
+ "LED_FUNCTION_ARM_STATE": "2",
+ "LED_FUNCTION_BATTERY": "3",
+ "LED_FUNCTION_RSSI": "4",
+ "LED_FUNCTION_GPS": "5",
+ "LED_FUNCTION_THRUST_RING": "6",
+ "LED_FUNCTION_CHANNEL": "7"
+ },
+ "ledDirectionId_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_DIRECTION_NORTH": "0",
+ "LED_DIRECTION_EAST": "1",
+ "LED_DIRECTION_SOUTH": "2",
+ "LED_DIRECTION_WEST": "3",
+ "LED_DIRECTION_UP": "4",
+ "LED_DIRECTION_DOWN": "5"
+ },
+ "ledModeIndex_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_MODE_ORIENTATION": "0",
+ "LED_MODE_HEADFREE": "1",
+ "LED_MODE_HORIZON": "2",
+ "LED_MODE_ANGLE": "3",
+ "LED_MODE_MAG": "4",
+ "LED_MODE_BARO": "5",
+ "LED_SPECIAL": "6"
+ },
+ "ledOverlayId_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_OVERLAY_THROTTLE": "0",
+ "LED_OVERLAY_LARSON_SCANNER": "1",
+ "LED_OVERLAY_BLINK": "2",
+ "LED_OVERLAY_LANDING_FLASH": "3",
+ "LED_OVERLAY_INDICATOR": "4",
+ "LED_OVERLAY_WARNING": "5",
+ "LED_OVERLAY_STROBE": "6"
+ },
+ "ledSpecialColorIds_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_SCOLOR_DISARMED": "0",
+ "LED_SCOLOR_ARMED": "1",
+ "LED_SCOLOR_ANIMATION": "2",
+ "LED_SCOLOR_BACKGROUND": "3",
+ "LED_SCOLOR_BLINKBACKGROUND": "4",
+ "LED_SCOLOR_GPSNOSATS": "5",
+ "LED_SCOLOR_GPSNOLOCK": "6",
+ "LED_SCOLOR_GPSLOCKED": "7",
+ "LED_SCOLOR_STROBE": "8"
+ },
+ "logicConditionFlags_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_FLAG_LATCH": "1 << 0",
+ "LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED": "1 << 1"
+ },
+ "logicConditionsGlobalFlags_t": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY": "(1 << 0)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE": "(1 << 1)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW": "(1 << 2)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL": "(1 << 3)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH": "(1 << 4)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW": "(1 << 5)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE": "(1 << 6)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT": "(1 << 7)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_RC_CHANNEL": "(1 << 8)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS": "(1 << 9)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_FLIGHT_AXIS": "(1 << 10)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_DISABLE_GPS_FIX": [
+ "(1 << 11)",
+ "USE_GPS_FIX_ESTIMATION"
+ ],
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_MIN_GROUND_SPEED": "(1 << 12)"
+ },
+ "logicFlightModeOperands_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_FAILSAFE": "0",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_MANUAL": "1",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_RTH": "2",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_POSHOLD": "3",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_CRUISE": "4",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ALTHOLD": "5",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLE": "6",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_HORIZON": "7",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR": "8",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1": "9",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER2": "10",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD": "11",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER3": "12",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4": "13",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO": "14",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION": "15",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLEHOLD": "16"
+ },
+ "logicFlightOperands_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER": "0",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE": "1",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE": "2",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_RSSI": "3",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_VBAT": "4",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_CELL_VOLTAGE": "5",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_CURRENT": "6",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MAH_DRAWN": "7",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_GPS_SATS": "8",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_GROUD_SPEED": "9",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_3D_SPEED": "10",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED": "11",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ALTITUDE": "12",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_VERTICAL_SPEED": "13",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_TROTTLE_POS": "14",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_ROLL": "15",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_PITCH": "16",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_ARMED": "17",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_AUTOLAUNCH": "18",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_ALTITUDE_CONTROL": "19",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_POSITION_CONTROL": "20",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_EMERGENCY_LANDING": "21",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_RTH": "22",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING": "23",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_FAILSAFE": "24",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL": "25",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH": "26",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW": "27",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_3D_HOME_DISTANCE": "28",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_LQ_UPLINK": "29",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_SNR": "30",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID": "31",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS": "32",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_PROFILE": "33",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_BATT_CELLS": "34",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS": "35",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_AGL": "36",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW": "37",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE": "38",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE": "39",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW": "40",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_FW_LAND_STATE": "41",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE": "42",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_FLOWN_LOITER_RADIUS": "43",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_LQ_DOWNLINK": "44",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_UPLINK_RSSI_DBM": "45",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MIN_GROUND_SPEED": "46",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_HORIZONTAL_WIND_SPEED": "47",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION": "48",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET": "49"
+ },
+ "logicOperation_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_TRUE": "0",
+ "LOGIC_CONDITION_EQUAL": "1",
+ "LOGIC_CONDITION_GREATER_THAN": "2",
+ "LOGIC_CONDITION_LOWER_THAN": "3",
+ "LOGIC_CONDITION_LOW": "4",
+ "LOGIC_CONDITION_MID": "5",
+ "LOGIC_CONDITION_HIGH": "6",
+ "LOGIC_CONDITION_AND": "7",
+ "LOGIC_CONDITION_OR": "8",
+ "LOGIC_CONDITION_XOR": "9",
+ "LOGIC_CONDITION_NAND": "10",
+ "LOGIC_CONDITION_NOR": "11",
+ "LOGIC_CONDITION_NOT": "12",
+ "LOGIC_CONDITION_STICKY": "13",
+ "LOGIC_CONDITION_ADD": "14",
+ "LOGIC_CONDITION_SUB": "15",
+ "LOGIC_CONDITION_MUL": "16",
+ "LOGIC_CONDITION_DIV": "17",
+ "LOGIC_CONDITION_GVAR_SET": "18",
+ "LOGIC_CONDITION_GVAR_INC": "19",
+ "LOGIC_CONDITION_GVAR_DEC": "20",
+ "LOGIC_CONDITION_PORT_SET": "21",
+ "LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY": "22",
+ "LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE": "23",
+ "LOGIC_CONDITION_SWAP_ROLL_YAW": "24",
+ "LOGIC_CONDITION_SET_VTX_POWER_LEVEL": "25",
+ "LOGIC_CONDITION_INVERT_ROLL": "26",
+ "LOGIC_CONDITION_INVERT_PITCH": "27",
+ "LOGIC_CONDITION_INVERT_YAW": "28",
+ "LOGIC_CONDITION_OVERRIDE_THROTTLE": "29",
+ "LOGIC_CONDITION_SET_VTX_BAND": "30",
+ "LOGIC_CONDITION_SET_VTX_CHANNEL": "31",
+ "LOGIC_CONDITION_SET_OSD_LAYOUT": "32",
+ "LOGIC_CONDITION_SIN": "33",
+ "LOGIC_CONDITION_COS": "34",
+ "LOGIC_CONDITION_TAN": "35",
+ "LOGIC_CONDITION_MAP_INPUT": "36",
+ "LOGIC_CONDITION_MAP_OUTPUT": "37",
+ "LOGIC_CONDITION_RC_CHANNEL_OVERRIDE": "38",
+ "LOGIC_CONDITION_SET_HEADING_TARGET": "39",
+ "LOGIC_CONDITION_MODULUS": "40",
+ "LOGIC_CONDITION_LOITER_OVERRIDE": "41",
+ "LOGIC_CONDITION_SET_PROFILE": "42",
+ "LOGIC_CONDITION_MIN": "43",
+ "LOGIC_CONDITION_MAX": "44",
+ "LOGIC_CONDITION_FLIGHT_AXIS_ANGLE_OVERRIDE": "45",
+ "LOGIC_CONDITION_FLIGHT_AXIS_RATE_OVERRIDE": "46",
+ "LOGIC_CONDITION_EDGE": "47",
+ "LOGIC_CONDITION_DELAY": "48",
+ "LOGIC_CONDITION_TIMER": "49",
+ "LOGIC_CONDITION_DELTA": "50",
+ "LOGIC_CONDITION_APPROX_EQUAL": "51",
+ "LOGIC_CONDITION_LED_PIN_PWM": "52",
+ "LOGIC_CONDITION_DISABLE_GPS_FIX": "53",
+ "LOGIC_CONDITION_RESET_MAG_CALIBRATION": "54",
+ "LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY": "55",
+ "LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED": "56",
+ "LOGIC_CONDITION_SET_ALTITUDE_TARGET": "57",
+ "LOGIC_CONDITION_LAST": "58"
+ },
+ "logicWaypointOperands_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_IS_WP": "0",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_INDEX": "1",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_ACTION": "2",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_NEXT_WAYPOINT_ACTION": "3",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_DISTANCE": "4",
+ "LOGIC_CONDTIION_OPERAND_WAYPOINTS_DISTANCE_FROM_WAYPOINT": "5",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION": "6",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION": "7",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION": "8",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION": "9",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION_NEXT_WP": "10",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION_NEXT_WP": "11",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION_NEXT_WP": "12",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION_NEXT_WP": "13"
+ },
+ "logTopic_e": {
+ "_source": "../../../src/main/common/log.h",
+ "LOG_TOPIC_SYSTEM": "0",
+ "LOG_TOPIC_GYRO": "1",
+ "LOG_TOPIC_BARO": "2",
+ "LOG_TOPIC_PITOT": "3",
+ "LOG_TOPIC_PWM": "4",
+ "LOG_TOPIC_TIMER": "5",
+ "LOG_TOPIC_IMU": "6",
+ "LOG_TOPIC_TEMPERATURE": "7",
+ "LOG_TOPIC_POS_ESTIMATOR": "8",
+ "LOG_TOPIC_VTX": "9",
+ "LOG_TOPIC_OSD": "10",
+ "LOG_TOPIC_COUNT": "11"
+ },
+ "lsm6dxxConfigMasks_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h",
+ "LSM6DXX_MASK_COUNTER_BDR1": "128",
+ "LSM6DXX_MASK_CTRL3_C": "60",
+ "LSM6DXX_MASK_CTRL3_C_RESET": "BIT(0)",
+ "LSM6DXX_MASK_CTRL4_C": "14",
+ "LSM6DXX_MASK_CTRL6_C": "23",
+ "LSM6DXX_MASK_CTRL7_G": "112",
+ "LSM6DXX_MASK_CTRL9_XL": "2",
+ "LSM6DSL_MASK_CTRL6_C": "19"
+ },
+ "lsm6dxxConfigValues_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h",
+ "LSM6DXX_VAL_COUNTER_BDR1_DDRY_PM": "BIT(7)",
+ "LSM6DXX_VAL_INT1_CTRL": "2",
+ "LSM6DXX_VAL_INT2_CTRL": "0",
+ "LSM6DXX_VAL_CTRL1_XL_ODR833": "7",
+ "LSM6DXX_VAL_CTRL1_XL_ODR1667": "8",
+ "LSM6DXX_VAL_CTRL1_XL_ODR3332": "9",
+ "LSM6DXX_VAL_CTRL1_XL_ODR3333": "10",
+ "LSM6DXX_VAL_CTRL1_XL_8G": "3",
+ "LSM6DXX_VAL_CTRL1_XL_16G": "1",
+ "LSM6DXX_VAL_CTRL1_XL_LPF1": "0",
+ "LSM6DXX_VAL_CTRL1_XL_LPF2": "1",
+ "LSM6DXX_VAL_CTRL2_G_ODR6664": "10",
+ "LSM6DXX_VAL_CTRL2_G_2000DPS": "3",
+ "LSM6DXX_VAL_CTRL3_C_H_LACTIVE": "0",
+ "LSM6DXX_VAL_CTRL3_C_PP_OD": "0",
+ "LSM6DXX_VAL_CTRL3_C_SIM": "0",
+ "LSM6DXX_VAL_CTRL3_C_IF_INC": "BIT(2)",
+ "LSM6DXX_VAL_CTRL4_C_DRDY_MASK": "BIT(3)",
+ "LSM6DXX_VAL_CTRL4_C_I2C_DISABLE": "BIT(2)",
+ "LSM6DXX_VAL_CTRL4_C_LPF1_SEL_G": "BIT(1)",
+ "LSM6DXX_VAL_CTRL6_C_XL_HM_MODE": "0",
+ "LSM6DXX_VAL_CTRL6_C_FTYPE_300HZ": "0",
+ "LSM6DXX_VAL_CTRL6_C_FTYPE_201HZ": "1",
+ "LSM6DXX_VAL_CTRL6_C_FTYPE_102HZ": "2",
+ "LSM6DXX_VAL_CTRL6_C_FTYPE_603HZ": "3",
+ "LSM6DXX_VAL_CTRL7_G_HP_EN_G": "BIT(6)",
+ "LSM6DXX_VAL_CTRL7_G_HPM_G_16": "0",
+ "LSM6DXX_VAL_CTRL7_G_HPM_G_65": "1",
+ "LSM6DXX_VAL_CTRL7_G_HPM_G_260": "2",
+ "LSM6DXX_VAL_CTRL7_G_HPM_G_1040": "3",
+ "LSM6DXX_VAL_CTRL9_XL_I3C_DISABLE": "BIT(1)"
+ },
+ "lsm6dxxRegister_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h",
+ "LSM6DXX_REG_COUNTER_BDR1": "11",
+ "LSM6DXX_REG_INT1_CTRL": "13",
+ "LSM6DXX_REG_INT2_CTRL": "14",
+ "LSM6DXX_REG_WHO_AM_I": "15",
+ "LSM6DXX_REG_CTRL1_XL": "16",
+ "LSM6DXX_REG_CTRL2_G": "17",
+ "LSM6DXX_REG_CTRL3_C": "18",
+ "LSM6DXX_REG_CTRL4_C": "19",
+ "LSM6DXX_REG_CTRL5_C": "20",
+ "LSM6DXX_REG_CTRL6_C": "21",
+ "LSM6DXX_REG_CTRL7_G": "22",
+ "LSM6DXX_REG_CTRL8_XL": "23",
+ "LSM6DXX_REG_CTRL9_XL": "24",
+ "LSM6DXX_REG_CTRL10_C": "25",
+ "LSM6DXX_REG_STATUS": "30",
+ "LSM6DXX_REG_OUT_TEMP_L": "32",
+ "LSM6DXX_REG_OUT_TEMP_H": "33",
+ "LSM6DXX_REG_OUTX_L_G": "34",
+ "LSM6DXX_REG_OUTX_H_G": "35",
+ "LSM6DXX_REG_OUTY_L_G": "36",
+ "LSM6DXX_REG_OUTY_H_G": "37",
+ "LSM6DXX_REG_OUTZ_L_G": "38",
+ "LSM6DXX_REG_OUTZ_H_G": "39",
+ "LSM6DXX_REG_OUTX_L_A": "40",
+ "LSM6DXX_REG_OUTX_H_A": "41",
+ "LSM6DXX_REG_OUTY_L_A": "42",
+ "LSM6DXX_REG_OUTY_H_A": "43",
+ "LSM6DXX_REG_OUTZ_L_A": "44",
+ "LSM6DXX_REG_OUTZ_H_A": "45"
+ },
+ "ltm_frame_e": {
+ "_source": "../../../src/main/telemetry/ltm.h",
+ "LTM_FRAME_START": "0",
+ "LTM_AFRAME": "LTM_FRAME_START",
+ "LTM_SFRAME": "",
+ "LTM_GFRAME": [
+ "",
+ "USE_GPS"
+ ],
+ "LTM_OFRAME": [
+ "",
+ "USE_GPS"
+ ],
+ "LTM_XFRAME": [
+ "",
+ "USE_GPS"
+ ],
+ "LTM_NFRAME": "",
+ "LTM_FRAME_COUNT": ""
+ },
+ "ltm_modes_e": {
+ "_source": "../../../src/main/telemetry/ltm.h",
+ "LTM_MODE_MANUAL": "0",
+ "LTM_MODE_RATE": "1",
+ "LTM_MODE_ANGLE": "2",
+ "LTM_MODE_HORIZON": "3",
+ "LTM_MODE_ACRO": "4",
+ "LTM_MODE_STABALIZED1": "5",
+ "LTM_MODE_STABALIZED2": "6",
+ "LTM_MODE_STABILIZED3": "7",
+ "LTM_MODE_ALTHOLD": "8",
+ "LTM_MODE_GPSHOLD": "9",
+ "LTM_MODE_WAYPOINTS": "10",
+ "LTM_MODE_HEADHOLD": "11",
+ "LTM_MODE_CIRCLE": "12",
+ "LTM_MODE_RTH": "13",
+ "LTM_MODE_FOLLOWWME": "14",
+ "LTM_MODE_LAND": "15",
+ "LTM_MODE_FLYBYWIRE1": "16",
+ "LTM_MODE_FLYBYWIRE2": "17",
+ "LTM_MODE_CRUISE": "18",
+ "LTM_MODE_UNKNOWN": "19",
+ "LTM_MODE_LAUNCH": "20",
+ "LTM_MODE_AUTOTUNE": "21"
+ },
+ "ltmUpdateRate_e": {
+ "_source": "../../../src/main/telemetry/telemetry.h",
+ "LTM_RATE_NORMAL": "0",
+ "LTM_RATE_MEDIUM": "1",
+ "LTM_RATE_SLOW": "2"
+ },
+ "magSensor_e": {
+ "_source": "../../../src/main/sensors/compass.h",
+ "MAG_NONE": "0",
+ "MAG_AUTODETECT": "1",
+ "MAG_HMC5883": "2",
+ "MAG_AK8975": "3",
+ "MAG_MAG3110": "4",
+ "MAG_AK8963": "5",
+ "MAG_IST8310": "6",
+ "MAG_QMC5883": "7",
+ "MAG_QMC5883P": "8",
+ "MAG_MPU9250": "9",
+ "MAG_IST8308": "10",
+ "MAG_LIS3MDL": "11",
+ "MAG_MSP": "12",
+ "MAG_RM3100": "13",
+ "MAG_VCM5883": "14",
+ "MAG_MLX90393": "15",
+ "MAG_FAKE": "16",
+ "MAG_MAX": "MAG_FAKE"
+ },
+ "mavlinkAutopilotType_e": {
+ "_source": "../../../src/main/telemetry/telemetry.h",
+ "MAVLINK_AUTOPILOT_GENERIC": "0",
+ "MAVLINK_AUTOPILOT_ARDUPILOT": "1"
+ },
+ "mavlinkRadio_e": {
+ "_source": "../../../src/main/telemetry/telemetry.h",
+ "MAVLINK_RADIO_GENERIC": "0",
+ "MAVLINK_RADIO_ELRS": "1",
+ "MAVLINK_RADIO_SIK": "2"
+ },
+ "measurementSteps_e": {
+ "_source": "../../../src/main/drivers/rangefinder/rangefinder_vl53l0x.c",
+ "MEASUREMENT_START": "0",
+ "MEASUREMENT_WAIT": "1",
+ "MEASUREMENT_READ": "2"
+ },
+ "mixerProfileATRequest_e": {
+ "_source": "../../../src/main/flight/mixer_profile.h",
+ "MIXERAT_REQUEST_NONE": "0",
+ "MIXERAT_REQUEST_RTH": "1",
+ "MIXERAT_REQUEST_LAND": "2",
+ "MIXERAT_REQUEST_ABORT": "3"
+ },
+ "mixerProfileATState_e": {
+ "_source": "../../../src/main/flight/mixer_profile.h",
+ "MIXERAT_PHASE_IDLE": "0",
+ "MIXERAT_PHASE_TRANSITION_INITIALIZE": "1",
+ "MIXERAT_PHASE_TRANSITIONING": "2",
+ "MIXERAT_PHASE_DONE": "3"
+ },
+ "modeActivationOperator_e": {
+ "_source": "../../../src/main/fc/rc_modes.h",
+ "MODE_OPERATOR_OR": "0",
+ "MODE_OPERATOR_AND": "1"
+ },
+ "motorPwmProtocolTypes_e": {
+ "_source": "../../../src/main/drivers/pwm_mapping.h",
+ "PWM_TYPE_STANDARD": "0",
+ "PWM_TYPE_ONESHOT125": "1",
+ "PWM_TYPE_MULTISHOT": "2",
+ "PWM_TYPE_BRUSHED": "3",
+ "PWM_TYPE_DSHOT150": "4",
+ "PWM_TYPE_DSHOT300": "5",
+ "PWM_TYPE_DSHOT600": "6"
+ },
+ "motorStatus_e": {
+ "_source": "../../../src/main/flight/mixer.h",
+ "MOTOR_STOPPED_USER": "0",
+ "MOTOR_STOPPED_AUTO": "1",
+ "MOTOR_RUNNING": "2"
+ },
+ "mpu9250CompassReadState_e": {
+ "_source": "../../../src/main/drivers/compass/compass_mpu9250.c",
+ "CHECK_STATUS": "0",
+ "WAITING_FOR_STATUS": "1",
+ "WAITING_FOR_DATA": "2"
+ },
+ "mspFlashfsFlags_e": {
+ "_source": "../../../src/main/fc/fc_msp.c",
+ "MSP_FLASHFS_BIT_READY": "1",
+ "MSP_FLASHFS_BIT_SUPPORTED": "2"
+ },
+ "mspPassthroughType_e": {
+ "_source": "../../../src/main/fc/fc_msp.c",
+ "MSP_PASSTHROUGH_SERIAL_ID": "253",
+ "MSP_PASSTHROUGH_SERIAL_FUNCTION_ID": "254",
+ "MSP_PASSTHROUGH_ESC_4WAY": "255"
+ },
+ "mspSDCardFlags_e": {
+ "_source": "../../../src/main/fc/fc_msp.c",
+ "MSP_SDCARD_FLAG_SUPPORTTED": "1"
+ },
+ "mspSDCardState_e": {
+ "_source": "../../../src/main/fc/fc_msp.c",
+ "MSP_SDCARD_STATE_NOT_PRESENT": "0",
+ "MSP_SDCARD_STATE_FATAL": "1",
+ "MSP_SDCARD_STATE_CARD_INIT": "2",
+ "MSP_SDCARD_STATE_FS_INIT": "3",
+ "MSP_SDCARD_STATE_READY": "4"
+ },
+ "multi_function_e": {
+ "_source": "../../../src/main/fc/multifunction.h",
+ "MULTI_FUNC_NONE": "0",
+ "MULTI_FUNC_1": "1",
+ "MULTI_FUNC_2": "2",
+ "MULTI_FUNC_3": "3",
+ "MULTI_FUNC_4": "4",
+ "MULTI_FUNC_5": "5",
+ "MULTI_FUNC_6": "6",
+ "MULTI_FUNC_END": "7"
+ },
+ "multiFunctionFlags_e": {
+ "_source": "../../../src/main/fc/multifunction.h",
+ "MF_SUSPEND_SAFEHOMES": "(1 << 0)",
+ "MF_SUSPEND_TRACKBACK": "(1 << 1)",
+ "MF_TURTLE_MODE": "(1 << 2)"
+ },
+ "nav_reset_type_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_RESET_NEVER": "0",
+ "NAV_RESET_ON_FIRST_ARM": "1",
+ "NAV_RESET_ON_EACH_ARM": "2"
+ },
+ "navAGLEstimateQuality_e": {
+ "_source": "../../../src/main/navigation/navigation_pos_estimator_private.h",
+ "SURFACE_QUAL_LOW": "0",
+ "SURFACE_QUAL_MID": "1",
+ "SURFACE_QUAL_HIGH": "2"
+ },
+ "navArmingBlocker_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_ARMING_BLOCKER_NONE": "0",
+ "NAV_ARMING_BLOCKER_MISSING_GPS_FIX": "1",
+ "NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE": "2",
+ "NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR": "3",
+ "NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR": "4"
+ },
+ "navDefaultAltitudeSensor_e": {
+ "_source": "../../../src/main/navigation/navigation_pos_estimator_private.h",
+ "ALTITUDE_SOURCE_GPS": "0",
+ "ALTITUDE_SOURCE_BARO": "1",
+ "ALTITUDE_SOURCE_GPS_ONLY": "2",
+ "ALTITUDE_SOURCE_BARO_ONLY": "3"
+ },
+ "navExtraArmingSafety_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_EXTRA_ARMING_SAFETY_ON": "0",
+ "NAV_EXTRA_ARMING_SAFETY_ALLOW_BYPASS": "1"
+ },
+ "navFwLaunchStatus_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "FW_LAUNCH_DETECTED": "5",
+ "FW_LAUNCH_ABORTED": "10",
+ "FW_LAUNCH_FLYING": "11"
+ },
+ "navigationEstimateStatus_e": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "EST_NONE": "0",
+ "EST_USABLE": "1",
+ "EST_TRUSTED": "2"
+ },
+ "navigationFSMEvent_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_FSM_EVENT_NONE": "0",
+ "NAV_FSM_EVENT_TIMEOUT": "1",
+ "NAV_FSM_EVENT_SUCCESS": "2",
+ "NAV_FSM_EVENT_ERROR": "3",
+ "NAV_FSM_EVENT_SWITCH_TO_IDLE": "4",
+ "NAV_FSM_EVENT_SWITCH_TO_ALTHOLD": "5",
+ "NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D": "6",
+ "NAV_FSM_EVENT_SWITCH_TO_RTH": "7",
+ "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT": "8",
+ "NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING": "9",
+ "NAV_FSM_EVENT_SWITCH_TO_LAUNCH": "10",
+ "NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD": "11",
+ "NAV_FSM_EVENT_SWITCH_TO_CRUISE": "12",
+ "NAV_FSM_EVENT_SWITCH_TO_COURSE_ADJ": "13",
+ "NAV_FSM_EVENT_SWITCH_TO_MIXERAT": "14",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING": "15",
+ "NAV_FSM_EVENT_SWITCH_TO_SEND_TO": "16",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_1": "17",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_2": "18",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_3": "19",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_4": "20",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_5": "21",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_ABORT": "NAV_FSM_EVENT_STATE_SPECIFIC_1",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_FINISHED": "NAV_FSM_EVENT_STATE_SPECIFIC_2",
+ "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_HOLD_TIME": "NAV_FSM_EVENT_STATE_SPECIFIC_1",
+ "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_RTH_LAND": "NAV_FSM_EVENT_STATE_SPECIFIC_2",
+ "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED": "NAV_FSM_EVENT_STATE_SPECIFIC_3",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_RTH_INITIALIZE": "NAV_FSM_EVENT_STATE_SPECIFIC_1",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_RTH_TRACKBACK": "NAV_FSM_EVENT_STATE_SPECIFIC_2",
+ "NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME": "NAV_FSM_EVENT_STATE_SPECIFIC_3",
+ "NAV_FSM_EVENT_SWITCH_TO_RTH_LOITER_ABOVE_HOME": "NAV_FSM_EVENT_STATE_SPECIFIC_4",
+ "NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING": "NAV_FSM_EVENT_STATE_SPECIFIC_5",
+ "NAV_FSM_EVENT_COUNT": ""
+ },
+ "navigationFSMState_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_STATE_UNDEFINED": "0",
+ "NAV_STATE_IDLE": "1",
+ "NAV_STATE_ALTHOLD_INITIALIZE": "2",
+ "NAV_STATE_ALTHOLD_IN_PROGRESS": "3",
+ "NAV_STATE_POSHOLD_3D_INITIALIZE": "4",
+ "NAV_STATE_POSHOLD_3D_IN_PROGRESS": "5",
+ "NAV_STATE_RTH_INITIALIZE": "6",
+ "NAV_STATE_RTH_CLIMB_TO_SAFE_ALT": "7",
+ "NAV_STATE_RTH_TRACKBACK": "8",
+ "NAV_STATE_RTH_HEAD_HOME": "9",
+ "NAV_STATE_RTH_LOITER_PRIOR_TO_LANDING": "10",
+ "NAV_STATE_RTH_LOITER_ABOVE_HOME": "11",
+ "NAV_STATE_RTH_LANDING": "12",
+ "NAV_STATE_RTH_FINISHING": "13",
+ "NAV_STATE_RTH_FINISHED": "14",
+ "NAV_STATE_WAYPOINT_INITIALIZE": "15",
+ "NAV_STATE_WAYPOINT_PRE_ACTION": "16",
+ "NAV_STATE_WAYPOINT_IN_PROGRESS": "17",
+ "NAV_STATE_WAYPOINT_REACHED": "18",
+ "NAV_STATE_WAYPOINT_HOLD_TIME": "19",
+ "NAV_STATE_WAYPOINT_NEXT": "20",
+ "NAV_STATE_WAYPOINT_FINISHED": "21",
+ "NAV_STATE_WAYPOINT_RTH_LAND": "22",
+ "NAV_STATE_EMERGENCY_LANDING_INITIALIZE": "23",
+ "NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS": "24",
+ "NAV_STATE_EMERGENCY_LANDING_FINISHED": "25",
+ "NAV_STATE_LAUNCH_INITIALIZE": "26",
+ "NAV_STATE_LAUNCH_WAIT": "27",
+ "NAV_STATE_LAUNCH_IN_PROGRESS": "28",
+ "NAV_STATE_COURSE_HOLD_INITIALIZE": "29",
+ "NAV_STATE_COURSE_HOLD_IN_PROGRESS": "30",
+ "NAV_STATE_COURSE_HOLD_ADJUSTING": "31",
+ "NAV_STATE_CRUISE_INITIALIZE": "32",
+ "NAV_STATE_CRUISE_IN_PROGRESS": "33",
+ "NAV_STATE_CRUISE_ADJUSTING": "34",
+ "NAV_STATE_FW_LANDING_CLIMB_TO_LOITER": "35",
+ "NAV_STATE_FW_LANDING_LOITER": "36",
+ "NAV_STATE_FW_LANDING_APPROACH": "37",
+ "NAV_STATE_FW_LANDING_GLIDE": "38",
+ "NAV_STATE_FW_LANDING_FLARE": "39",
+ "NAV_STATE_FW_LANDING_FINISHED": "40",
+ "NAV_STATE_FW_LANDING_ABORT": "41",
+ "NAV_STATE_MIXERAT_INITIALIZE": "42",
+ "NAV_STATE_MIXERAT_IN_PROGRESS": "43",
+ "NAV_STATE_MIXERAT_ABORT": "44",
+ "NAV_STATE_SEND_TO_INITALIZE": "45",
+ "NAV_STATE_SEND_TO_IN_PROGESS": "46",
+ "NAV_STATE_SEND_TO_FINISHED": "47",
+ "NAV_STATE_COUNT": "48"
+ },
+ "navigationFSMStateFlags_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_CTL_ALT": "(1 << 0)",
+ "NAV_CTL_POS": "(1 << 1)",
+ "NAV_CTL_YAW": "(1 << 2)",
+ "NAV_CTL_EMERG": "(1 << 3)",
+ "NAV_CTL_LAUNCH": "(1 << 4)",
+ "NAV_REQUIRE_ANGLE": "(1 << 5)",
+ "NAV_REQUIRE_ANGLE_FW": "(1 << 6)",
+ "NAV_REQUIRE_MAGHOLD": "(1 << 7)",
+ "NAV_REQUIRE_THRTILT": "(1 << 8)",
+ "NAV_AUTO_RTH": "(1 << 9)",
+ "NAV_AUTO_WP": "(1 << 10)",
+ "NAV_RC_ALT": "(1 << 11)",
+ "NAV_RC_POS": "(1 << 12)",
+ "NAV_RC_YAW": "(1 << 13)",
+ "NAV_CTL_LAND": "(1 << 14)",
+ "NAV_AUTO_WP_DONE": "(1 << 15)",
+ "NAV_MIXERAT": "(1 << 16)",
+ "NAV_CTL_HOLD": "(1 << 17)"
+ },
+ "navigationHomeFlags_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_HOME_INVALID": "0",
+ "NAV_HOME_VALID_XY": "1 << 0",
+ "NAV_HOME_VALID_Z": "1 << 1",
+ "NAV_HOME_VALID_HEADING": "1 << 2",
+ "NAV_HOME_VALID_ALL": "NAV_HOME_VALID_XY | NAV_HOME_VALID_Z | NAV_HOME_VALID_HEADING"
+ },
+ "navigationPersistentId_e": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_PERSISTENT_ID_UNDEFINED": "0",
+ "NAV_PERSISTENT_ID_IDLE": "1",
+ "NAV_PERSISTENT_ID_ALTHOLD_INITIALIZE": "2",
+ "NAV_PERSISTENT_ID_ALTHOLD_IN_PROGRESS": "3",
+ "NAV_PERSISTENT_ID_UNUSED_1": "4",
+ "NAV_PERSISTENT_ID_UNUSED_2": "5",
+ "NAV_PERSISTENT_ID_POSHOLD_3D_INITIALIZE": "6",
+ "NAV_PERSISTENT_ID_POSHOLD_3D_IN_PROGRESS": "7",
+ "NAV_PERSISTENT_ID_RTH_INITIALIZE": "8",
+ "NAV_PERSISTENT_ID_RTH_CLIMB_TO_SAFE_ALT": "9",
+ "NAV_PERSISTENT_ID_RTH_HEAD_HOME": "10",
+ "NAV_PERSISTENT_ID_RTH_LOITER_PRIOR_TO_LANDING": "11",
+ "NAV_PERSISTENT_ID_RTH_LANDING": "12",
+ "NAV_PERSISTENT_ID_RTH_FINISHING": "13",
+ "NAV_PERSISTENT_ID_RTH_FINISHED": "14",
+ "NAV_PERSISTENT_ID_WAYPOINT_INITIALIZE": "15",
+ "NAV_PERSISTENT_ID_WAYPOINT_PRE_ACTION": "16",
+ "NAV_PERSISTENT_ID_WAYPOINT_IN_PROGRESS": "17",
+ "NAV_PERSISTENT_ID_WAYPOINT_REACHED": "18",
+ "NAV_PERSISTENT_ID_WAYPOINT_NEXT": "19",
+ "NAV_PERSISTENT_ID_WAYPOINT_FINISHED": "20",
+ "NAV_PERSISTENT_ID_WAYPOINT_RTH_LAND": "21",
+ "NAV_PERSISTENT_ID_EMERGENCY_LANDING_INITIALIZE": "22",
+ "NAV_PERSISTENT_ID_EMERGENCY_LANDING_IN_PROGRESS": "23",
+ "NAV_PERSISTENT_ID_EMERGENCY_LANDING_FINISHED": "24",
+ "NAV_PERSISTENT_ID_LAUNCH_INITIALIZE": "25",
+ "NAV_PERSISTENT_ID_LAUNCH_WAIT": "26",
+ "NAV_PERSISTENT_ID_UNUSED_3": "27",
+ "NAV_PERSISTENT_ID_LAUNCH_IN_PROGRESS": "28",
+ "NAV_PERSISTENT_ID_COURSE_HOLD_INITIALIZE": "29",
+ "NAV_PERSISTENT_ID_COURSE_HOLD_IN_PROGRESS": "30",
+ "NAV_PERSISTENT_ID_COURSE_HOLD_ADJUSTING": "31",
+ "NAV_PERSISTENT_ID_CRUISE_INITIALIZE": "32",
+ "NAV_PERSISTENT_ID_CRUISE_IN_PROGRESS": "33",
+ "NAV_PERSISTENT_ID_CRUISE_ADJUSTING": "34",
+ "NAV_PERSISTENT_ID_WAYPOINT_HOLD_TIME": "35",
+ "NAV_PERSISTENT_ID_RTH_LOITER_ABOVE_HOME": "36",
+ "NAV_PERSISTENT_ID_UNUSED_4": "37",
+ "NAV_PERSISTENT_ID_RTH_TRACKBACK": "38",
+ "NAV_PERSISTENT_ID_MIXERAT_INITIALIZE": "39",
+ "NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS": "40",
+ "NAV_PERSISTENT_ID_MIXERAT_ABORT": "41",
+ "NAV_PERSISTENT_ID_FW_LANDING_CLIMB_TO_LOITER": "42",
+ "NAV_PERSISTENT_ID_FW_LANDING_LOITER": "43",
+ "NAV_PERSISTENT_ID_FW_LANDING_APPROACH": "44",
+ "NAV_PERSISTENT_ID_FW_LANDING_GLIDE": "45",
+ "NAV_PERSISTENT_ID_FW_LANDING_FLARE": "46",
+ "NAV_PERSISTENT_ID_FW_LANDING_ABORT": "47",
+ "NAV_PERSISTENT_ID_FW_LANDING_FINISHED": "48",
+ "NAV_PERSISTENT_ID_SEND_TO_INITALIZE": "49",
+ "NAV_PERSISTENT_ID_SEND_TO_IN_PROGRES": "50",
+ "NAV_PERSISTENT_ID_SEND_TO_FINISHED": "51"
+ },
+ "navMcAltHoldThrottle_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MC_ALT_HOLD_STICK": "0",
+ "MC_ALT_HOLD_MID": "1",
+ "MC_ALT_HOLD_HOVER": "2"
+ },
+ "navMissionRestart_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "WP_MISSION_START": "0",
+ "WP_MISSION_RESUME": "1",
+ "WP_MISSION_SWITCH": "2"
+ },
+ "navOverridesMotorStop_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NOMS_OFF_ALWAYS": "0",
+ "NOMS_OFF": "1",
+ "NOMS_AUTO_ONLY": "2",
+ "NOMS_ALL_NAV": "3"
+ },
+ "navPositionEstimationFlags_e": {
+ "_source": "../../../src/main/navigation/navigation_pos_estimator_private.h",
+ "EST_GPS_XY_VALID": "(1 << 0)",
+ "EST_GPS_Z_VALID": "(1 << 1)",
+ "EST_BARO_VALID": "(1 << 2)",
+ "EST_SURFACE_VALID": "(1 << 3)",
+ "EST_FLOW_VALID": "(1 << 4)",
+ "EST_XY_VALID": "(1 << 5)",
+ "EST_Z_VALID": "(1 << 6)"
+ },
+ "navRTHAllowLanding_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_RTH_ALLOW_LANDING_NEVER": "0",
+ "NAV_RTH_ALLOW_LANDING_ALWAYS": "1",
+ "NAV_RTH_ALLOW_LANDING_FS_ONLY": "2"
+ },
+ "navRTHClimbFirst_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "RTH_CLIMB_OFF": "0",
+ "RTH_CLIMB_ON": "1",
+ "RTH_CLIMB_ON_FW_SPIRAL": "2"
+ },
+ "navSetWaypointFlags_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_POS_UPDATE_NONE": "0",
+ "NAV_POS_UPDATE_Z": "1 << 1",
+ "NAV_POS_UPDATE_XY": "1 << 0",
+ "NAV_POS_UPDATE_HEADING": "1 << 2",
+ "NAV_POS_UPDATE_BEARING": "1 << 3",
+ "NAV_POS_UPDATE_BEARING_TAIL_FIRST": "1 << 4"
+ },
+ "navSystemStatus_Error_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MW_NAV_ERROR_NONE": "0",
+ "MW_NAV_ERROR_TOOFAR": "1",
+ "MW_NAV_ERROR_SPOILED_GPS": "2",
+ "MW_NAV_ERROR_WP_CRC": "3",
+ "MW_NAV_ERROR_FINISH": "4",
+ "MW_NAV_ERROR_TIMEWAIT": "5",
+ "MW_NAV_ERROR_INVALID_JUMP": "6",
+ "MW_NAV_ERROR_INVALID_DATA": "7",
+ "MW_NAV_ERROR_WAIT_FOR_RTH_ALT": "8",
+ "MW_NAV_ERROR_GPS_FIX_LOST": "9",
+ "MW_NAV_ERROR_DISARMED": "10",
+ "MW_NAV_ERROR_LANDING": "11"
+ },
+ "navSystemStatus_Flags_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MW_NAV_FLAG_ADJUSTING_POSITION": "1 << 0",
+ "MW_NAV_FLAG_ADJUSTING_ALTITUDE": "1 << 1"
+ },
+ "navSystemStatus_Mode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MW_GPS_MODE_NONE": "0",
+ "MW_GPS_MODE_HOLD": "1",
+ "MW_GPS_MODE_RTH": "2",
+ "MW_GPS_MODE_NAV": "3",
+ "MW_GPS_MODE_EMERG": "15"
+ },
+ "navSystemStatus_State_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MW_NAV_STATE_NONE": "0",
+ "MW_NAV_STATE_RTH_START": "1",
+ "MW_NAV_STATE_RTH_ENROUTE": "2",
+ "MW_NAV_STATE_HOLD_INFINIT": "3",
+ "MW_NAV_STATE_HOLD_TIMED": "4",
+ "MW_NAV_STATE_WP_ENROUTE": "5",
+ "MW_NAV_STATE_PROCESS_NEXT": "6",
+ "MW_NAV_STATE_DO_JUMP": "7",
+ "MW_NAV_STATE_LAND_START": "8",
+ "MW_NAV_STATE_LAND_IN_PROGRESS": "9",
+ "MW_NAV_STATE_LANDED": "10",
+ "MW_NAV_STATE_LAND_SETTLE": "11",
+ "MW_NAV_STATE_LAND_START_DESCENT": "12",
+ "MW_NAV_STATE_HOVER_ABOVE_HOME": "13",
+ "MW_NAV_STATE_EMERGENCY_LANDING": "14",
+ "MW_NAV_STATE_RTH_CLIMB": "15"
+ },
+ "navWaypointActions_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_ACTION_WAYPOINT": "1",
+ "NAV_WP_ACTION_HOLD_TIME": "3",
+ "NAV_WP_ACTION_RTH": "4",
+ "NAV_WP_ACTION_SET_POI": "5",
+ "NAV_WP_ACTION_JUMP": "6",
+ "NAV_WP_ACTION_SET_HEAD": "7",
+ "NAV_WP_ACTION_LAND": "8"
+ },
+ "navWaypointFlags_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_FLAG_HOME": "72",
+ "NAV_WP_FLAG_LAST": "165"
+ },
+ "navWaypointHeadings_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_HEAD_MODE_NONE": "0",
+ "NAV_WP_HEAD_MODE_POI": "1",
+ "NAV_WP_HEAD_MODE_FIXED": "2"
+ },
+ "navWaypointP3Flags_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_ALTMODE": "(1<<0)",
+ "NAV_WP_USER1": "(1<<1)",
+ "NAV_WP_USER2": "(1<<2)",
+ "NAV_WP_USER3": "(1<<3)",
+ "NAV_WP_USER4": "(1<<4)"
+ },
+ "opflowQuality_e": {
+ "_source": "../../../src/main/sensors/opflow.h",
+ "OPFLOW_QUALITY_INVALID": "0",
+ "OPFLOW_QUALITY_VALID": "1"
+ },
+ "opticalFlowSensor_e": {
+ "_source": "../../../src/main/sensors/opflow.h",
+ "OPFLOW_NONE": "0",
+ "OPFLOW_CXOF": "1",
+ "OPFLOW_MSP": "2",
+ "OPFLOW_FAKE": "3"
+ },
+ "osd_adsb_warning_style_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_ADSB_WARNING_STYLE_COMPACT": "0",
+ "OSD_ADSB_WARNING_STYLE_EXTENDED": "1"
+ },
+ "osd_ahi_style_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_AHI_STYLE_DEFAULT": "0",
+ "OSD_AHI_STYLE_LINE": "1"
+ },
+ "osd_alignment_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_ALIGN_LEFT": "0",
+ "OSD_ALIGN_RIGHT": "1"
+ },
+ "osd_crosshairs_style_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_CROSSHAIRS_STYLE_DEFAULT": "0",
+ "OSD_CROSSHAIRS_STYLE_AIRCRAFT": "1",
+ "OSD_CROSSHAIRS_STYLE_TYPE3": "2",
+ "OSD_CROSSHAIRS_STYLE_TYPE4": "3",
+ "OSD_CROSSHAIRS_STYLE_TYPE5": "4",
+ "OSD_CROSSHAIRS_STYLE_TYPE6": "5",
+ "OSD_CROSSHAIRS_STYLE_TYPE7": "6"
+ },
+ "osd_crsf_lq_format_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_CRSF_LQ_TYPE1": "0",
+ "OSD_CRSF_LQ_TYPE2": "1",
+ "OSD_CRSF_LQ_TYPE3": "2"
+ },
+ "osd_items_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_RSSI_VALUE": "0",
+ "OSD_MAIN_BATT_VOLTAGE": "1",
+ "OSD_CROSSHAIRS": "2",
+ "OSD_ARTIFICIAL_HORIZON": "3",
+ "OSD_HORIZON_SIDEBARS": "4",
+ "OSD_ONTIME": "5",
+ "OSD_FLYTIME": "6",
+ "OSD_FLYMODE": "7",
+ "OSD_CRAFT_NAME": "8",
+ "OSD_THROTTLE_POS": "9",
+ "OSD_VTX_CHANNEL": "10",
+ "OSD_CURRENT_DRAW": "11",
+ "OSD_MAH_DRAWN": "12",
+ "OSD_GPS_SPEED": "13",
+ "OSD_GPS_SATS": "14",
+ "OSD_ALTITUDE": "15",
+ "OSD_ROLL_PIDS": "16",
+ "OSD_PITCH_PIDS": "17",
+ "OSD_YAW_PIDS": "18",
+ "OSD_POWER": "19",
+ "OSD_GPS_LON": "20",
+ "OSD_GPS_LAT": "21",
+ "OSD_HOME_DIR": "22",
+ "OSD_HOME_DIST": "23",
+ "OSD_HEADING": "24",
+ "OSD_VARIO": "25",
+ "OSD_VERTICAL_SPEED_INDICATOR": "26",
+ "OSD_AIR_SPEED": "27",
+ "OSD_ONTIME_FLYTIME": "28",
+ "OSD_RTC_TIME": "29",
+ "OSD_MESSAGES": "30",
+ "OSD_GPS_HDOP": "31",
+ "OSD_MAIN_BATT_CELL_VOLTAGE": "32",
+ "OSD_SCALED_THROTTLE_POS": "33",
+ "OSD_HEADING_GRAPH": "34",
+ "OSD_EFFICIENCY_MAH_PER_KM": "35",
+ "OSD_WH_DRAWN": "36",
+ "OSD_BATTERY_REMAINING_CAPACITY": "37",
+ "OSD_BATTERY_REMAINING_PERCENT": "38",
+ "OSD_EFFICIENCY_WH_PER_KM": "39",
+ "OSD_TRIP_DIST": "40",
+ "OSD_ATTITUDE_PITCH": "41",
+ "OSD_ATTITUDE_ROLL": "42",
+ "OSD_MAP_NORTH": "43",
+ "OSD_MAP_TAKEOFF": "44",
+ "OSD_RADAR": "45",
+ "OSD_WIND_SPEED_HORIZONTAL": "46",
+ "OSD_WIND_SPEED_VERTICAL": "47",
+ "OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH": "48",
+ "OSD_REMAINING_DISTANCE_BEFORE_RTH": "49",
+ "OSD_HOME_HEADING_ERROR": "50",
+ "OSD_COURSE_HOLD_ERROR": "51",
+ "OSD_COURSE_HOLD_ADJUSTMENT": "52",
+ "OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE": "53",
+ "OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE": "54",
+ "OSD_POWER_SUPPLY_IMPEDANCE": "55",
+ "OSD_LEVEL_PIDS": "56",
+ "OSD_POS_XY_PIDS": "57",
+ "OSD_POS_Z_PIDS": "58",
+ "OSD_VEL_XY_PIDS": "59",
+ "OSD_VEL_Z_PIDS": "60",
+ "OSD_HEADING_P": "61",
+ "OSD_BOARD_ALIGN_ROLL": "62",
+ "OSD_BOARD_ALIGN_PITCH": "63",
+ "OSD_RC_EXPO": "64",
+ "OSD_RC_YAW_EXPO": "65",
+ "OSD_THROTTLE_EXPO": "66",
+ "OSD_PITCH_RATE": "67",
+ "OSD_ROLL_RATE": "68",
+ "OSD_YAW_RATE": "69",
+ "OSD_MANUAL_RC_EXPO": "70",
+ "OSD_MANUAL_RC_YAW_EXPO": "71",
+ "OSD_MANUAL_PITCH_RATE": "72",
+ "OSD_MANUAL_ROLL_RATE": "73",
+ "OSD_MANUAL_YAW_RATE": "74",
+ "OSD_NAV_FW_CRUISE_THR": "75",
+ "OSD_NAV_FW_PITCH2THR": "76",
+ "OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE": "77",
+ "OSD_DEBUG": "78",
+ "OSD_FW_ALT_PID_OUTPUTS": "79",
+ "OSD_FW_POS_PID_OUTPUTS": "80",
+ "OSD_MC_VEL_X_PID_OUTPUTS": "81",
+ "OSD_MC_VEL_Y_PID_OUTPUTS": "82",
+ "OSD_MC_VEL_Z_PID_OUTPUTS": "83",
+ "OSD_MC_POS_XYZ_P_OUTPUTS": "84",
+ "OSD_3D_SPEED": "85",
+ "OSD_IMU_TEMPERATURE": "86",
+ "OSD_BARO_TEMPERATURE": "87",
+ "OSD_TEMP_SENSOR_0_TEMPERATURE": "88",
+ "OSD_TEMP_SENSOR_1_TEMPERATURE": "89",
+ "OSD_TEMP_SENSOR_2_TEMPERATURE": "90",
+ "OSD_TEMP_SENSOR_3_TEMPERATURE": "91",
+ "OSD_TEMP_SENSOR_4_TEMPERATURE": "92",
+ "OSD_TEMP_SENSOR_5_TEMPERATURE": "93",
+ "OSD_TEMP_SENSOR_6_TEMPERATURE": "94",
+ "OSD_TEMP_SENSOR_7_TEMPERATURE": "95",
+ "OSD_ALTITUDE_MSL": "96",
+ "OSD_PLUS_CODE": "97",
+ "OSD_MAP_SCALE": "98",
+ "OSD_MAP_REFERENCE": "99",
+ "OSD_GFORCE": "100",
+ "OSD_GFORCE_X": "101",
+ "OSD_GFORCE_Y": "102",
+ "OSD_GFORCE_Z": "103",
+ "OSD_RC_SOURCE": "104",
+ "OSD_VTX_POWER": "105",
+ "OSD_ESC_RPM": "106",
+ "OSD_ESC_TEMPERATURE": "107",
+ "OSD_AZIMUTH": "108",
+ "OSD_RSSI_DBM": "109",
+ "OSD_LQ_UPLINK": "110",
+ "OSD_SNR_DB": "111",
+ "OSD_TX_POWER_UPLINK": "112",
+ "OSD_GVAR_0": "113",
+ "OSD_GVAR_1": "114",
+ "OSD_GVAR_2": "115",
+ "OSD_GVAR_3": "116",
+ "OSD_TPA": "117",
+ "OSD_NAV_FW_CONTROL_SMOOTHNESS": "118",
+ "OSD_VERSION": "119",
+ "OSD_RANGEFINDER": "120",
+ "OSD_PLIMIT_REMAINING_BURST_TIME": "121",
+ "OSD_PLIMIT_ACTIVE_CURRENT_LIMIT": "122",
+ "OSD_PLIMIT_ACTIVE_POWER_LIMIT": "123",
+ "OSD_GLIDESLOPE": "124",
+ "OSD_GPS_MAX_SPEED": "125",
+ "OSD_3D_MAX_SPEED": "126",
+ "OSD_AIR_MAX_SPEED": "127",
+ "OSD_ACTIVE_PROFILE": "128",
+ "OSD_MISSION": "129",
+ "OSD_SWITCH_INDICATOR_0": "130",
+ "OSD_SWITCH_INDICATOR_1": "131",
+ "OSD_SWITCH_INDICATOR_2": "132",
+ "OSD_SWITCH_INDICATOR_3": "133",
+ "OSD_TPA_TIME_CONSTANT": "134",
+ "OSD_FW_LEVEL_TRIM": "135",
+ "OSD_GLIDE_TIME_REMAINING": "136",
+ "OSD_GLIDE_RANGE": "137",
+ "OSD_CLIMB_EFFICIENCY": "138",
+ "OSD_NAV_WP_MULTI_MISSION_INDEX": "139",
+ "OSD_GROUND_COURSE": "140",
+ "OSD_CROSS_TRACK_ERROR": "141",
+ "OSD_PILOT_NAME": "142",
+ "OSD_PAN_SERVO_CENTRED": "143",
+ "OSD_MULTI_FUNCTION": "144",
+ "OSD_ODOMETER": "145",
+ "OSD_PILOT_LOGO": "146",
+ "OSD_CUSTOM_ELEMENT_1": "147",
+ "OSD_CUSTOM_ELEMENT_2": "148",
+ "OSD_CUSTOM_ELEMENT_3": "149",
+ "OSD_ADSB_WARNING": "150",
+ "OSD_ADSB_INFO": "151",
+ "OSD_BLACKBOX": "152",
+ "OSD_FORMATION_FLIGHT": "153",
+ "OSD_CUSTOM_ELEMENT_4": "154",
+ "OSD_CUSTOM_ELEMENT_5": "155",
+ "OSD_CUSTOM_ELEMENT_6": "156",
+ "OSD_CUSTOM_ELEMENT_7": "157",
+ "OSD_CUSTOM_ELEMENT_8": "158",
+ "OSD_LQ_DOWNLINK": "159",
+ "OSD_RX_POWER_DOWNLINK": "160",
+ "OSD_RX_BAND": "161",
+ "OSD_RX_MODE": "162",
+ "OSD_COURSE_TO_FENCE": "163",
+ "OSD_H_DIST_TO_FENCE": "164",
+ "OSD_V_DIST_TO_FENCE": "165",
+ "OSD_NAV_FW_ALT_CONTROL_RESPONSE": "166",
+ "OSD_NAV_MIN_GROUND_SPEED": "167",
+ "OSD_THROTTLE_GAUGE": "168",
+ "OSD_ITEM_COUNT": "169"
+ },
+ "osd_sidebar_arrow_e": {
+ "_source": "../../../src/main/io/osd_grid.c",
+ "OSD_SIDEBAR_ARROW_NONE": "0",
+ "OSD_SIDEBAR_ARROW_UP": "1",
+ "OSD_SIDEBAR_ARROW_DOWN": "2"
+ },
+ "osd_sidebar_scroll_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_SIDEBAR_SCROLL_NONE": "0",
+ "OSD_SIDEBAR_SCROLL_ALTITUDE": "1",
+ "OSD_SIDEBAR_SCROLL_SPEED": "2",
+ "OSD_SIDEBAR_SCROLL_HOME_DISTANCE": "3",
+ "OSD_SIDEBAR_SCROLL_MAX": "OSD_SIDEBAR_SCROLL_HOME_DISTANCE"
+ },
+ "osd_SpeedTypes_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_SPEED_TYPE_GROUND": "0",
+ "OSD_SPEED_TYPE_AIR": "1",
+ "OSD_SPEED_TYPE_3D": "2",
+ "OSD_SPEED_TYPE_MIN_GROUND": "3"
+ },
+ "osd_stats_energy_unit_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_STATS_ENERGY_UNIT_MAH": "0",
+ "OSD_STATS_ENERGY_UNIT_WH": "1"
+ },
+ "osd_unit_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_UNIT_IMPERIAL": "0",
+ "OSD_UNIT_METRIC": "1",
+ "OSD_UNIT_METRIC_MPH": "2",
+ "OSD_UNIT_UK": "3",
+ "OSD_UNIT_GA": "4",
+ "OSD_UNIT_MAX": "OSD_UNIT_GA"
+ },
+ "osdCustomElementType_e": {
+ "_source": "../../../src/main/io/osd/custom_elements.h",
+ "CUSTOM_ELEMENT_TYPE_NONE": "0",
+ "CUSTOM_ELEMENT_TYPE_TEXT": "1",
+ "CUSTOM_ELEMENT_TYPE_ICON_STATIC": "2",
+ "CUSTOM_ELEMENT_TYPE_ICON_GV": "3",
+ "CUSTOM_ELEMENT_TYPE_ICON_LC": "4",
+ "CUSTOM_ELEMENT_TYPE_GV_1": "5",
+ "CUSTOM_ELEMENT_TYPE_GV_2": "6",
+ "CUSTOM_ELEMENT_TYPE_GV_3": "7",
+ "CUSTOM_ELEMENT_TYPE_GV_4": "8",
+ "CUSTOM_ELEMENT_TYPE_GV_5": "9",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_1": "10",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_2": "11",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_1": "12",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_2": "13",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_1": "14",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_2": "15",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_4_1": "16",
+ "CUSTOM_ELEMENT_TYPE_LC_1": "17",
+ "CUSTOM_ELEMENT_TYPE_LC_2": "18",
+ "CUSTOM_ELEMENT_TYPE_LC_3": "19",
+ "CUSTOM_ELEMENT_TYPE_LC_4": "20",
+ "CUSTOM_ELEMENT_TYPE_LC_5": "21",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_1": "22",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_2": "23",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_1": "24",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_2": "25",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_1": "26",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_2": "27",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_4_1": "28",
+ "CUSTOM_ELEMENT_TYPE_END": "29"
+ },
+ "osdCustomElementTypeVisibility_e": {
+ "_source": "../../../src/main/io/osd/custom_elements.h",
+ "CUSTOM_ELEMENT_VISIBILITY_ALWAYS": "0",
+ "CUSTOM_ELEMENT_VISIBILITY_GV": "1",
+ "CUSTOM_ELEMENT_VISIBILITY_LOGIC_CON": "2"
+ },
+ "osdDrawPointType_e": {
+ "_source": "../../../src/main/io/osd_common.h",
+ "OSD_DRAW_POINT_TYPE_GRID": "0",
+ "OSD_DRAW_POINT_TYPE_PIXEL": "1"
+ },
+ "osdDriver_e": {
+ "_source": "../../../src/main/drivers/osd.h",
+ "OSD_DRIVER_NONE": "0",
+ "OSD_DRIVER_MAX7456": "1"
+ },
+ "osdSpeedSource_e": {
+ "_source": "../../../src/main/io/osd_common.h",
+ "OSD_SPEED_SOURCE_GROUND": "0",
+ "OSD_SPEED_SOURCE_3D": "1",
+ "OSD_SPEED_SOURCE_AIR": "2"
+ },
+ "outputMode_e": {
+ "_source": "../../../src/main/flight/mixer.h",
+ "OUTPUT_MODE_AUTO": "0",
+ "OUTPUT_MODE_MOTORS": "1",
+ "OUTPUT_MODE_SERVOS": "2",
+ "OUTPUT_MODE_LED": "3"
+ },
+ "pageId_e": {
+ "_source": "../../../src/main/io/dashboard.h",
+ "PAGE_WELCOME": "0",
+ "PAGE_ARMED": "1",
+ "PAGE_STATUS": "2"
+ },
+ "persistentObjectId_e": {
+ "_source": "../../../src/main/drivers/persistent.h",
+ "PERSISTENT_OBJECT_MAGIC": "0",
+ "PERSISTENT_OBJECT_RESET_REASON": "1",
+ "PERSISTENT_OBJECT_COUNT": "2"
+ },
+ "pidAutotuneState_e": {
+ "_source": "../../../src/main/flight/pid_autotune.c",
+ "DEMAND_TOO_LOW": "0",
+ "DEMAND_UNDERSHOOT": "1",
+ "DEMAND_OVERSHOOT": "2",
+ "TUNE_UPDATED": "3"
+ },
+ "pidControllerFlags_e": {
+ "_source": "../../../src/main/common/fp_pid.h",
+ "PID_DTERM_FROM_ERROR": "1 << 0",
+ "PID_ZERO_INTEGRATOR": "1 << 1",
+ "PID_SHRINK_INTEGRATOR": "1 << 2",
+ "PID_LIMIT_INTEGRATOR": "1 << 3",
+ "PID_FREEZE_INTEGRATOR": "1 << 4"
+ },
+ "pidIndex_e": {
+ "_source": "../../../src/main/flight/pid.h",
+ "PID_ROLL": "0",
+ "PID_PITCH": "1",
+ "PID_YAW": "2",
+ "PID_POS_Z": "3",
+ "PID_POS_XY": "4",
+ "PID_VEL_XY": "5",
+ "PID_SURFACE": "6",
+ "PID_LEVEL": "7",
+ "PID_HEADING": "8",
+ "PID_VEL_Z": "9",
+ "PID_POS_HEADING": "10",
+ "PID_ITEM_COUNT": "11"
+ },
+ "pidType_e": {
+ "_source": "../../../src/main/flight/pid.h",
+ "PID_TYPE_NONE": "0",
+ "PID_TYPE_PID": "1",
+ "PID_TYPE_PIFF": "2",
+ "PID_TYPE_AUTO": "3"
+ },
+ "pinLabel_e": {
+ "_source": "../../../src/main/drivers/pwm_mapping.h",
+ "PIN_LABEL_NONE": "0",
+ "PIN_LABEL_LED": "1"
+ },
+ "pitotSensor_e": {
+ "_source": "../../../src/main/sensors/pitotmeter.h",
+ "PITOT_NONE": "0",
+ "PITOT_AUTODETECT": "1",
+ "PITOT_MS4525": "2",
+ "PITOT_ADC": "3",
+ "PITOT_VIRTUAL": "4",
+ "PITOT_FAKE": "5",
+ "PITOT_MSP": "6",
+ "PITOT_DLVR": "7"
+ },
+ "pollType_e": {
+ "_source": "../../../src/main/io/smartport_master.c",
+ "PT_ACTIVE_ID": "0",
+ "PT_INACTIVE_ID": "1"
+ },
+ "portSharing_e": {
+ "_source": "../../../src/main/io/serial.h",
+ "PORTSHARING_UNUSED": "0",
+ "PORTSHARING_NOT_SHARED": "1",
+ "PORTSHARING_SHARED": "2"
+ },
+ "pwmInitError_e": {
+ "_source": "../../../src/main/drivers/pwm_mapping.h",
+ "PWM_INIT_ERROR_NONE": "0",
+ "PWM_INIT_ERROR_TOO_MANY_MOTORS": "1",
+ "PWM_INIT_ERROR_TOO_MANY_SERVOS": "2",
+ "PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS": "3",
+ "PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS": "4",
+ "PWM_INIT_ERROR_TIMER_INIT_FAILED": "5"
+ },
+ "quadrant_e": {
+ "_source": "../../../src/main/io/ledstrip.c",
+ "QUADRANT_NORTH": "1 << 0",
+ "QUADRANT_SOUTH": "1 << 1",
+ "QUADRANT_EAST": "1 << 2",
+ "QUADRANT_WEST": "1 << 3",
+ "QUADRANT_NORTH_EAST": "1 << 4",
+ "QUADRANT_SOUTH_EAST": "1 << 5",
+ "QUADRANT_NORTH_WEST": "1 << 6",
+ "QUADRANT_SOUTH_WEST": "1 << 7",
+ "QUADRANT_NONE": "1 << 8",
+ "QUADRANT_NOTDIAG": "1 << 9",
+ "QUADRANT_ANY": "QUADRANT_NORTH | QUADRANT_SOUTH | QUADRANT_EAST | QUADRANT_WEST | QUADRANT_NONE"
+ },
+ "QUADSPIClockDivider_e": {
+ "_source": "../../../src/main/drivers/bus_quadspi.h",
+ "QUADSPI_CLOCK_INITIALISATION": "255",
+ "QUADSPI_CLOCK_SLOW": "19",
+ "QUADSPI_CLOCK_STANDARD": "9",
+ "QUADSPI_CLOCK_FAST": "3",
+ "QUADSPI_CLOCK_ULTRAFAST": "1"
+ },
+ "quadSpiMode_e": {
+ "_source": "../../../src/main/drivers/bus_quadspi.h",
+ "QUADSPI_MODE_BK1_ONLY": "0",
+ "QUADSPI_MODE_BK2_ONLY": "1",
+ "QUADSPI_MODE_DUAL_FLASH": "2"
+ },
+ "rangefinderType_e": {
+ "_source": "../../../src/main/sensors/rangefinder.h",
+ "RANGEFINDER_NONE": "0",
+ "RANGEFINDER_SRF10": "1",
+ "RANGEFINDER_VL53L0X": "2",
+ "RANGEFINDER_MSP": "3",
+ "RANGEFINDER_BENEWAKE": "4",
+ "RANGEFINDER_VL53L1X": "5",
+ "RANGEFINDER_US42": "6",
+ "RANGEFINDER_TOF10102I2C": "7",
+ "RANGEFINDER_FAKE": "8",
+ "RANGEFINDER_TERARANGER_EVO": "9",
+ "RANGEFINDER_USD1_V0": "10",
+ "RANGEFINDER_NANORADAR": "11"
+ },
+ "RCDEVICE_5key_connection_event_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN": "1",
+ "RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE": "2"
+ },
+ "rcdevice_5key_simulation_operation_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE": "0",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET": "1",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT": "2",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT": "3",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP": "4",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN": "5"
+ },
+ "rcdevice_camera_control_opeation_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN": "0",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN": "1",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE": "2",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_START_RECORDING": "3",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_STOP_RECORDING": "4",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION": "255"
+ },
+ "rcdevice_features_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON": "(1 << 0)",
+ "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON": "(1 << 1)",
+ "RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE": "(1 << 2)",
+ "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE": "(1 << 3)",
+ "RCDEVICE_PROTOCOL_FEATURE_START_RECORDING": "(1 << 6)",
+ "RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING": "(1 << 7)",
+ "RCDEVICE_PROTOCOL_FEATURE_CMS_MENU": "(1 << 8)"
+ },
+ "rcdevice_protocol_version_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_RCSPLIT_VERSION": "0",
+ "RCDEVICE_PROTOCOL_VERSION_1_0": "1",
+ "RCDEVICE_PROTOCOL_UNKNOWN": "2"
+ },
+ "rcdeviceCamSimulationKeyEvent_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_CAM_KEY_NONE": "0",
+ "RCDEVICE_CAM_KEY_ENTER": "1",
+ "RCDEVICE_CAM_KEY_LEFT": "2",
+ "RCDEVICE_CAM_KEY_UP": "3",
+ "RCDEVICE_CAM_KEY_RIGHT": "4",
+ "RCDEVICE_CAM_KEY_DOWN": "5",
+ "RCDEVICE_CAM_KEY_CONNECTION_CLOSE": "6",
+ "RCDEVICE_CAM_KEY_CONNECTION_OPEN": "7",
+ "RCDEVICE_CAM_KEY_RELEASE": "8"
+ },
+ "rcdeviceResponseStatus_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_RESP_SUCCESS": "0",
+ "RCDEVICE_RESP_INCORRECT_CRC": "1",
+ "RCDEVICE_RESP_TIMEOUT": "2"
+ },
+ "resolutionType_e": {
+ "_source": "../../../src/main/io/displayport_msp_osd.c",
+ "SD_3016": "0",
+ "HD_5018": "1",
+ "HD_3016": "2",
+ "HD_6022": "3",
+ "HD_5320": "4"
+ },
+ "resourceOwner_e": {
+ "_source": "../../../src/main/drivers/resource.h",
+ "OWNER_FREE": "0",
+ "OWNER_PWMIO": "1",
+ "OWNER_MOTOR": "2",
+ "OWNER_SERVO": "3",
+ "OWNER_SOFTSERIAL": "4",
+ "OWNER_ADC": "5",
+ "OWNER_SERIAL": "6",
+ "OWNER_TIMER": "7",
+ "OWNER_RANGEFINDER": "8",
+ "OWNER_SYSTEM": "9",
+ "OWNER_SPI": "10",
+ "OWNER_QUADSPI": "11",
+ "OWNER_I2C": "12",
+ "OWNER_SDCARD": "13",
+ "OWNER_FLASH": "14",
+ "OWNER_USB": "15",
+ "OWNER_BEEPER": "16",
+ "OWNER_OSD": "17",
+ "OWNER_BARO": "18",
+ "OWNER_MPU": "19",
+ "OWNER_INVERTER": "20",
+ "OWNER_LED_STRIP": "21",
+ "OWNER_LED": "22",
+ "OWNER_RX": "23",
+ "OWNER_TX": "24",
+ "OWNER_VTX": "25",
+ "OWNER_SPI_PREINIT": "26",
+ "OWNER_COMPASS": "27",
+ "OWNER_TEMPERATURE": "28",
+ "OWNER_1WIRE": "29",
+ "OWNER_AIRSPEED": "30",
+ "OWNER_OLED_DISPLAY": "31",
+ "OWNER_PINIO": "32",
+ "OWNER_IRLOCK": "33",
+ "OWNER_TOTAL_COUNT": "34"
+ },
+ "resourceType_e": {
+ "_source": "../../../src/main/drivers/resource.h",
+ "RESOURCE_NONE": "0",
+ "RESOURCE_INPUT": "1",
+ "RESOURCE_TIMER": "2",
+ "RESOURCE_UART_TX": "3",
+ "RESOURCE_EXTI": "4",
+ "RESOURCE_I2C_SCL": "5",
+ "RESOURCE_SPI_SCK": "6",
+ "RESOURCE_QUADSPI_CLK": "7",
+ "RESOURCE_QUADSPI_BK1IO2": "8",
+ "RESOURCE_QUADSPI_BK2IO0": "9",
+ "RESOURCE_QUADSPI_BK2IO3": "10",
+ "RESOURCE_ADC_CH1": "11",
+ "RESOURCE_RX_CE": "12",
+ "RESOURCE_TOTAL_COUNT": "13"
+ },
+ "reversibleMotorsThrottleState_e": {
+ "_source": "../../../src/main/flight/mixer.h",
+ "MOTOR_DIRECTION_FORWARD": "0",
+ "MOTOR_DIRECTION_BACKWARD": "1",
+ "MOTOR_DIRECTION_DEADBAND": "2"
+ },
+ "rollPitchStatus_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "NOT_CENTERED": "0",
+ "CENTERED": "1"
+ },
+ "rssiSource_e": {
+ "_source": "../../../src/main/rx/rx.h",
+ "RSSI_SOURCE_NONE": "0",
+ "RSSI_SOURCE_AUTO": "1",
+ "RSSI_SOURCE_ADC": "2",
+ "RSSI_SOURCE_RX_CHANNEL": "3",
+ "RSSI_SOURCE_RX_PROTOCOL": "4",
+ "RSSI_SOURCE_MSP": "5"
+ },
+ "rthState_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "RTH_IDLE": "0",
+ "RTH_IN_PROGRESS": "1",
+ "RTH_HAS_LANDED": "2"
+ },
+ "rthTargetMode_e": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "RTH_HOME_ENROUTE_INITIAL": "0",
+ "RTH_HOME_ENROUTE_PROPORTIONAL": "1",
+ "RTH_HOME_ENROUTE_FINAL": "2",
+ "RTH_HOME_FINAL_LOITER": "3",
+ "RTH_HOME_FINAL_LAND": "4"
+ },
+ "rthTrackbackMode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "RTH_TRACKBACK_OFF": "0",
+ "RTH_TRACKBACK_ON": "1",
+ "RTH_TRACKBACK_FS": "2"
+ },
+ "rxFrameState_e": {
+ "_source": "../../../src/main/rx/rx.h",
+ "RX_FRAME_PENDING": "0",
+ "RX_FRAME_COMPLETE": "(1 << 0)",
+ "RX_FRAME_FAILSAFE": "(1 << 1)",
+ "RX_FRAME_PROCESSING_REQUIRED": "(1 << 2)",
+ "RX_FRAME_DROPPED": "(1 << 3)"
+ },
+ "rxReceiverType_e": {
+ "_source": "../../../src/main/rx/rx.h",
+ "RX_TYPE_NONE": "0",
+ "RX_TYPE_SERIAL": "1",
+ "RX_TYPE_MSP": "2",
+ "RX_TYPE_SIM": "3"
+ },
+ "rxSerialReceiverType_e": {
+ "_source": "../../../src/main/rx/rx.h",
+ "SERIALRX_SPEKTRUM1024": "0",
+ "SERIALRX_SPEKTRUM2048": "1",
+ "SERIALRX_SBUS": "2",
+ "SERIALRX_SUMD": "3",
+ "SERIALRX_IBUS": "4",
+ "SERIALRX_JETIEXBUS": "5",
+ "SERIALRX_CRSF": "6",
+ "SERIALRX_FPORT": "7",
+ "SERIALRX_SBUS_FAST": "8",
+ "SERIALRX_FPORT2": "9",
+ "SERIALRX_SRXL2": "10",
+ "SERIALRX_GHST": "11",
+ "SERIALRX_MAVLINK": "12",
+ "SERIALRX_FBUS": "13",
+ "SERIALRX_SBUS2": "14"
+ },
+ "safehomeUsageMode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "SAFEHOME_USAGE_OFF": "0",
+ "SAFEHOME_USAGE_RTH": "1",
+ "SAFEHOME_USAGE_RTH_FS": "2"
+ },
+ "sbasMode_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "SBAS_AUTO": "0",
+ "SBAS_EGNOS": "1",
+ "SBAS_WAAS": "2",
+ "SBAS_MSAS": "3",
+ "SBAS_GAGAN": "4",
+ "SBAS_SPAN": "5",
+ "SBAS_NONE": "6"
+ },
+ "sbusDecoderState_e": {
+ "_source": "../../../src/main/rx/sbus.c",
+ "STATE_SBUS_SYNC": "0",
+ "STATE_SBUS_PAYLOAD": "1",
+ "STATE_SBUS26_PAYLOAD": "2",
+ "STATE_SBUS_WAIT_SYNC": "3"
+ },
+ "sdcardBlockOperation_e": {
+ "_source": "../../../src/main/drivers/sdcard/sdcard.h",
+ "SDCARD_BLOCK_OPERATION_READ": "0",
+ "SDCARD_BLOCK_OPERATION_WRITE": "1",
+ "SDCARD_BLOCK_OPERATION_ERASE": "2"
+ },
+ "sdcardOperationStatus_e": {
+ "_source": "../../../src/main/drivers/sdcard/sdcard.h",
+ "SDCARD_OPERATION_IN_PROGRESS": "0",
+ "SDCARD_OPERATION_BUSY": "1",
+ "SDCARD_OPERATION_SUCCESS": "2",
+ "SDCARD_OPERATION_FAILURE": "3"
+ },
+ "sdcardReceiveBlockStatus_e": {
+ "_source": "../../../src/main/drivers/sdcard/sdcard_spi.c",
+ "SDCARD_RECEIVE_SUCCESS": "0",
+ "SDCARD_RECEIVE_BLOCK_IN_PROGRESS": "1",
+ "SDCARD_RECEIVE_ERROR": "2"
+ },
+ "sdcardState_e": {
+ "_source": "../../../src/main/drivers/sdcard/sdcard_impl.h",
+ "SDCARD_STATE_NOT_PRESENT": "0",
+ "SDCARD_STATE_RESET": "1",
+ "SDCARD_STATE_CARD_INIT_IN_PROGRESS": "2",
+ "SDCARD_STATE_INITIALIZATION_RECEIVE_CID": "3",
+ "SDCARD_STATE_READY": "4",
+ "SDCARD_STATE_READING": "5",
+ "SDCARD_STATE_SENDING_WRITE": "6",
+ "SDCARD_STATE_WAITING_FOR_WRITE": "7",
+ "SDCARD_STATE_WRITING_MULTIPLE_BLOCKS": "8",
+ "SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE": "9"
+ },
+ "SDIODevice": {
+ "_source": "../../../src/main/drivers/sdio.h",
+ "SDIOINVALID": "-1",
+ "SDIODEV_1": "0",
+ "SDIODEV_2": "1"
+ },
+ "sensor_align_e": {
+ "_source": "../../../src/main/drivers/sensor.h",
+ "ALIGN_DEFAULT": "0",
+ "CW0_DEG": "1",
+ "CW90_DEG": "2",
+ "CW180_DEG": "3",
+ "CW270_DEG": "4",
+ "CW0_DEG_FLIP": "5",
+ "CW90_DEG_FLIP": "6",
+ "CW180_DEG_FLIP": "7",
+ "CW270_DEG_FLIP": "8"
+ },
+ "sensorIndex_e": {
+ "_source": "../../../src/main/sensors/sensors.h",
+ "SENSOR_INDEX_GYRO": "0",
+ "SENSOR_INDEX_ACC": "1",
+ "SENSOR_INDEX_BARO": "2",
+ "SENSOR_INDEX_MAG": "3",
+ "SENSOR_INDEX_RANGEFINDER": "4",
+ "SENSOR_INDEX_PITOT": "5",
+ "SENSOR_INDEX_OPFLOW": "6",
+ "SENSOR_INDEX_COUNT": "7"
+ },
+ "sensors_e": {
+ "_source": "../../../src/main/sensors/sensors.h",
+ "SENSOR_GYRO": "1 << 0",
+ "SENSOR_ACC": "1 << 1",
+ "SENSOR_BARO": "1 << 2",
+ "SENSOR_MAG": "1 << 3",
+ "SENSOR_RANGEFINDER": "1 << 4",
+ "SENSOR_PITOT": "1 << 5",
+ "SENSOR_OPFLOW": "1 << 6",
+ "SENSOR_GPS": "1 << 7",
+ "SENSOR_GPSMAG": "1 << 8",
+ "SENSOR_TEMP": "1 << 9"
+ },
+ "sensorTempCalState_e": {
+ "_source": "../../../src/main/sensors/sensors.h",
+ "SENSOR_TEMP_CAL_INITIALISE": "0",
+ "SENSOR_TEMP_CAL_IN_PROGRESS": "1",
+ "SENSOR_TEMP_CAL_COMPLETE": "2"
+ },
+ "serialPortFunction_e": {
+ "_source": "../../../src/main/io/serial.h",
+ "FUNCTION_NONE": "0",
+ "FUNCTION_MSP": "(1 << 0)",
+ "FUNCTION_GPS": "(1 << 1)",
+ "FUNCTION_UNUSED_3": "(1 << 2)",
+ "FUNCTION_TELEMETRY_HOTT": "(1 << 3)",
+ "FUNCTION_TELEMETRY_LTM": "(1 << 4)",
+ "FUNCTION_TELEMETRY_SMARTPORT": "(1 << 5)",
+ "FUNCTION_RX_SERIAL": "(1 << 6)",
+ "FUNCTION_BLACKBOX": "(1 << 7)",
+ "FUNCTION_TELEMETRY_MAVLINK": "(1 << 8)",
+ "FUNCTION_TELEMETRY_IBUS": "(1 << 9)",
+ "FUNCTION_RCDEVICE": "(1 << 10)",
+ "FUNCTION_VTX_SMARTAUDIO": "(1 << 11)",
+ "FUNCTION_VTX_TRAMP": "(1 << 12)",
+ "FUNCTION_UNUSED_1": "(1 << 13)",
+ "FUNCTION_OPTICAL_FLOW": "(1 << 14)",
+ "FUNCTION_LOG": "(1 << 15)",
+ "FUNCTION_RANGEFINDER": "(1 << 16)",
+ "FUNCTION_VTX_FFPV": "(1 << 17)",
+ "FUNCTION_ESCSERIAL": "(1 << 18)",
+ "FUNCTION_TELEMETRY_SIM": "(1 << 19)",
+ "FUNCTION_FRSKY_OSD": "(1 << 20)",
+ "FUNCTION_DJI_HD_OSD": "(1 << 21)",
+ "FUNCTION_SERVO_SERIAL": "(1 << 22)",
+ "FUNCTION_TELEMETRY_SMARTPORT_MASTER": "(1 << 23)",
+ "FUNCTION_UNUSED_2": "(1 << 24)",
+ "FUNCTION_MSP_OSD": "(1 << 25)",
+ "FUNCTION_GIMBAL": "(1 << 26)",
+ "FUNCTION_GIMBAL_HEADTRACKER": "(1 << 27)"
+ },
+ "serialPortIdentifier_e": {
+ "_source": "../../../src/main/io/serial.h",
+ "SERIAL_PORT_NONE": "-1",
+ "SERIAL_PORT_USART1": "0",
+ "SERIAL_PORT_USART2": "1",
+ "SERIAL_PORT_USART3": "2",
+ "SERIAL_PORT_USART4": "3",
+ "SERIAL_PORT_USART5": "4",
+ "SERIAL_PORT_USART6": "5",
+ "SERIAL_PORT_USART7": "6",
+ "SERIAL_PORT_USART8": "7",
+ "SERIAL_PORT_USB_VCP": "20",
+ "SERIAL_PORT_SOFTSERIAL1": "30",
+ "SERIAL_PORT_SOFTSERIAL2": "31",
+ "SERIAL_PORT_IDENTIFIER_MAX": "SERIAL_PORT_SOFTSERIAL2"
+ },
+ "servoAutotrimState_e": {
+ "_source": "../../../src/main/flight/servos.c",
+ "AUTOTRIM_IDLE": "0",
+ "AUTOTRIM_COLLECTING": "1",
+ "AUTOTRIM_SAVE_PENDING": "2",
+ "AUTOTRIM_DONE": "3"
+ },
+ "servoIndex_e": {
+ "_source": "../../../src/main/flight/servos.h",
+ "SERVO_GIMBAL_PITCH": "0",
+ "SERVO_GIMBAL_ROLL": "1",
+ "SERVO_ELEVATOR": "2",
+ "SERVO_FLAPPERON_1": "3",
+ "SERVO_FLAPPERON_2": "4",
+ "SERVO_RUDDER": "5",
+ "SERVO_BICOPTER_LEFT": "4",
+ "SERVO_BICOPTER_RIGHT": "5",
+ "SERVO_DUALCOPTER_LEFT": "4",
+ "SERVO_DUALCOPTER_RIGHT": "5",
+ "SERVO_SINGLECOPTER_1": "3",
+ "SERVO_SINGLECOPTER_2": "4",
+ "SERVO_SINGLECOPTER_3": "5",
+ "SERVO_SINGLECOPTER_4": "6"
+ },
+ "servoProtocolType_e": {
+ "_source": "../../../src/main/drivers/pwm_mapping.h",
+ "SERVO_TYPE_PWM": "0",
+ "SERVO_TYPE_SBUS": "1",
+ "SERVO_TYPE_SBUS_PWM": "2"
+ },
+ "setting_mode_e": {
+ "_source": "../../../src/main/fc/settings.h",
+ "MODE_DIRECT": "(0 << SETTING_MODE_OFFSET)",
+ "MODE_LOOKUP": "(1 << SETTING_MODE_OFFSET)"
+ },
+ "setting_section_e": {
+ "_source": "../../../src/main/fc/settings.h",
+ "MASTER_VALUE": "(0 << SETTING_SECTION_OFFSET)",
+ "PROFILE_VALUE": "(1 << SETTING_SECTION_OFFSET)",
+ "CONTROL_VALUE": "(2 << SETTING_SECTION_OFFSET)",
+ "BATTERY_CONFIG_VALUE": "(3 << SETTING_SECTION_OFFSET)",
+ "MIXER_CONFIG_VALUE": "(4 << SETTING_SECTION_OFFSET)",
+ "EZ_TUNE_VALUE": "(5 << SETTING_SECTION_OFFSET)"
+ },
+ "setting_type_e": {
+ "_source": "../../../src/main/fc/settings.h",
+ "VAR_UINT8": "(0 << SETTING_TYPE_OFFSET)",
+ "VAR_INT8": "(1 << SETTING_TYPE_OFFSET)",
+ "VAR_UINT16": "(2 << SETTING_TYPE_OFFSET)",
+ "VAR_INT16": "(3 << SETTING_TYPE_OFFSET)",
+ "VAR_UINT32": "(4 << SETTING_TYPE_OFFSET)",
+ "VAR_FLOAT": "(5 << SETTING_TYPE_OFFSET)",
+ "VAR_STRING": "(6 << SETTING_TYPE_OFFSET)"
+ },
+ "simATCommandState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_AT_OK": "0",
+ "SIM_AT_ERROR": "1",
+ "SIM_AT_WAITING_FOR_RESPONSE": "2"
+ },
+ "simModuleState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_MODULE_NOT_DETECTED": "0",
+ "SIM_MODULE_NOT_REGISTERED": "1",
+ "SIM_MODULE_REGISTERED": "2"
+ },
+ "simReadState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_READSTATE_RESPONSE": "0",
+ "SIM_READSTATE_SMS": "1",
+ "SIM_READSTATE_SKIP": "2"
+ },
+ "simTelemetryState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_STATE_INIT": "0",
+ "SIM_STATE_INIT2": "1",
+ "SIM_STATE_INIT_ENTER_PIN": "2",
+ "SIM_STATE_SET_MODES": "3",
+ "SIM_STATE_SEND_SMS": "4",
+ "SIM_STATE_SEND_SMS_ENTER_MESSAGE": "5"
+ },
+ "simTransmissionState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_TX_NO": "0",
+ "SIM_TX_FS": "1",
+ "SIM_TX": "2"
+ },
+ "simTxFlags_e": {
+ "_source": "../../../src/main/telemetry/sim.h",
+ "SIM_TX_FLAG": "(1 << 0)",
+ "SIM_TX_FLAG_FAILSAFE": "(1 << 1)",
+ "SIM_TX_FLAG_GPS": "(1 << 2)",
+ "SIM_TX_FLAG_ACC": "(1 << 3)",
+ "SIM_TX_FLAG_LOW_ALT": "(1 << 4)",
+ "SIM_TX_FLAG_RESPONSE": "(1 << 5)"
+ },
+ "simulatorFlags_t": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "HITL_RESET_FLAGS": "(0 << 0)",
+ "HITL_ENABLE": "(1 << 0)",
+ "HITL_SIMULATE_BATTERY": "(1 << 1)",
+ "HITL_MUTE_BEEPER": "(1 << 2)",
+ "HITL_USE_IMU": "(1 << 3)",
+ "HITL_HAS_NEW_GPS_DATA": "(1 << 4)",
+ "HITL_EXT_BATTERY_VOLTAGE": "(1 << 5)",
+ "HITL_AIRSPEED": "(1 << 6)",
+ "HITL_EXTENDED_FLAGS": "(1 << 7)",
+ "HITL_GPS_TIMEOUT": "(1 << 8)",
+ "HITL_PITOT_FAILURE": "(1 << 9)"
+ },
+ "smartAudioVersion_e": {
+ "_source": "../../../src/main/io/vtx_smartaudio.h",
+ "SA_UNKNOWN": "0",
+ "SA_1_0": "1",
+ "SA_2_0": "2",
+ "SA_2_1": "3"
+ },
+ "smartportFuelUnit_e": {
+ "_source": "../../../src/main/telemetry/telemetry.h",
+ "SMARTPORT_FUEL_UNIT_PERCENT": "0",
+ "SMARTPORT_FUEL_UNIT_MAH": "1",
+ "SMARTPORT_FUEL_UNIT_MWH": "2"
+ },
+ "softSerialPortIndex_e": {
+ "_source": "../../../src/main/drivers/serial_softserial.h",
+ "SOFTSERIAL1": "0",
+ "SOFTSERIAL2": "1"
+ },
+ "SPIClockSpeed_e": {
+ "_source": "../../../src/main/drivers/bus_spi.h",
+ "SPI_CLOCK_INITIALIZATON": "0",
+ "SPI_CLOCK_SLOW": "1",
+ "SPI_CLOCK_STANDARD": "2",
+ "SPI_CLOCK_FAST": "3",
+ "SPI_CLOCK_ULTRAFAST": "4"
+ },
+ "Srxl2BindRequest": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "EnterBindMode": "235",
+ "RequestBindStatus": "181",
+ "BoundDataReport": "219",
+ "SetBindInfo": "91"
+ },
+ "Srxl2BindType": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "NotBound": "0",
+ "DSM2_1024_22ms": "1",
+ "DSM2_1024_MC24": "2",
+ "DMS2_2048_11ms": "18",
+ "DMSX_22ms": "162",
+ "DMSX_11ms": "178",
+ "Surface_DSM2_16_5ms": "99",
+ "DSMR_11ms_22ms": "226",
+ "DSMR_5_5ms": "228"
+ },
+ "Srxl2ControlDataCommand": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "ChannelData": "0",
+ "FailsafeChannelData": "1",
+ "VTXData": "2"
+ },
+ "Srxl2DeviceId": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "FlightControllerDefault": "48",
+ "FlightControllerMax": "63",
+ "Broadcast": "255"
+ },
+ "Srxl2DeviceType": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "NoDevice": "0",
+ "RemoteReceiver": "1",
+ "Receiver": "2",
+ "FlightController": "3",
+ "ESC": "4",
+ "Reserved": "5",
+ "SRXLServo": "6",
+ "SRXLServo_2": "7",
+ "VTX": "8"
+ },
+ "Srxl2PacketType": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "Handshake": "33",
+ "BindInfo": "65",
+ "ParameterConfiguration": "80",
+ "SignalQuality": "85",
+ "TelemetrySensorData": "128",
+ "ControlData": "205"
+ },
+ "Srxl2State": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "Disabled": "0",
+ "ListenForActivity": "1",
+ "SendHandshake": "2",
+ "ListenForHandshake": "3",
+ "Running": "4"
+ },
+ "stateFlags_t": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "GPS_FIX_HOME": "(1 << 0)",
+ "GPS_FIX": "(1 << 1)",
+ "CALIBRATE_MAG": "(1 << 2)",
+ "SMALL_ANGLE": "(1 << 3)",
+ "FIXED_WING_LEGACY": "(1 << 4)",
+ "ANTI_WINDUP": "(1 << 5)",
+ "FLAPERON_AVAILABLE": "(1 << 6)",
+ "NAV_MOTOR_STOP_OR_IDLE": "(1 << 7)",
+ "COMPASS_CALIBRATED": "(1 << 8)",
+ "ACCELEROMETER_CALIBRATED": "(1 << 9)",
+ "GPS_ESTIMATED_FIX": [
+ "(1 << 10)",
+ "USE_GPS_FIX_ESTIMATION"
+ ],
+ "NAV_CRUISE_BRAKING": "(1 << 11)",
+ "NAV_CRUISE_BRAKING_BOOST": "(1 << 12)",
+ "NAV_CRUISE_BRAKING_LOCKED": "(1 << 13)",
+ "NAV_EXTRA_ARMING_SAFETY_BYPASSED": "(1 << 14)",
+ "AIRMODE_ACTIVE": "(1 << 15)",
+ "ESC_SENSOR_ENABLED": "(1 << 16)",
+ "AIRPLANE": "(1 << 17)",
+ "MULTIROTOR": "(1 << 18)",
+ "ROVER": "(1 << 19)",
+ "BOAT": "(1 << 20)",
+ "ALTITUDE_CONTROL": "(1 << 21)",
+ "MOVE_FORWARD_ONLY": "(1 << 22)",
+ "SET_REVERSIBLE_MOTORS_FORWARD": "(1 << 23)",
+ "FW_HEADING_USE_YAW": "(1 << 24)",
+ "ANTI_WINDUP_DEACTIVATED": "(1 << 25)",
+ "LANDING_DETECTED": "(1 << 26)",
+ "IN_FLIGHT_EMERG_REARM": "(1 << 27)",
+ "TAILSITTER": "(1 << 28)"
+ },
+ "stickPositions_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "ROL_LO": "(1 << (2 * ROLL))",
+ "ROL_CE": "(3 << (2 * ROLL))",
+ "ROL_HI": "(2 << (2 * ROLL))",
+ "PIT_LO": "(1 << (2 * PITCH))",
+ "PIT_CE": "(3 << (2 * PITCH))",
+ "PIT_HI": "(2 << (2 * PITCH))",
+ "YAW_LO": "(1 << (2 * YAW))",
+ "YAW_CE": "(3 << (2 * YAW))",
+ "YAW_HI": "(2 << (2 * YAW))",
+ "THR_LO": "(1 << (2 * THROTTLE))",
+ "THR_CE": "(3 << (2 * THROTTLE))",
+ "THR_HI": "(2 << (2 * THROTTLE))"
+ },
+ "systemState_e": {
+ "_source": "../../../src/main/fc/fc_init.h",
+ "SYSTEM_STATE_INITIALISING": "0",
+ "SYSTEM_STATE_CONFIG_LOADED": "(1 << 0)",
+ "SYSTEM_STATE_SENSORS_READY": "(1 << 1)",
+ "SYSTEM_STATE_MOTORS_READY": "(1 << 2)",
+ "SYSTEM_STATE_TRANSPONDER_ENABLED": "(1 << 3)",
+ "SYSTEM_STATE_READY": "(1 << 7)"
+ },
+ "tchDmaState_e": {
+ "_source": "../../../src/main/drivers/timer.h",
+ "TCH_DMA_IDLE": "0",
+ "TCH_DMA_READY": "1",
+ "TCH_DMA_ACTIVE": "2"
+ },
+ "tempSensorType_e": {
+ "_source": "../../../src/main/sensors/temperature.h",
+ "TEMP_SENSOR_NONE": "0",
+ "TEMP_SENSOR_LM75": "1",
+ "TEMP_SENSOR_DS18B20": "2"
+ },
+ "throttleStatus_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "THROTTLE_LOW": "0",
+ "THROTTLE_HIGH": "1"
+ },
+ "throttleStatusType_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "THROTTLE_STATUS_TYPE_RC": "0",
+ "THROTTLE_STATUS_TYPE_COMMAND": "1"
+ },
+ "timerMode_e": {
+ "_source": "../../../src/main/drivers/serial_softserial.c",
+ "TIMER_MODE_SINGLE": "0",
+ "TIMER_MODE_DUAL": "1"
+ },
+ "timerUsageFlag_e": {
+ "_source": "../../../src/main/drivers/timer.h",
+ "TIM_USE_ANY": "0",
+ "TIM_USE_PPM": "(1 << 0)",
+ "TIM_USE_PWM": "(1 << 1)",
+ "TIM_USE_MOTOR": "(1 << 2)",
+ "TIM_USE_SERVO": "(1 << 3)",
+ "TIM_USE_MC_CHNFW": "(1 << 4)",
+ "TIM_USE_LED": "(1 << 24)",
+ "TIM_USE_BEEPER": "(1 << 25)"
+ },
+ "timId_e": {
+ "_source": "../../../src/main/io/ledstrip.c",
+ "timBlink": "0",
+ "timLarson": "1",
+ "timBattery": "2",
+ "timRssi": "3",
+ "timGps": [
+ "(4)",
+ "USE_GPS"
+ ],
+ "timWarning": "5",
+ "timIndicator": "6",
+ "timAnimation": [
+ "(7)",
+ "USE_LED_ANIMATION"
+ ],
+ "timRing": "8",
+ "timTimerCount": "9"
+ },
+ "tristate_e": {
+ "_source": "../../../src/main/common/tristate.h",
+ "TRISTATE_AUTO": "0",
+ "TRISTATE_ON": "1",
+ "TRISTATE_OFF": "2"
+ },
+ "tz_automatic_dst_e": {
+ "_source": "../../../src/main/common/time.h",
+ "TZ_AUTO_DST_OFF": "0",
+ "TZ_AUTO_DST_EU": "1",
+ "TZ_AUTO_DST_USA": "2"
+ },
+ "UARTDevice_e": {
+ "_source": "../../../src/main/drivers/serial_uart.h",
+ "UARTDEV_1": "0",
+ "UARTDEV_2": "1",
+ "UARTDEV_3": "2",
+ "UARTDEV_4": "3",
+ "UARTDEV_5": "4",
+ "UARTDEV_6": "5",
+ "UARTDEV_7": "6",
+ "UARTDEV_8": "7",
+ "UARTDEV_MAX": "8"
+ },
+ "uartInverterLine_e": {
+ "_source": "../../../src/main/drivers/uart_inverter.h",
+ "UART_INVERTER_LINE_NONE": "0",
+ "UART_INVERTER_LINE_RX": "1 << 0",
+ "UART_INVERTER_LINE_TX": "1 << 1"
+ },
+ "ublox_nav_sig_health_e": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "UBLOX_SIG_HEALTH_UNKNOWN": "0",
+ "UBLOX_SIG_HEALTH_HEALTHY": "1",
+ "UBLOX_SIG_HEALTH_UNHEALTHY": "2"
+ },
+ "ublox_nav_sig_quality": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "UBLOX_SIG_QUALITY_NOSIGNAL": "0",
+ "UBLOX_SIG_QUALITY_SEARCHING": "1",
+ "UBLOX_SIG_QUALITY_ACQUIRED": "2",
+ "UBLOX_SIG_QUALITY_UNUSABLE": "3",
+ "UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC": "4",
+ "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC": "5",
+ "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC2": "6",
+ "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC3": "7"
+ },
+ "ubs_nav_fix_type_t": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "FIX_NONE": "0",
+ "FIX_DEAD_RECKONING": "1",
+ "FIX_2D": "2",
+ "FIX_3D": "3",
+ "FIX_GPS_DEAD_RECKONING": "4",
+ "FIX_TIME": "5"
+ },
+ "ubx_ack_state_t": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "UBX_ACK_WAITING": "0",
+ "UBX_ACK_GOT_ACK": "1",
+ "UBX_ACK_GOT_NAK": "2"
+ },
+ "ubx_nav_status_bits_t": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "NAV_STATUS_FIX_VALID": "1"
+ },
+ "ubx_protocol_bytes_t": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "PREAMBLE1": "181",
+ "PREAMBLE2": "98",
+ "CLASS_NAV": "1",
+ "CLASS_ACK": "5",
+ "CLASS_CFG": "6",
+ "CLASS_MON": "10",
+ "MSG_CLASS_UBX": "1",
+ "MSG_CLASS_NMEA": "240",
+ "MSG_VER": "4",
+ "MSG_ACK_NACK": "0",
+ "MSG_ACK_ACK": "1",
+ "MSG_NMEA_GGA": "0",
+ "MSG_NMEA_GLL": "1",
+ "MSG_NMEA_GSA": "2",
+ "MSG_NMEA_GSV": "3",
+ "MSG_NMEA_RMC": "4",
+ "MSG_NMEA_VGS": "5",
+ "MSG_POSLLH": "2",
+ "MSG_STATUS": "3",
+ "MSG_SOL": "6",
+ "MSG_PVT": "7",
+ "MSG_VELNED": "18",
+ "MSG_TIMEUTC": "33",
+ "MSG_SVINFO": "48",
+ "MSG_NAV_SAT": "53",
+ "MSG_CFG_PRT": "0",
+ "MSG_CFG_RATE": "8",
+ "MSG_CFG_SET_RATE": "1",
+ "MSG_CFG_NAV_SETTINGS": "36",
+ "MSG_CFG_SBAS": "22",
+ "MSG_CFG_GNSS": "62",
+ "MSG_MON_GNSS": "40",
+ "MSG_NAV_SIG": "67"
+ },
+ "vcselPeriodType_e": {
+ "_source": "../../../src/main/drivers/rangefinder/rangefinder_vl53l0x.c",
+ "VcselPeriodPreRange": "0",
+ "VcselPeriodFinalRange": "1"
+ },
+ "videoSystem_e": {
+ "_source": "../../../src/main/drivers/osd.h",
+ "VIDEO_SYSTEM_AUTO": "0",
+ "VIDEO_SYSTEM_PAL": "1",
+ "VIDEO_SYSTEM_NTSC": "2",
+ "VIDEO_SYSTEM_HDZERO": "3",
+ "VIDEO_SYSTEM_DJIWTF": "4",
+ "VIDEO_SYSTEM_AVATAR": "5",
+ "VIDEO_SYSTEM_DJICOMPAT": "6",
+ "VIDEO_SYSTEM_DJICOMPAT_HD": "7",
+ "VIDEO_SYSTEM_DJI_NATIVE": "8"
+ },
+ "voltageSensor_e": {
+ "_source": "../../../src/main/sensors/battery_config_structs.h",
+ "VOLTAGE_SENSOR_NONE": "0",
+ "VOLTAGE_SENSOR_ADC": "1",
+ "VOLTAGE_SENSOR_ESC": "2",
+ "VOLTAGE_SENSOR_FAKE": "3",
+ "VOLTAGE_SENSOR_SMARTPORT": "4",
+ "VOLTAGE_SENSOR_MAX": "VOLTAGE_SENSOR_SMARTPORT"
+ },
+ "vs600Band_e": {
+ "_source": "../../../src/main/io/smartport_master.h",
+ "VS600_BAND_A": "0",
+ "VS600_BAND_B": "1",
+ "VS600_BAND_C": "2",
+ "VS600_BAND_D": "3",
+ "VS600_BAND_E": "4",
+ "VS600_BAND_F": "5"
+ },
+ "vs600Power_e": {
+ "_source": "../../../src/main/io/smartport_master.h",
+ "VS600_POWER_PIT": "0",
+ "VS600_POWER_25MW": "1",
+ "VS600_POWER_200MW": "2",
+ "VS600_POWER_600MW": "3"
+ },
+ "vtxDevType_e": {
+ "_source": "../../../src/main/drivers/vtx_common.h",
+ "VTXDEV_UNSUPPORTED": "0",
+ "VTXDEV_RTC6705": "1",
+ "VTXDEV_SMARTAUDIO": "3",
+ "VTXDEV_TRAMP": "4",
+ "VTXDEV_FFPV": "5",
+ "VTXDEV_MSP": "6",
+ "VTXDEV_UNKNOWN": "255"
+ },
+ "vtxFrequencyGroups_e": {
+ "_source": "../../../src/main/drivers/vtx_common.h",
+ "FREQUENCYGROUP_5G8": "0",
+ "FREQUENCYGROUP_2G4": "1",
+ "FREQUENCYGROUP_1G3": "2"
+ },
+ "vtxLowerPowerDisarm_e": {
+ "_source": "../../../src/main/io/vtx.h",
+ "VTX_LOW_POWER_DISARM_OFF": "0",
+ "VTX_LOW_POWER_DISARM_ALWAYS": "1",
+ "VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM": "2"
+ },
+ "vtxProtoResponseType_e": {
+ "_source": "../../../src/main/io/vtx_tramp.c",
+ "VTX_RESPONSE_TYPE_NONE": "0",
+ "VTX_RESPONSE_TYPE_CAPABILITIES": "1",
+ "VTX_RESPONSE_TYPE_STATUS": "2"
+ },
+ "vtxProtoState_e": {
+ "_source": "../../../src/main/io/vtx_tramp.c",
+ "VTX_STATE_RESET": "0",
+ "VTX_STATE_OFFILE": "1",
+ "VTX_STATE_DETECTING": "2",
+ "VTX_STATE_IDLE": "3",
+ "VTX_STATE_QUERY_DELAY": "4",
+ "VTX_STATE_QUERY_STATUS": "5",
+ "VTX_STATE_WAIT_STATUS": "6"
+ },
+ "vtxScheduleParams_e": {
+ "_source": "../../../src/main/io/vtx.c",
+ "VTX_PARAM_POWER": "0",
+ "VTX_PARAM_BANDCHAN": "1",
+ "VTX_PARAM_PITMODE": "2",
+ "VTX_PARAM_COUNT": "3"
+ },
+ "warningFlags_e": {
+ "_source": "../../../src/main/io/ledstrip.c",
+ "WARNING_ARMING_DISABLED": "0",
+ "WARNING_LOW_BATTERY": "1",
+ "WARNING_FAILSAFE": "2",
+ "WARNING_HW_ERROR": "3"
+ },
+ "warningLedState_e": {
+ "_source": "../../../src/main/io/statusindicator.c",
+ "WARNING_LED_OFF": "0",
+ "WARNING_LED_ON": "1",
+ "WARNING_LED_FLASH": "2"
+ },
+ "widgetAHIOptions_t": {
+ "_source": "../../../src/main/drivers/display_widgets.h",
+ "DISPLAY_WIDGET_AHI_OPTION_SHOW_CORNERS": "1 << 0"
+ },
+ "widgetAHIStyle_e": {
+ "_source": "../../../src/main/drivers/display_widgets.h",
+ "DISPLAY_WIDGET_AHI_STYLE_STAIRCASE": "0",
+ "DISPLAY_WIDGET_AHI_STYLE_LINE": "1"
+ },
+ "wpFwTurnSmoothing_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "WP_TURN_SMOOTHING_OFF": "0",
+ "WP_TURN_SMOOTHING_ON": "1",
+ "WP_TURN_SMOOTHING_CUT": "2"
+ },
+ "wpMissionPlannerStatus_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "WP_PLAN_WAIT": "0",
+ "WP_PLAN_SAVE": "1",
+ "WP_PLAN_OK": "2",
+ "WP_PLAN_FULL": "3"
+ },
+ "zeroCalibrationState_e": {
+ "_source": "../../../src/main/common/calibration.h",
+ "ZERO_CALIBRATION_NONE": "0",
+ "ZERO_CALIBRATION_IN_PROGRESS": "1",
+ "ZERO_CALIBRATION_DONE": "2",
+ "ZERO_CALIBRATION_FAIL": "3"
+ }
+}
\ No newline at end of file
diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum
index f90eaa7b1bf..2378484b4c5 100644
--- a/docs/development/msp/msp_messages.checksum
+++ b/docs/development/msp/msp_messages.checksum
@@ -1 +1 @@
-7601652331e47d41941de8efdcb0c1e7
+57e31d0fb1ead3ea8330d1abf34ee0ac
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index db8dbe22833..53abae82833 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -10852,6 +10852,32 @@
"notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 5 bytes. Returns error if index is outside `MAX_GLOBAL_VARIABLES`.",
"description": "Sets the specified Global Variable (GVAR) to the provided value."
},
+ "MSP2_INAV_SET_ALT_TARGET": {
+ "code": 8725,
+ "mspv": 2,
+ "request": {
+ "payload": [
+ {
+ "name": "altitudeDatum",
+ "ctype": "uint8_t",
+ "desc": "Altitude reference datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (not implemented yet)",
+ "units": "",
+ "enum": "geoAltitudeDatumFlag_e"
+ },
+ {
+ "name": "altitudeTarget",
+ "ctype": "int32_t",
+ "desc": "Desired altitude target according to reference datum",
+ "units": "cm"
+ }
+ ]
+ },
+ "reply": {
+ "payload": null
+ },
+ "notes": "Set new altitude target. Requires 5-byte payload (datum + target) and is set-only. Valid only in NAV or ALTHOLD modes. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected).",
+ "description": "Set the active altitude hold target using updateClimbRateToAltitudeController."
+ },
"MSP2_INAV_FULL_LOCAL_POSE": {
"code": 8736,
"mspv": 2,
diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md
index f0f3b800357..636de872f9b 100644
--- a/docs/development/msp/msp_ref.md
+++ b/docs/development/msp/msp_ref.md
@@ -10,7 +10,7 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
For current generation code, see [documentation project](https://github.com/xznhj8129/msp_documentation) (temporary until official implementation)
-**JSON file rev: 3
+**JSON file rev: 4
**
**Warning: Verification needed, exercise caution until completely verified for accuracy and cleared, especially for integer signs. Source-based generation/validation is forthcoming. Refer to source for absolute certainty**
@@ -413,7 +413,7 @@ For current generation code, see [documentation project](https://github.com/xznh
[8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex)
[8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex)
[8724 - MSP2_INAV_SET_GVAR](#msp2_inav_set_gvar)
-[8725 - MSP2_INAV_ALT_TARGET](#msp2_inav_alt_target)
+[8725 - MSP2_INAV_SET_ALT_TARGET](#msp2_inav_set_alt_target)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
@@ -4495,25 +4495,21 @@ For current generation code, see [documentation project](https://github.com/xznh
**Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).
-## `MSP2_INAV_ALT_TARGET (8725 / 0x2215)`
-**Description:** Get or set the active altitude hold target using updateClimbRateToAltitudeController.
-#### Variant: `get`
-
-**Description:** Get current altitude target
-
-**Request Payload:** **None**
+## `MSP2_INAV_SET_GVAR (8724 / 0x2214)`
+**Description:** Sets the specified Global Variable (GVAR) to the provided value.
-**Reply Payload:**
+**Request Payload:**
|Field|C Type|Size (Bytes)|Units|Description|
|---|---|---|---|---|
-| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Default internal reference altitude datum `NAV_WP_TAKEOFF_DATUM` |
-| `altitudeTarget` | `int32_t` | 4 | cm | Current altitude target (`posControl.desiredState.pos.z`) |
+| `gvarIndex` | `uint8_t` | 1 | Index | Index of the Global Variable to set |
+| `value` | `int32_t` | 4 | - | New value to store (clamped to configured min/max by `gvSet()`) |
-#### Variant: `set`
+**Reply Payload:** **None**
-**Description:** Set new altitude target
-## `MSP2_INAV_SET_GVAR (8724 / 0x2214)`
-**Description:** Sets the specified Global Variable (GVAR) to the provided value.
+**Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 5 bytes. Returns error if index is outside `MAX_GLOBAL_VARIABLES`.
+
+## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)`
+**Description:** Set the active altitude hold target using updateClimbRateToAltitudeController.
**Request Payload:**
|Field|C Type|Size (Bytes)|Units|Description|
@@ -4523,14 +4519,7 @@ For current generation code, see [documentation project](https://github.com/xznh
**Reply Payload:** **None**
-
-**Notes:** Empty request payload returns the current altitude target with datum. Sending a 5-byte payload sets a new target: 1 byte datum, 4 bytes altitude. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected).
-| `gvarIndex` | `uint8_t` | 1 | Index | Index of the Global Variable to set |
-| `value` | `int32_t` | 4 | - | New value to store (clamped to configured min/max by `gvSet()`) |
-
-**Reply Payload:** **None**
-
-**Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 5 bytes. Returns error if index is outside `MAX_GLOBAL_VARIABLES`.
+**Notes:** Set new altitude target. Requires 5-byte payload (datum + target) and is set-only. Valid only in NAV or ALTHOLD modes. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected).
## `MSP2_INAV_FULL_LOCAL_POSE (8736 / 0x2220)`
**Description:** Provides estimates of current attitude, local NEU position, and velocity.
diff --git a/docs/development/msp/rev b/docs/development/msp/rev
index 00750edc07d..b8626c4cff2 100644
--- a/docs/development/msp/rev
+++ b/docs/development/msp/rev
@@ -1 +1 @@
-3
+4
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index c5a3dfb6222..70a76f7e19d 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -4130,31 +4130,19 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
#endif
#ifdef USE_BARO
- case MSP2_INAV_ALT_TARGET:
- {
- if (dataSize == 0) {
- sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM);
- sbufWriteU32(dst, (uint32_t)lrintf(posControl.desiredState.pos.z));
- *ret = MSP_RESULT_ACK;
- break;
- }
-
+ case MSP2_INAV_SET_ALT_TARGET:
if (dataSize != (sizeof(int32_t) + sizeof(uint8_t))) {
*ret = MSP_RESULT_ERROR;
break;
}
- const uint8_t datumFlag = sbufReadU8(src);
- const int32_t targetAltitudeCm = (int32_t)sbufReadU32(src);
-
- if (!navigationSetAltitudeTargetWithDatum((geoAltitudeDatumFlag_e)datumFlag, targetAltitudeCm)) {
- *ret = MSP_RESULT_ERROR;
+ if (navigationSetAltitudeTargetWithDatum((geoAltitudeDatumFlag_e)sbufReadU8(src), (int32_t)sbufReadU32(src))) {
+ *ret = MSP_RESULT_ACK;
break;
}
- *ret = MSP_RESULT_ACK;
+ *ret = MSP_RESULT_ERROR;
break;
- }
#endif
#ifdef USE_SIMULATOR
diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h
index e0827c4392b..b021a8850ce 100755
--- a/src/main/msp/msp_protocol_v2_inav.h
+++ b/src/main/msp/msp_protocol_v2_inav.h
@@ -124,6 +124,6 @@
#define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213
#define MSP2_INAV_SET_GVAR 0x2214
-#define MSP2_INAV_ALT_TARGET 0x2215
+#define MSP2_INAV_SET_ALT_TARGET 0x2215
#define MSP2_INAV_FULL_LOCAL_POSE 0x2220
From fff841622318eaa61f09775868b0b6dbb33228d2 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Mon, 5 Jan 2026 10:51:01 -0500
Subject: [PATCH 10/11] fix bracket error
---
src/main/telemetry/mavlink.c | 79 ++++++++++++++++++------------------
1 file changed, 40 insertions(+), 39 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 13e6c0344b7..60f6aed67c3 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1215,6 +1215,46 @@ static bool handleIncoming_COMMAND_INT(void)
mavlinkSendMessage();
}
} else {
+#ifdef USE_BARO
+ if (msg.command == MAV_CMD_DO_CHANGE_ALTITUDE) {
+ const float altitudeMeters = msg.param1;
+ const uint8_t frame = (uint8_t)msg.frame;
+
+ geoAltitudeDatumFlag_e datum;
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ case MAV_FRAME_GLOBAL_INT:
+ datum = NAV_WP_MSL_DATUM;
+ break;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ datum = NAV_WP_TAKEOFF_DATUM;
+ break;
+ default:
+ mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ msg.command,
+ MAV_RESULT_UNSUPPORTED,
+ 0,
+ 0,
+ mavRecvMsg.sysid,
+ mavRecvMsg.compid);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
+ const bool accepted = navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm);
+ mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ msg.command,
+ accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED,
+ 0,
+ 0,
+ mavRecvMsg.sysid,
+ mavRecvMsg.compid);
+ mavlinkSendMessage();
+ return true;
+ }
+#endif
mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
msg.command,
MAV_RESULT_UNSUPPORTED,
@@ -1225,45 +1265,6 @@ static bool handleIncoming_COMMAND_INT(void)
mavlinkSendMessage();
}
return true;
-#ifdef USE_BARO
- } else if (msg.command == MAV_CMD_DO_CHANGE_ALTITUDE) {
- const float altitudeMeters = msg.param1;
- const uint8_t frame = (uint8_t)msg.frame;
-
- geoAltitudeDatumFlag_e datum;
- switch (frame) {
- case MAV_FRAME_GLOBAL:
- case MAV_FRAME_GLOBAL_INT:
- datum = NAV_WP_MSL_DATUM;
- break;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
- datum = NAV_WP_TAKEOFF_DATUM;
- break;
- default:
- mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- msg.command,
- MAV_RESULT_UNSUPPORTED,
- 0,
- 0,
- mavRecvMsg.sysid,
- mavRecvMsg.compid);
- mavlinkSendMessage();
- return true;
- }
-
- const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
- const bool accepted = navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm);
- mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- msg.command,
- accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED,
- 0,
- 0,
- mavRecvMsg.sysid,
- mavRecvMsg.compid);
- mavlinkSendMessage();
- return true;
-#endif
}
return false;
}
From 189d5527e82d01e41570ce66f9b1999ab4fa8968 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 6 Jan 2026 10:16:36 -0500
Subject: [PATCH 11/11] fix missing enums (regex)
---
docs/development/msp/gen_enum_md.py | 2 +-
docs/development/msp/inav_enums.json | 314 +++++++++++++++++++++++
docs/development/msp/inav_enums_ref.md | 342 +++++++++++++++++++++++++
3 files changed, 657 insertions(+), 1 deletion(-)
diff --git a/docs/development/msp/gen_enum_md.py b/docs/development/msp/gen_enum_md.py
index b15c38e67cd..616bd4d7c67 100644
--- a/docs/development/msp/gen_enum_md.py
+++ b/docs/development/msp/gen_enum_md.py
@@ -62,7 +62,7 @@ def is_plain_int_literal(expr: str) -> Optional[int]:
# ---------- Parsing regexes ----------
-RE_ENUM_START = re.compile(r'^\s*typedef\s+enum\s*\{')
+RE_ENUM_START = re.compile(r'^\s*typedef\s+enum(?:\s+[A-Za-z_]\w*)?\s*\{')
RE_ENUM_END = re.compile(r'^\s*\}\s*([A-Za-z_]\w*)\s*;')
RE_LINE_COMMENT = re.compile(r'^\s*//\s*(.+?)\s*$')
diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json
index f3f09b1a803..0ff90f16b2c 100644
--- a/docs/development/msp/inav_enums.json
+++ b/docs/development/msp/inav_enums.json
@@ -34,6 +34,24 @@
"ADC_CHN_MAX": "ADC_CHN_6",
"ADC_CHN_COUNT": ""
},
+ "ADCDevice": {
+ "_source": "../../../src/main/drivers/adc_impl.h",
+ "ADCINVALID": "-1",
+ "ADCDEV_1": "0",
+ "ADCDEV_2": [
+ "(1)",
+ "STM32F4 || STM32F7 || STM32H7"
+ ],
+ "ADCDEV_3": [
+ "(2)",
+ "STM32F4 || STM32F7 || STM32H7"
+ ],
+ "ADCDEV_MAX": [
+ "ADCDEV_1",
+ "NOT(STM32F4 || STM32F7 || STM32H7)"
+ ],
+ "ADCDEV_COUNT": "ADCDEV_MAX + 1"
+ },
"adcFunction_e": {
"_source": "../../../src/main/drivers/adc.h",
"ADC_BATTERY": "0",
@@ -428,6 +446,23 @@
"BLACKBOX_RESERVE_TEMPORARY_FAILURE": "1",
"BLACKBOX_RESERVE_PERMANENT_FAILURE": "2"
},
+ "BlackboxDevice": {
+ "_source": "../../../src/main/blackbox/blackbox_io.h",
+ "BLACKBOX_DEVICE_SERIAL": "0",
+ "BLACKBOX_DEVICE_FLASH": [
+ "1",
+ "USE_FLASHFS"
+ ],
+ "BLACKBOX_DEVICE_SDCARD": [
+ "2",
+ "USE_SDCARD"
+ ],
+ "BLACKBOX_DEVICE_FILE": [
+ "3",
+ "SITL_BUILD"
+ ],
+ "BLACKBOX_DEVICE_END": "4"
+ },
"blackboxFeatureMask_e": {
"_source": "../../../src/main/blackbox/blackbox.h",
"BLACKBOX_FEATURE_NAV_ACC": "1 << 0",
@@ -445,6 +480,21 @@
"BLACKBOX_FEATURE_GYRO_PEAKS_YAW": "1 << 12",
"BLACKBOX_FEATURE_SERVOS": "1 << 13"
},
+ "BlackboxState": {
+ "_source": "../../../src/main/blackbox/blackbox.h",
+ "BLACKBOX_STATE_DISABLED": "0",
+ "BLACKBOX_STATE_STOPPED": "1",
+ "BLACKBOX_STATE_PREPARE_LOG_FILE": "2",
+ "BLACKBOX_STATE_SEND_HEADER": "3",
+ "BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER": "4",
+ "BLACKBOX_STATE_SEND_GPS_H_HEADER": "5",
+ "BLACKBOX_STATE_SEND_GPS_G_HEADER": "6",
+ "BLACKBOX_STATE_SEND_SLOW_HEADER": "7",
+ "BLACKBOX_STATE_SEND_SYSINFO": "8",
+ "BLACKBOX_STATE_PAUSED": "9",
+ "BLACKBOX_STATE_RUNNING": "10",
+ "BLACKBOX_STATE_SHUTTING_DOWN": "11"
+ },
"bmi270Register_e": {
"_source": "../../../src/main/drivers/accgyro/accgyro_bmi270.c",
"BMI270_REG_CHIP_ID": "0",
@@ -806,6 +856,18 @@
"DEVFLAGS_USE_MANUAL_DEVICE_SELECT": "(1 << 1)",
"DEVFLAGS_SPI_MODE_0": "(1 << 2)"
},
+ "disarmReason_t": {
+ "_source": "../../../src/main/fc/fc_core.h",
+ "DISARM_NONE": "0",
+ "DISARM_TIMEOUT": "1",
+ "DISARM_STICKS": "2",
+ "DISARM_SWITCH_3D": "3",
+ "DISARM_SWITCH": "4",
+ "DISARM_FAILSAFE": "6",
+ "DISARM_NAVIGATION": "7",
+ "DISARM_LANDING": "8",
+ "DISARM_REASON_COUNT": "9"
+ },
"displayCanvasBitmapOption_t": {
"_source": "../../../src/main/drivers/display_canvas.h",
"DISPLAY_CANVAS_BITMAP_OPT_INVERT_COLORS": "1 << 0",
@@ -1046,6 +1108,112 @@
"FD_PITCH": "1",
"FD_YAW": "2"
},
+ "FlightLogEvent": {
+ "_source": "../../../src/main/blackbox/blackbox_fielddefs.h",
+ "FLIGHT_LOG_EVENT_SYNC_BEEP": "0",
+ "FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT": "13",
+ "FLIGHT_LOG_EVENT_LOGGING_RESUME": "14",
+ "FLIGHT_LOG_EVENT_FLIGHTMODE": "30",
+ "FLIGHT_LOG_EVENT_IMU_FAILURE": "40",
+ "FLIGHT_LOG_EVENT_LOG_END": "255"
+ },
+ "FlightLogFieldCondition": {
+ "_source": "../../../src/main/blackbox/blackbox_fielddefs.h",
+ "FLIGHT_LOG_FIELD_CONDITION_ALWAYS": "0",
+ "FLIGHT_LOG_FIELD_CONDITION_MOTORS": "1",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1": "2",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2": "3",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3": "4",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4": "5",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5": "6",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6": "7",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7": "8",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8": "9",
+ "FLIGHT_LOG_FIELD_CONDITION_SERVOS": "10",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1": "11",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2": "12",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3": "13",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4": "14",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5": "15",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6": "16",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7": "17",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8": "18",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9": "19",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10": "20",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11": "21",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12": "22",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13": "23",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14": "24",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15": "25",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16": "26",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17": "27",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18": "28",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19": "29",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20": "30",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21": "31",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22": "32",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23": "33",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24": "34",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25": "35",
+ "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26": "36",
+ "FLIGHT_LOG_FIELD_CONDITION_MAG": "37",
+ "FLIGHT_LOG_FIELD_CONDITION_BARO": "38",
+ "FLIGHT_LOG_FIELD_CONDITION_PITOT": "39",
+ "FLIGHT_LOG_FIELD_CONDITION_VBAT": "40",
+ "FLIGHT_LOG_FIELD_CONDITION_AMPERAGE": "41",
+ "FLIGHT_LOG_FIELD_CONDITION_SURFACE": "42",
+ "FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV": "43",
+ "FLIGHT_LOG_FIELD_CONDITION_MC_NAV": "44",
+ "FLIGHT_LOG_FIELD_CONDITION_RSSI": "45",
+ "FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0": "46",
+ "FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1": "47",
+ "FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2": "48",
+ "FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME": "49",
+ "FLIGHT_LOG_FIELD_CONDITION_DEBUG": "50",
+ "FLIGHT_LOG_FIELD_CONDITION_NAV_ACC": "51",
+ "FLIGHT_LOG_FIELD_CONDITION_NAV_POS": "52",
+ "FLIGHT_LOG_FIELD_CONDITION_NAV_PID": "53",
+ "FLIGHT_LOG_FIELD_CONDITION_ACC": "54",
+ "FLIGHT_LOG_FIELD_CONDITION_ATTITUDE": "55",
+ "FLIGHT_LOG_FIELD_CONDITION_RC_DATA": "56",
+ "FLIGHT_LOG_FIELD_CONDITION_RC_COMMAND": "57",
+ "FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW": "58",
+ "FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_ROLL": "59",
+ "FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_PITCH": "60",
+ "FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_YAW": "61",
+ "FLIGHT_LOG_FIELD_CONDITION_NEVER": "62",
+ "FLIGHT_LOG_FIELD_CONDITION_FIRST": "FLIGHT_LOG_FIELD_CONDITION_ALWAYS",
+ "FLIGHT_LOG_FIELD_CONDITION_LAST": "FLIGHT_LOG_FIELD_CONDITION_NEVER"
+ },
+ "FlightLogFieldEncoding": {
+ "_source": "../../../src/main/blackbox/blackbox_fielddefs.h",
+ "FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB": "0",
+ "FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB": "1",
+ "FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT": "3",
+ "FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB": "6",
+ "FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32": "7",
+ "FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16": "8",
+ "FLIGHT_LOG_FIELD_ENCODING_NULL": "9"
+ },
+ "FlightLogFieldPredictor": {
+ "_source": "../../../src/main/blackbox/blackbox_fielddefs.h",
+ "FLIGHT_LOG_FIELD_PREDICTOR_0": "0",
+ "FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS": "1",
+ "FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE": "2",
+ "FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2": "3",
+ "FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE": "4",
+ "FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0": "5",
+ "FLIGHT_LOG_FIELD_PREDICTOR_INC": "6",
+ "FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD": "7",
+ "FLIGHT_LOG_FIELD_PREDICTOR_1500": "8",
+ "FLIGHT_LOG_FIELD_PREDICTOR_VBATREF": "9",
+ "FLIGHT_LOG_FIELD_PREDICTOR_LAST_MAIN_FRAME_TIME": "10"
+ },
+ "FlightLogFieldSign": {
+ "_source": "../../../src/main/blackbox/blackbox_fielddefs.h",
+ "FLIGHT_LOG_FIELD_UNSIGNED": "0",
+ "FLIGHT_LOG_FIELD_SIGNED": "1"
+ },
"flightModeFlags_e": {
"_source": "../../../src/main/fc/runtime_config.h",
"ANGLE_MODE": "(1 << 0)",
@@ -1420,6 +1588,19 @@
"HSV_SATURATION": "1",
"HSV_VALUE": "2"
},
+ "I2CDevice": {
+ "_source": "../../../src/main/drivers/bus_i2c.h",
+ "I2CINVALID": "-1",
+ "I2CDEV_EMULATED": "-1",
+ "I2CDEV_1": "0",
+ "I2CDEV_2": "1",
+ "I2CDEV_3": "2",
+ "I2CDEV_4": [
+ "(3)",
+ "USE_I2C_DEVICE_4"
+ ],
+ "I2CDEV_COUNT": "4"
+ },
"I2CSpeed": {
"_source": "../../../src/main/drivers/bus_i2c.h",
"I2C_SPEED_100KHZ": "2",
@@ -1802,6 +1983,18 @@
"LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION": "48",
"LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET": "49"
},
+ "logicOperandType_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_OPERAND_TYPE_VALUE": "0",
+ "LOGIC_CONDITION_OPERAND_TYPE_RC_CHANNEL": "1",
+ "LOGIC_CONDITION_OPERAND_TYPE_FLIGHT": "2",
+ "LOGIC_CONDITION_OPERAND_TYPE_FLIGHT_MODE": "3",
+ "LOGIC_CONDITION_OPERAND_TYPE_LC": "4",
+ "LOGIC_CONDITION_OPERAND_TYPE_GVAR": "5",
+ "LOGIC_CONDITION_OPERAND_TYPE_PID": "6",
+ "LOGIC_CONDITION_OPERAND_TYPE_WAYPOINTS": "7",
+ "LOGIC_CONDITION_OPERAND_TYPE_LAST": "8"
+ },
"logicOperation_e": {
"_source": "../../../src/main/programming/logic_condition.h",
"LOGIC_CONDITION_TRUE": "0",
@@ -2868,6 +3061,29 @@
"PT_ACTIVE_ID": "0",
"PT_INACTIVE_ID": "1"
},
+ "portMode_t": {
+ "_source": "../../../src/main/drivers/serial.h",
+ "MODE_RX": "1 << 0",
+ "MODE_TX": "1 << 1",
+ "MODE_RXTX": "MODE_RX | MODE_TX"
+ },
+ "portOptions_t": {
+ "_source": "../../../src/main/drivers/serial.h",
+ "SERIAL_NOT_INVERTED": "0 << 0",
+ "SERIAL_INVERTED": "1 << 0",
+ "SERIAL_STOPBITS_1": "0 << 1",
+ "SERIAL_STOPBITS_2": "1 << 1",
+ "SERIAL_PARITY_NO": "0 << 2",
+ "SERIAL_PARITY_EVEN": "1 << 2",
+ "SERIAL_UNIDIR": "0 << 3",
+ "SERIAL_BIDIR": "1 << 3",
+ "SERIAL_BIDIR_OD": "0 << 4",
+ "SERIAL_BIDIR_PP": "1 << 4",
+ "SERIAL_BIDIR_NOPULL": "1 << 5",
+ "SERIAL_BIDIR_UP": "0 << 5",
+ "SERIAL_LONGSTOP": "0 << 6",
+ "SERIAL_SHORTSTOP": "1 << 6"
+ },
"portSharing_e": {
"_source": "../../../src/main/io/serial.h",
"PORTSHARING_UNUSED": "0",
@@ -2905,6 +3121,11 @@
"QUADSPI_CLOCK_FAST": "3",
"QUADSPI_CLOCK_ULTRAFAST": "1"
},
+ "QUADSPIDevice": {
+ "_source": "../../../src/main/drivers/bus_quadspi.h",
+ "QUADSPIINVALID": "-1",
+ "QUADSPIDEV_1": "0"
+ },
"quadSpiMode_e": {
"_source": "../../../src/main/drivers/bus_quadspi.h",
"QUADSPI_MODE_BK1_ONLY": "0",
@@ -2926,6 +3147,91 @@
"RANGEFINDER_USD1_V0": "10",
"RANGEFINDER_NANORADAR": "11"
},
+ "rc_alias_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "ROLL": "0",
+ "PITCH": "1",
+ "YAW": "2",
+ "THROTTLE": "3",
+ "AUX1": "4",
+ "AUX2": "5",
+ "AUX3": "6",
+ "AUX4": "7",
+ "AUX5": "8",
+ "AUX6": "9",
+ "AUX7": "10",
+ "AUX8": "11",
+ "AUX9": "12",
+ "AUX10": "13",
+ "AUX11": "14",
+ "AUX12": "15",
+ "AUX13": "16",
+ "AUX14": "17",
+ "AUX15": [
+ "(18)",
+ "USE_34CHANNELS"
+ ],
+ "AUX16": [
+ "(19)",
+ "USE_34CHANNELS"
+ ],
+ "AUX17": [
+ "(20)",
+ "USE_34CHANNELS"
+ ],
+ "AUX18": [
+ "(21)",
+ "USE_34CHANNELS"
+ ],
+ "AUX19": [
+ "(22)",
+ "USE_34CHANNELS"
+ ],
+ "AUX20": [
+ "(23)",
+ "USE_34CHANNELS"
+ ],
+ "AUX21": [
+ "(24)",
+ "USE_34CHANNELS"
+ ],
+ "AUX22": [
+ "(25)",
+ "USE_34CHANNELS"
+ ],
+ "AUX23": [
+ "(26)",
+ "USE_34CHANNELS"
+ ],
+ "AUX24": [
+ "(27)",
+ "USE_34CHANNELS"
+ ],
+ "AUX25": [
+ "(28)",
+ "USE_34CHANNELS"
+ ],
+ "AUX26": [
+ "(29)",
+ "USE_34CHANNELS"
+ ],
+ "AUX27": [
+ "(30)",
+ "USE_34CHANNELS"
+ ],
+ "AUX28": [
+ "(31)",
+ "USE_34CHANNELS"
+ ],
+ "AUX29": [
+ "(32)",
+ "USE_34CHANNELS"
+ ],
+ "AUX30": [
+ "(33)",
+ "USE_34CHANNELS"
+ ]
+ },
"RCDEVICE_5key_connection_event_e": {
"_source": "../../../src/main/io/rcdevice.h",
"RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN": "1",
@@ -3406,6 +3712,14 @@
"SPI_CLOCK_FAST": "3",
"SPI_CLOCK_ULTRAFAST": "4"
},
+ "SPIDevice": {
+ "_source": "../../../src/main/drivers/bus_spi.h",
+ "SPIINVALID": "-1",
+ "SPIDEV_1": "0",
+ "SPIDEV_2": "1",
+ "SPIDEV_3": "2",
+ "SPIDEV_4": "3"
+ },
"Srxl2BindRequest": {
"_source": "../../../src/main/rx/srxl2_types.h",
"EnterBindMode": "235",
diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md
index b0941d90897..d258c66d4a7 100644
--- a/docs/development/msp/inav_enums_ref.md
+++ b/docs/development/msp/inav_enums_ref.md
@@ -7,6 +7,7 @@
- [accelerationSensor_e](#enum-accelerationsensor_e)
- [accEvent_t](#enum-accevent_t)
- [adcChannel_e](#enum-adcchannel_e)
+- [ADCDevice](#enum-adcdevice)
- [adcFunction_e](#enum-adcfunction_e)
- [adjustmentFunction_e](#enum-adjustmentfunction_e)
- [adjustmentMode_e](#enum-adjustmentmode_e)
@@ -41,7 +42,9 @@
- [beeperMode_e](#enum-beepermode_e)
- [biquadFilterType_e](#enum-biquadfiltertype_e)
- [blackboxBufferReserveStatus_e](#enum-blackboxbufferreservestatus_e)
+- [BlackboxDevice](#enum-blackboxdevice)
- [blackboxFeatureMask_e](#enum-blackboxfeaturemask_e)
+- [BlackboxState](#enum-blackboxstate)
- [bmi270Register_e](#enum-bmi270register_e)
- [bootLogEventCode_e](#enum-bootlogeventcode_e)
- [bootLogFlags_e](#enum-bootlogflags_e)
@@ -62,6 +65,7 @@
- [currentSensor_e](#enum-currentsensor_e)
- [devHardwareType_e](#enum-devhardwaretype_e)
- [deviceFlags_e](#enum-deviceflags_e)
+- [disarmReason_t](#enum-disarmreason_t)
- [displayCanvasBitmapOption_t](#enum-displaycanvasbitmapoption_t)
- [displayCanvasColor_e](#enum-displaycanvascolor_e)
- [displayCanvasOutlineType_e](#enum-displaycanvasoutlinetype_e)
@@ -89,6 +93,11 @@
- [flashPartitionType_e](#enum-flashpartitiontype_e)
- [flashType_e](#enum-flashtype_e)
- [flight_dynamics_index_t](#enum-flight_dynamics_index_t)
+- [FlightLogEvent](#enum-flightlogevent)
+- [FlightLogFieldCondition](#enum-flightlogfieldcondition)
+- [FlightLogFieldEncoding](#enum-flightlogfieldencoding)
+- [FlightLogFieldPredictor](#enum-flightlogfieldpredictor)
+- [FlightLogFieldSign](#enum-flightlogfieldsign)
- [flightModeFlags_e](#enum-flightmodeflags_e)
- [flightModeForTelemetry_e](#enum-flightmodefortelemetry_e)
- [flyingPlatformType_e](#enum-flyingplatformtype_e)
@@ -133,6 +142,7 @@
- [hottEamAlarm2Flag_e](#enum-hotteamalarm2flag_e)
- [hottState_e](#enum-hottstate_e)
- [hsvColorComponent_e](#enum-hsvcolorcomponent_e)
+- [I2CDevice](#enum-i2cdevice)
- [I2CSpeed](#enum-i2cspeed)
- [i2cState_t](#enum-i2cstate_t)
- [i2cTransferDirection_t](#enum-i2ctransferdirection_t)
@@ -152,6 +162,7 @@
- [logicConditionsGlobalFlags_t](#enum-logicconditionsglobalflags_t)
- [logicFlightModeOperands_e](#enum-logicflightmodeoperands_e)
- [logicFlightOperands_e](#enum-logicflightoperands_e)
+- [logicOperandType_e](#enum-logicoperandtype_e)
- [logicOperation_e](#enum-logicoperation_e)
- [logicWaypointOperands_e](#enum-logicwaypointoperands_e)
- [logTopic_e](#enum-logtopic_e)
@@ -232,12 +243,16 @@
- [pinLabel_e](#enum-pinlabel_e)
- [pitotSensor_e](#enum-pitotsensor_e)
- [pollType_e](#enum-polltype_e)
+- [portMode_t](#enum-portmode_t)
+- [portOptions_t](#enum-portoptions_t)
- [portSharing_e](#enum-portsharing_e)
- [pwmInitError_e](#enum-pwminiterror_e)
- [quadrant_e](#enum-quadrant_e)
- [QUADSPIClockDivider_e](#enum-quadspiclockdivider_e)
+- [QUADSPIDevice](#enum-quadspidevice)
- [quadSpiMode_e](#enum-quadspimode_e)
- [rangefinderType_e](#enum-rangefindertype_e)
+- [rc_alias_e](#enum-rc_alias_e)
- [RCDEVICE_5key_connection_event_e](#enum-rcdevice_5key_connection_event_e)
- [rcdevice_5key_simulation_operation_e](#enum-rcdevice_5key_simulation_operation_e)
- [rcdevice_camera_control_opeation_e](#enum-rcdevice_camera_control_opeation_e)
@@ -289,6 +304,7 @@
- [smartportFuelUnit_e](#enum-smartportfuelunit_e)
- [softSerialPortIndex_e](#enum-softserialportindex_e)
- [SPIClockSpeed_e](#enum-spiclockspeed_e)
+- [SPIDevice](#enum-spidevice)
- [Srxl2BindRequest](#enum-srxl2bindrequest)
- [Srxl2BindType](#enum-srxl2bindtype)
- [Srxl2ControlDataCommand](#enum-srxl2controldatacommand)
@@ -386,6 +402,21 @@
| `ADC_CHN_MAX` | ADC_CHN_6 | |
| `ADC_CHN_COUNT` | | |
+---
+## `ADCDevice`
+
+> Source: ../../../src/main/drivers/adc_impl.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `ADCINVALID` | -1 | |
+| `ADCDEV_1` | 0 | |
+| `ADCDEV_2` | (1) | STM32F4 || STM32F7 || STM32H7 |
+| `ADCDEV_3` | (2) | STM32F4 || STM32F7 || STM32H7 |
+| `ADCDEV_MAX` | ADCDEV_3 | STM32F4 || STM32F7 || STM32H7 |
+| `ADCDEV_MAX` | ADCDEV_1 | NOT(STM32F4 || STM32F7 || STM32H7) |
+| `ADCDEV_COUNT` | ADCDEV_MAX + 1 | |
+
---
## `adcFunction_e`
@@ -920,6 +951,19 @@
| `BLACKBOX_RESERVE_TEMPORARY_FAILURE` | 1 | |
| `BLACKBOX_RESERVE_PERMANENT_FAILURE` | 2 | |
+---
+## `BlackboxDevice`
+
+> Source: ../../../src/main/blackbox/blackbox_io.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `BLACKBOX_DEVICE_SERIAL` | 0 | |
+| `BLACKBOX_DEVICE_FLASH` | 1 | USE_FLASHFS |
+| `BLACKBOX_DEVICE_SDCARD` | 2 | USE_SDCARD |
+| `BLACKBOX_DEVICE_FILE` | 3 | SITL_BUILD |
+| `BLACKBOX_DEVICE_END` | 4 | |
+
---
## `blackboxFeatureMask_e`
@@ -942,6 +986,26 @@
| `BLACKBOX_FEATURE_GYRO_PEAKS_YAW` | 1 << 12 | |
| `BLACKBOX_FEATURE_SERVOS` | 1 << 13 | |
+---
+## `BlackboxState`
+
+> Source: ../../../src/main/blackbox/blackbox.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `BLACKBOX_STATE_DISABLED` | 0 | |
+| `BLACKBOX_STATE_STOPPED` | 1 | |
+| `BLACKBOX_STATE_PREPARE_LOG_FILE` | 2 | |
+| `BLACKBOX_STATE_SEND_HEADER` | 3 | |
+| `BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER` | 4 | |
+| `BLACKBOX_STATE_SEND_GPS_H_HEADER` | 5 | |
+| `BLACKBOX_STATE_SEND_GPS_G_HEADER` | 6 | |
+| `BLACKBOX_STATE_SEND_SLOW_HEADER` | 7 | |
+| `BLACKBOX_STATE_SEND_SYSINFO` | 8 | |
+| `BLACKBOX_STATE_PAUSED` | 9 | |
+| `BLACKBOX_STATE_RUNNING` | 10 | |
+| `BLACKBOX_STATE_SHUTTING_DOWN` | 11 | |
+
---
## `bmi270Register_e`
@@ -1403,6 +1467,23 @@
| `DEVFLAGS_USE_MANUAL_DEVICE_SELECT` | (1 << 1) | |
| `DEVFLAGS_SPI_MODE_0` | (1 << 2) | |
+---
+## `disarmReason_t`
+
+> Source: ../../../src/main/fc/fc_core.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `DISARM_NONE` | 0 | |
+| `DISARM_TIMEOUT` | 1 | |
+| `DISARM_STICKS` | 2 | |
+| `DISARM_SWITCH_3D` | 3 | |
+| `DISARM_SWITCH` | 4 | |
+| `DISARM_FAILSAFE` | 6 | |
+| `DISARM_NAVIGATION` | 7 | |
+| `DISARM_LANDING` | 8 | |
+| `DISARM_REASON_COUNT` | 9 | |
+
---
## `displayCanvasBitmapOption_t`
@@ -1778,6 +1859,137 @@
| `FD_PITCH` | 1 | |
| `FD_YAW` | 2 | |
+---
+## `FlightLogEvent`
+
+> Source: ../../../src/main/blackbox/blackbox_fielddefs.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `FLIGHT_LOG_EVENT_SYNC_BEEP` | 0 | |
+| `FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT` | 13 | |
+| `FLIGHT_LOG_EVENT_LOGGING_RESUME` | 14 | |
+| `FLIGHT_LOG_EVENT_FLIGHTMODE` | 30 | |
+| `FLIGHT_LOG_EVENT_IMU_FAILURE` | 40 | |
+| `FLIGHT_LOG_EVENT_LOG_END` | 255 | |
+
+---
+## `FlightLogFieldCondition`
+
+> Source: ../../../src/main/blackbox/blackbox_fielddefs.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `FLIGHT_LOG_FIELD_CONDITION_ALWAYS` | 0 | |
+| `FLIGHT_LOG_FIELD_CONDITION_MOTORS` | 1 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1` | 2 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2` | 3 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3` | 4 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4` | 5 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5` | 6 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6` | 7 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7` | 8 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8` | 9 | |
+| `FLIGHT_LOG_FIELD_CONDITION_SERVOS` | 10 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1` | 11 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2` | 12 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3` | 13 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4` | 14 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5` | 15 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6` | 16 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7` | 17 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8` | 18 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9` | 19 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10` | 20 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11` | 21 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12` | 22 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13` | 23 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14` | 24 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15` | 25 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16` | 26 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17` | 27 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18` | 28 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19` | 29 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20` | 30 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21` | 31 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22` | 32 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23` | 33 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24` | 34 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25` | 35 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26` | 36 | |
+| `FLIGHT_LOG_FIELD_CONDITION_MAG` | 37 | |
+| `FLIGHT_LOG_FIELD_CONDITION_BARO` | 38 | |
+| `FLIGHT_LOG_FIELD_CONDITION_PITOT` | 39 | |
+| `FLIGHT_LOG_FIELD_CONDITION_VBAT` | 40 | |
+| `FLIGHT_LOG_FIELD_CONDITION_AMPERAGE` | 41 | |
+| `FLIGHT_LOG_FIELD_CONDITION_SURFACE` | 42 | |
+| `FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV` | 43 | |
+| `FLIGHT_LOG_FIELD_CONDITION_MC_NAV` | 44 | |
+| `FLIGHT_LOG_FIELD_CONDITION_RSSI` | 45 | |
+| `FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0` | 46 | |
+| `FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1` | 47 | |
+| `FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2` | 48 | |
+| `FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME` | 49 | |
+| `FLIGHT_LOG_FIELD_CONDITION_DEBUG` | 50 | |
+| `FLIGHT_LOG_FIELD_CONDITION_NAV_ACC` | 51 | |
+| `FLIGHT_LOG_FIELD_CONDITION_NAV_POS` | 52 | |
+| `FLIGHT_LOG_FIELD_CONDITION_NAV_PID` | 53 | |
+| `FLIGHT_LOG_FIELD_CONDITION_ACC` | 54 | |
+| `FLIGHT_LOG_FIELD_CONDITION_ATTITUDE` | 55 | |
+| `FLIGHT_LOG_FIELD_CONDITION_RC_DATA` | 56 | |
+| `FLIGHT_LOG_FIELD_CONDITION_RC_COMMAND` | 57 | |
+| `FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW` | 58 | |
+| `FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_ROLL` | 59 | |
+| `FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_PITCH` | 60 | |
+| `FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_YAW` | 61 | |
+| `FLIGHT_LOG_FIELD_CONDITION_NEVER` | 62 | |
+| `FLIGHT_LOG_FIELD_CONDITION_FIRST` | FLIGHT_LOG_FIELD_CONDITION_ALWAYS | |
+| `FLIGHT_LOG_FIELD_CONDITION_LAST` | FLIGHT_LOG_FIELD_CONDITION_NEVER | |
+
+---
+## `FlightLogFieldEncoding`
+
+> Source: ../../../src/main/blackbox/blackbox_fielddefs.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB` | 0 | |
+| `FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB` | 1 | |
+| `FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT` | 3 | |
+| `FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB` | 6 | |
+| `FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32` | 7 | |
+| `FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16` | 8 | |
+| `FLIGHT_LOG_FIELD_ENCODING_NULL` | 9 | |
+
+---
+## `FlightLogFieldPredictor`
+
+> Source: ../../../src/main/blackbox/blackbox_fielddefs.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `FLIGHT_LOG_FIELD_PREDICTOR_0` | 0 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS` | 1 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE` | 2 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2` | 3 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE` | 4 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0` | 5 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_INC` | 6 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD` | 7 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_1500` | 8 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_VBATREF` | 9 | |
+| `FLIGHT_LOG_FIELD_PREDICTOR_LAST_MAIN_FRAME_TIME` | 10 | |
+
+---
+## `FlightLogFieldSign`
+
+> Source: ../../../src/main/blackbox/blackbox_fielddefs.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `FLIGHT_LOG_FIELD_UNSIGNED` | 0 | |
+| `FLIGHT_LOG_FIELD_SIGNED` | 1 | |
+
---
## `flightModeFlags_e`
@@ -2372,6 +2584,21 @@
| `HSV_SATURATION` | 1 | |
| `HSV_VALUE` | 2 | |
+---
+## `I2CDevice`
+
+> Source: ../../../src/main/drivers/bus_i2c.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `I2CINVALID` | -1 | |
+| `I2CDEV_EMULATED` | -1 | |
+| `I2CDEV_1` | 0 | |
+| `I2CDEV_2` | 1 | |
+| `I2CDEV_3` | 2 | |
+| `I2CDEV_4` | (3) | USE_I2C_DEVICE_4 |
+| `I2CDEV_COUNT` | 4 | |
+
---
## `I2CSpeed`
@@ -2846,6 +3073,23 @@
| `LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION` | 48 | |
| `LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET` | 49 | |
+---
+## `logicOperandType_e`
+
+> Source: ../../../src/main/programming/logic_condition.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `LOGIC_CONDITION_OPERAND_TYPE_VALUE` | 0 | |
+| `LOGIC_CONDITION_OPERAND_TYPE_RC_CHANNEL` | 1 | |
+| `LOGIC_CONDITION_OPERAND_TYPE_FLIGHT` | 2 | |
+| `LOGIC_CONDITION_OPERAND_TYPE_FLIGHT_MODE` | 3 | |
+| `LOGIC_CONDITION_OPERAND_TYPE_LC` | 4 | |
+| `LOGIC_CONDITION_OPERAND_TYPE_GVAR` | 5 | |
+| `LOGIC_CONDITION_OPERAND_TYPE_PID` | 6 | |
+| `LOGIC_CONDITION_OPERAND_TYPE_WAYPOINTS` | 7 | |
+| `LOGIC_CONDITION_OPERAND_TYPE_LAST` | 8 | |
+
---
## `logicOperation_e`
@@ -4303,6 +4547,39 @@
| `PT_ACTIVE_ID` | 0 | |
| `PT_INACTIVE_ID` | 1 | |
+---
+## `portMode_t`
+
+> Source: ../../../src/main/drivers/serial.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `MODE_RX` | 1 << 0 | |
+| `MODE_TX` | 1 << 1 | |
+| `MODE_RXTX` | MODE_RX | MODE_TX | |
+
+---
+## `portOptions_t`
+
+> Source: ../../../src/main/drivers/serial.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `SERIAL_NOT_INVERTED` | 0 << 0 | |
+| `SERIAL_INVERTED` | 1 << 0 | |
+| `SERIAL_STOPBITS_1` | 0 << 1 | |
+| `SERIAL_STOPBITS_2` | 1 << 1 | |
+| `SERIAL_PARITY_NO` | 0 << 2 | |
+| `SERIAL_PARITY_EVEN` | 1 << 2 | |
+| `SERIAL_UNIDIR` | 0 << 3 | |
+| `SERIAL_BIDIR` | 1 << 3 | |
+| `SERIAL_BIDIR_OD` | 0 << 4 | |
+| `SERIAL_BIDIR_PP` | 1 << 4 | |
+| `SERIAL_BIDIR_NOPULL` | 1 << 5 | |
+| `SERIAL_BIDIR_UP` | 0 << 5 | |
+| `SERIAL_LONGSTOP` | 0 << 6 | |
+| `SERIAL_SHORTSTOP` | 1 << 6 | |
+
---
## `portSharing_e`
@@ -4360,6 +4637,16 @@
| `QUADSPI_CLOCK_FAST` | 3 | |
| `QUADSPI_CLOCK_ULTRAFAST` | 1 | |
+---
+## `QUADSPIDevice`
+
+> Source: ../../../src/main/drivers/bus_quadspi.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `QUADSPIINVALID` | -1 | |
+| `QUADSPIDEV_1` | 0 | |
+
---
## `quadSpiMode_e`
@@ -4391,6 +4678,48 @@
| `RANGEFINDER_USD1_V0` | 10 | |
| `RANGEFINDER_NANORADAR` | 11 | |
+---
+## `rc_alias_e`
+
+> Source: ../../../src/main/fc/rc_controls.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `ROLL` | 0 | |
+| `PITCH` | 1 | |
+| `YAW` | 2 | |
+| `THROTTLE` | 3 | |
+| `AUX1` | 4 | |
+| `AUX2` | 5 | |
+| `AUX3` | 6 | |
+| `AUX4` | 7 | |
+| `AUX5` | 8 | |
+| `AUX6` | 9 | |
+| `AUX7` | 10 | |
+| `AUX8` | 11 | |
+| `AUX9` | 12 | |
+| `AUX10` | 13 | |
+| `AUX11` | 14 | |
+| `AUX12` | 15 | |
+| `AUX13` | 16 | |
+| `AUX14` | 17 | |
+| `AUX15` | (18) | USE_34CHANNELS |
+| `AUX16` | (19) | USE_34CHANNELS |
+| `AUX17` | (20) | USE_34CHANNELS |
+| `AUX18` | (21) | USE_34CHANNELS |
+| `AUX19` | (22) | USE_34CHANNELS |
+| `AUX20` | (23) | USE_34CHANNELS |
+| `AUX21` | (24) | USE_34CHANNELS |
+| `AUX22` | (25) | USE_34CHANNELS |
+| `AUX23` | (26) | USE_34CHANNELS |
+| `AUX24` | (27) | USE_34CHANNELS |
+| `AUX25` | (28) | USE_34CHANNELS |
+| `AUX26` | (29) | USE_34CHANNELS |
+| `AUX27` | (30) | USE_34CHANNELS |
+| `AUX28` | (31) | USE_34CHANNELS |
+| `AUX29` | (32) | USE_34CHANNELS |
+| `AUX30` | (33) | USE_34CHANNELS |
+
---
## `RCDEVICE_5key_connection_event_e`
@@ -5132,6 +5461,19 @@
| `SPI_CLOCK_FAST` | 3 | |
| `SPI_CLOCK_ULTRAFAST` | 4 | |
+---
+## `SPIDevice`
+
+> Source: ../../../src/main/drivers/bus_spi.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `SPIINVALID` | -1 | |
+| `SPIDEV_1` | 0 | |
+| `SPIDEV_2` | 1 | |
+| `SPIDEV_3` | 2 | |
+| `SPIDEV_4` | 3 | |
+
---
## `Srxl2BindRequest`