From bebd887e3bd6451d325733864d8ff8d0efc22625 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 17 Dec 2025 11:50:13 -0500
Subject: [PATCH] 8226 deprecated, enum parse fix, enums json
---
docs/development/msp/format.md | 2 +-
docs/development/msp/gen_enum_md.py | 5 +-
docs/development/msp/inav_enums.json | 4128 ++++++++++++++++++++
docs/development/msp/inav_enums_ref.md | 342 ++
docs/development/msp/msp_messages.checksum | 2 +-
docs/development/msp/msp_messages.json | 5 +-
docs/development/msp/msp_ref.md | 9 +-
docs/development/msp/original_msp_ref.md | 3514 -----------------
docs/development/msp/rev | 2 +-
9 files changed, 4484 insertions(+), 3525 deletions(-)
create mode 100644 docs/development/msp/inav_enums.json
delete mode 100644 docs/development/msp/original_msp_ref.md
diff --git a/docs/development/msp/format.md b/docs/development/msp/format.md
index 7349b11ad7c..e8c6a348c07 100644
--- a/docs/development/msp/format.md
+++ b/docs/development/msp/format.md
@@ -39,7 +39,7 @@
**reply**: null or dict of data received\
**variable_len**: Optional boolean, if true, message does not have a predefined fixed length and needs appropriate handling\
**variants**: Optional special case, message has different cases of reply/request. Key/description is not a strict expression or code; just a readable condition\
-**not_implemented**: Optional special case, message is not implemented\
+**not_implemented**: Optional special case, message is not implemented (never or deprecated)\
**notes**: String with details of message
## Data dict fields:
diff --git a/docs/development/msp/gen_enum_md.py b/docs/development/msp/gen_enum_md.py
index b15c38e67cd..64e8d66f756 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*$')
@@ -273,6 +273,9 @@ def render_markdown(enums: List[EnumDef]) -> str:
cond = it.cond
out.append(f"| {name_md} | {val} | {cond} |")
jsonfile[e.name][name_md.strip('`')] = [val, cond] if len(cond)>0 else val
+ # normalize source to a stable inav/src/... path
+ if '_source' in jsonfile[e.name]:
+ jsonfile[e.name]['_source'] = jsonfile[e.name]['_source'].replace('../../../src', 'inav/src')
out.append("")
# While we're at it, chuck this all into a JSON file
Path("inav_enums.json").write_text(json.dumps(jsonfile,indent=4), encoding="utf-8")
diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json
new file mode 100644
index 00000000000..ebd1fba018a
--- /dev/null
+++ b/docs/development/msp/inav_enums.json
@@ -0,0 +1,4128 @@
+{
+ "accelerationSensor_e": {
+ "_source": "inav/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": "inav/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": "inav/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": ""
+ },
+ "ADCDevice": {
+ "_source": "inav/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": "inav/src/main/drivers/adc.h",
+ "ADC_BATTERY": "0",
+ "ADC_RSSI": "1",
+ "ADC_CURRENT": "2",
+ "ADC_AIRSPEED": "3",
+ "ADC_FUNCTION_COUNT": "4"
+ },
+ "adjustmentFunction_e": {
+ "_source": "inav/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": "inav/src/main/fc/rc_adjustments.h",
+ "ADJUSTMENT_MODE_STEP": "0",
+ "ADJUSTMENT_MODE_SELECT": "1"
+ },
+ "afatfsAppendFreeClusterPhase_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_DELETE_FILE_DELETE_DIRECTORY_ENTRY": "0",
+ "AFATFS_DELETE_FILE_DEALLOCATE_CLUSTERS": "1"
+ },
+ "afatfsError_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_OPERATION_IN_PROGRESS": "0",
+ "AFATFS_OPERATION_SUCCESS": "1",
+ "AFATFS_OPERATION_FAILURE": "2"
+ },
+ "afatfsSaveDirectoryEntryMode_e": {
+ "_source": "inav/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": "inav/src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_SEEK_SET": "0",
+ "AFATFS_SEEK_CUR": "1",
+ "AFATFS_SEEK_END": "2"
+ },
+ "afatfsTruncateFilePhase_e": {
+ "_source": "inav/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": "inav/src/main/fc/rc_controls.h",
+ "STICK_CENTER": "0",
+ "THROTTLE_THRESHOLD": "1",
+ "STICK_CENTER_ONCE": "2"
+ },
+ "angle_index_t": {
+ "_source": "inav/src/main/common/axis.h",
+ "AI_ROLL": "0",
+ "AI_PITCH": "1"
+ },
+ "armingFlag_e": {
+ "_source": "inav/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": "inav/src/main/common/axis.h",
+ "X": "0",
+ "Y": "1",
+ "Z": "2"
+ },
+ "barometerState_e": {
+ "_source": "inav/src/main/sensors/barometer.c",
+ "BAROMETER_NEEDS_SAMPLES": "0",
+ "BAROMETER_NEEDS_CALCULATION": "1"
+ },
+ "baroSensor_e": {
+ "_source": "inav/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": "inav/src/main/sensors/battery_config_structs.h",
+ "BAT_CAPACITY_UNIT_MAH": "0",
+ "BAT_CAPACITY_UNIT_MWH": "1"
+ },
+ "batteryState_e": {
+ "_source": "inav/src/main/sensors/battery.h",
+ "BATTERY_OK": "0",
+ "BATTERY_WARNING": "1",
+ "BATTERY_CRITICAL": "2",
+ "BATTERY_NOT_PRESENT": "3"
+ },
+ "batVoltageSource_e": {
+ "_source": "inav/src/main/sensors/battery_config_structs.h",
+ "BAT_VOLTAGE_RAW": "0",
+ "BAT_VOLTAGE_SAG_COMP": "1"
+ },
+ "baudRate_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/common/filter.h",
+ "FILTER_LPF": "0",
+ "FILTER_NOTCH": "1"
+ },
+ "blackboxBufferReserveStatus_e": {
+ "_source": "inav/src/main/blackbox/blackbox_io.h",
+ "BLACKBOX_RESERVE_SUCCESS": "0",
+ "BLACKBOX_RESERVE_TEMPORARY_FAILURE": "1",
+ "BLACKBOX_RESERVE_PERMANENT_FAILURE": "2"
+ },
+ "BlackboxDevice": {
+ "_source": "inav/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": "inav/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"
+ },
+ "BlackboxState": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/drivers/bus.h",
+ "BUSINDEX_1": "0",
+ "BUSINDEX_2": "1",
+ "BUSINDEX_3": "2",
+ "BUSINDEX_4": "3"
+ },
+ "busSpeed_e": {
+ "_source": "inav/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": "inav/src/main/drivers/bus.h",
+ "BUSTYPE_ANY": "0",
+ "BUSTYPE_NONE": "0",
+ "BUSTYPE_I2C": "1",
+ "BUSTYPE_SPI": "2",
+ "BUSTYPE_SDIO": "3"
+ },
+ "channelType_t": {
+ "_source": "inav/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": "inav/src/main/navigation/navigation_private.h",
+ "ROC_TO_ALT_CURRENT": "0",
+ "ROC_TO_ALT_CONSTANT": "1",
+ "ROC_TO_ALT_TARGET": "2"
+ },
+ "colorComponent_e": {
+ "_source": "inav/src/main/common/color.h",
+ "RGB_RED": "0",
+ "RGB_GREEN": "1",
+ "RGB_BLUE": "2"
+ },
+ "colorId_e": {
+ "_source": "inav/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": "inav/src/main/telemetry/crsf.c",
+ "CRSF_ACTIVE_ANTENNA1": "0",
+ "CRSF_ACTIVE_ANTENNA2": "1"
+ },
+ "crsfAddress_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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)"
+ },
+ "disarmReason_t": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/drivers/display_widgets.h",
+ "DISPLAY_WIDGET_TYPE_AHI": "0",
+ "DISPLAY_WIDGET_TYPE_SIDEBAR": "1"
+ },
+ "DjiCraftNameElements_t": {
+ "_source": "inav/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": "inav/src/main/drivers/pwm_output.h",
+ "DSHOT_CMD_SPIN_DIRECTION_NORMAL": "20",
+ "DSHOT_CMD_SPIN_DIRECTION_REVERSED": "21"
+ },
+ "dumpFlags_e": {
+ "_source": "inav/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": "inav/src/main/sensors/gyro.h",
+ "DYNAMIC_NOTCH_MODE_2D": "0",
+ "DYNAMIC_NOTCH_MODE_3D": "1"
+ },
+ "emergLandState_e": {
+ "_source": "inav/src/main/flight/failsafe.h",
+ "EMERG_LAND_IDLE": "0",
+ "EMERG_LAND_IN_PROGRESS": "1",
+ "EMERG_LAND_HAS_LANDED": "2"
+ },
+ "escSensorFrameStatus_t": {
+ "_source": "inav/src/main/sensors/esc_sensor.c",
+ "ESC_SENSOR_FRAME_PENDING": "0",
+ "ESC_SENSOR_FRAME_COMPLETE": "1",
+ "ESC_SENSOR_FRAME_FAILED": "2"
+ },
+ "escSensorState_t": {
+ "_source": "inav/src/main/sensors/esc_sensor.c",
+ "ESC_SENSOR_WAIT_STARTUP": "0",
+ "ESC_SENSOR_READY": "1",
+ "ESC_SENSOR_WAITING": "2"
+ },
+ "failsafeChannelBehavior_e": {
+ "_source": "inav/src/main/flight/failsafe.c",
+ "FAILSAFE_CHANNEL_HOLD": "0",
+ "FAILSAFE_CHANNEL_NEUTRAL": "1"
+ },
+ "failsafePhase_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/flight/failsafe.h",
+ "FAILSAFE_RXLINK_DOWN": "0",
+ "FAILSAFE_RXLINK_UP": "1"
+ },
+ "failureMode_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/common/filter.h",
+ "FILTER_PT1": "0",
+ "FILTER_BIQUAD": "1",
+ "FILTER_PT2": "2",
+ "FILTER_PT3": "3",
+ "FILTER_LULU": "4"
+ },
+ "fixedWingLaunchEvent_t": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/drivers/flash.h",
+ "FLASH_TYPE_NOR": "0",
+ "FLASH_TYPE_NAND": "1"
+ },
+ "flight_dynamics_index_t": {
+ "_source": "inav/src/main/common/axis.h",
+ "FD_ROLL": "0",
+ "FD_PITCH": "1",
+ "FD_YAW": "2"
+ },
+ "FlightLogEvent": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/blackbox/blackbox_fielddefs.h",
+ "FLIGHT_LOG_FIELD_UNSIGNED": "0",
+ "FLIGHT_LOG_FIELD_SIGNED": "1"
+ },
+ "flightModeFlags_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/rx/fport2.c",
+ "CFT_RC": "255",
+ "CFT_OTA_START": "240",
+ "CFT_OTA_DATA": "241",
+ "CFT_OTA_STOP": "242"
+ },
+ "frame_state_e": {
+ "_source": "inav/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": "inav/src/main/rx/fport2.c",
+ "FT_CONTROL": "0",
+ "FT_DOWNLINK": "1"
+ },
+ "frskyOSDColor_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/flight/pid.h",
+ "FIXED": "0",
+ "LIMIT": "1",
+ "AUTO": "2"
+ },
+ "fwAutolandApproachDirection_e": {
+ "_source": "inav/src/main/navigation/navigation.h",
+ "FW_AUTOLAND_APPROACH_DIRECTION_LEFT": "0",
+ "FW_AUTOLAND_APPROACH_DIRECTION_RIGHT": "1"
+ },
+ "fwAutolandState_t": {
+ "_source": "inav/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": "inav/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": "inav/src/main/navigation/navigation.h",
+ "GEO_ALT_ABSOLUTE": "0",
+ "GEO_ALT_RELATIVE": "1"
+ },
+ "geoAltitudeDatumFlag_e": {
+ "_source": "inav/src/main/navigation/navigation.h",
+ "NAV_WP_TAKEOFF_DATUM": "0",
+ "NAV_WP_MSL_DATUM": "1"
+ },
+ "geoOriginResetMode_e": {
+ "_source": "inav/src/main/navigation/navigation.h",
+ "GEO_ORIGIN_SET": "0",
+ "GEO_ORIGIN_RESET_ALTITUDE": "1"
+ },
+ "geozoneActionState_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/drivers/gimbal_common.h",
+ "GIMBAL_DEV_UNSUPPORTED": "0",
+ "GIMBAL_DEV_SERIAL": "1",
+ "GIMBAL_DEV_UNKNOWN": "255"
+ },
+ "gimbalHeadtrackerState_e": {
+ "_source": "inav/src/main/io/gimbal_serial.h",
+ "WAITING_HDR1": "0",
+ "WAITING_HDR2": "1",
+ "WAITING_PAYLOAD": "2",
+ "WAITING_CRCH": "3",
+ "WAITING_CRCL": "4"
+ },
+ "gpsAutoBaud_e": {
+ "_source": "inav/src/main/io/gps.h",
+ "GPS_AUTOBAUD_OFF": "0",
+ "GPS_AUTOBAUD_ON": "1"
+ },
+ "gpsAutoConfig_e": {
+ "_source": "inav/src/main/io/gps.h",
+ "GPS_AUTOCONFIG_OFF": "0",
+ "GPS_AUTOCONFIG_ON": "1"
+ },
+ "gpsBaudRate_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/io/gps.h",
+ "GPS_NO_FIX": "0",
+ "GPS_FIX_2D": "1",
+ "GPS_FIX_3D": "2"
+ },
+ "gpsProvider_e": {
+ "_source": "inav/src/main/io/gps.h",
+ "GPS_UBLOX": "0",
+ "GPS_MSP": "1",
+ "GPS_FAKE": "2",
+ "GPS_PROVIDER_COUNT": "3"
+ },
+ "gpsState_e": {
+ "_source": "inav/src/main/io/gps_private.h",
+ "GPS_UNKNOWN": "0",
+ "GPS_INITIALIZING": "1",
+ "GPS_RUNNING": "2",
+ "GPS_LOST_COMMUNICATION": "3"
+ },
+ "gyroFilterMode_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/drivers/pwm_esc_detect.h",
+ "MOTOR_UNKNOWN": "0",
+ "MOTOR_BRUSHED": "1",
+ "MOTOR_BRUSHLESS": "2"
+ },
+ "hardwareSensorStatus_e": {
+ "_source": "inav/src/main/sensors/diagnostics.h",
+ "HW_SENSOR_NONE": "0",
+ "HW_SENSOR_OK": "1",
+ "HW_SENSOR_UNAVAILABLE": "2",
+ "HW_SENSOR_UNHEALTHY": "3"
+ },
+ "headTrackerDevType_e": {
+ "_source": "inav/src/main/drivers/headtracker_common.h",
+ "HEADTRACKER_NONE": "0",
+ "HEADTRACKER_SERIAL": "1",
+ "HEADTRACKER_MSP": "2",
+ "HEADTRACKER_UNKNOWN": "255"
+ },
+ "hottEamAlarm1Flag_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/common/color.h",
+ "HSV_HUE": "0",
+ "HSV_SATURATION": "1",
+ "HSV_VALUE": "2"
+ },
+ "I2CDevice": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/drivers/bus_i2c_stm32f40x.c",
+ "I2C_TXN_READ": "0",
+ "I2C_TXN_WRITE": "1"
+ },
+ "ibusCommand_e": {
+ "_source": "inav/src/main/telemetry/ibus_shared.c",
+ "IBUS_COMMAND_DISCOVER_SENSOR": "128",
+ "IBUS_COMMAND_SENSOR_TYPE": "144",
+ "IBUS_COMMAND_MEASUREMENT": "160"
+ },
+ "ibusSensorType1_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/flight/pid.h",
+ "ITERM_RELAX_OFF": "0",
+ "ITERM_RELAX_RP": "1",
+ "ITERM_RELAX_RPY": "2"
+ },
+ "led_pin_pwm_mode_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_FLAG_LATCH": "1 << 0",
+ "LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED": "1 << 1"
+ },
+ "logicConditionsGlobalFlags_t": {
+ "_source": "inav/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": "inav/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": "inav/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"
+ },
+ "logicOperandType_e": {
+ "_source": "inav/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": "inav/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_LAST": "57"
+ },
+ "logicWaypointOperands_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/telemetry/telemetry.h",
+ "LTM_RATE_NORMAL": "0",
+ "LTM_RATE_MEDIUM": "1",
+ "LTM_RATE_SLOW": "2"
+ },
+ "magSensor_e": {
+ "_source": "inav/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": "inav/src/main/telemetry/telemetry.h",
+ "MAVLINK_AUTOPILOT_GENERIC": "0",
+ "MAVLINK_AUTOPILOT_ARDUPILOT": "1"
+ },
+ "mavlinkRadio_e": {
+ "_source": "inav/src/main/telemetry/telemetry.h",
+ "MAVLINK_RADIO_GENERIC": "0",
+ "MAVLINK_RADIO_ELRS": "1",
+ "MAVLINK_RADIO_SIK": "2"
+ },
+ "measurementSteps_e": {
+ "_source": "inav/src/main/drivers/rangefinder/rangefinder_vl53l0x.c",
+ "MEASUREMENT_START": "0",
+ "MEASUREMENT_WAIT": "1",
+ "MEASUREMENT_READ": "2"
+ },
+ "mixerProfileATRequest_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/fc/rc_modes.h",
+ "MODE_OPERATOR_OR": "0",
+ "MODE_OPERATOR_AND": "1"
+ },
+ "motorPwmProtocolTypes_e": {
+ "_source": "inav/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": "inav/src/main/flight/mixer.h",
+ "MOTOR_STOPPED_USER": "0",
+ "MOTOR_STOPPED_AUTO": "1",
+ "MOTOR_RUNNING": "2"
+ },
+ "mpu9250CompassReadState_e": {
+ "_source": "inav/src/main/drivers/compass/compass_mpu9250.c",
+ "CHECK_STATUS": "0",
+ "WAITING_FOR_STATUS": "1",
+ "WAITING_FOR_DATA": "2"
+ },
+ "mspFlashfsFlags_e": {
+ "_source": "inav/src/main/fc/fc_msp.c",
+ "MSP_FLASHFS_BIT_READY": "1",
+ "MSP_FLASHFS_BIT_SUPPORTED": "2"
+ },
+ "mspPassthroughType_e": {
+ "_source": "inav/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": "inav/src/main/fc/fc_msp.c",
+ "MSP_SDCARD_FLAG_SUPPORTTED": "1"
+ },
+ "mspSDCardState_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/navigation/navigation.h",
+ "NAV_RESET_NEVER": "0",
+ "NAV_RESET_ON_FIRST_ARM": "1",
+ "NAV_RESET_ON_EACH_ARM": "2"
+ },
+ "navAGLEstimateQuality_e": {
+ "_source": "inav/src/main/navigation/navigation_pos_estimator_private.h",
+ "SURFACE_QUAL_LOW": "0",
+ "SURFACE_QUAL_MID": "1",
+ "SURFACE_QUAL_HIGH": "2"
+ },
+ "navArmingBlocker_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/navigation/navigation.h",
+ "NAV_EXTRA_ARMING_SAFETY_ON": "0",
+ "NAV_EXTRA_ARMING_SAFETY_ALLOW_BYPASS": "1"
+ },
+ "navFwLaunchStatus_e": {
+ "_source": "inav/src/main/navigation/navigation.h",
+ "FW_LAUNCH_DETECTED": "5",
+ "FW_LAUNCH_ABORTED": "10",
+ "FW_LAUNCH_FLYING": "11"
+ },
+ "navigationEstimateStatus_e": {
+ "_source": "inav/src/main/navigation/navigation_private.h",
+ "EST_NONE": "0",
+ "EST_USABLE": "1",
+ "EST_TRUSTED": "2"
+ },
+ "navigationFSMEvent_t": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/navigation/navigation.h",
+ "MC_ALT_HOLD_STICK": "0",
+ "MC_ALT_HOLD_MID": "1",
+ "MC_ALT_HOLD_HOVER": "2"
+ },
+ "navMissionRestart_e": {
+ "_source": "inav/src/main/navigation/navigation.h",
+ "WP_MISSION_START": "0",
+ "WP_MISSION_RESUME": "1",
+ "WP_MISSION_SWITCH": "2"
+ },
+ "navOverridesMotorStop_e": {
+ "_source": "inav/src/main/navigation/navigation.h",
+ "NOMS_OFF_ALWAYS": "0",
+ "NOMS_OFF": "1",
+ "NOMS_AUTO_ONLY": "2",
+ "NOMS_ALL_NAV": "3"
+ },
+ "navPositionEstimationFlags_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/navigation/navigation.h",
+ "RTH_CLIMB_OFF": "0",
+ "RTH_CLIMB_ON": "1",
+ "RTH_CLIMB_ON_FW_SPIRAL": "2"
+ },
+ "navSetWaypointFlags_t": {
+ "_source": "inav/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": "inav/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": "inav/src/main/navigation/navigation.h",
+ "MW_NAV_FLAG_ADJUSTING_POSITION": "1 << 0",
+ "MW_NAV_FLAG_ADJUSTING_ALTITUDE": "1 << 1"
+ },
+ "navSystemStatus_Mode_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/navigation/navigation.h",
+ "NAV_WP_FLAG_HOME": "72",
+ "NAV_WP_FLAG_LAST": "165"
+ },
+ "navWaypointHeadings_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/sensors/opflow.h",
+ "OPFLOW_QUALITY_INVALID": "0",
+ "OPFLOW_QUALITY_VALID": "1"
+ },
+ "opticalFlowSensor_e": {
+ "_source": "inav/src/main/sensors/opflow.h",
+ "OPFLOW_NONE": "0",
+ "OPFLOW_CXOF": "1",
+ "OPFLOW_MSP": "2",
+ "OPFLOW_FAKE": "3"
+ },
+ "osd_adsb_warning_style_e": {
+ "_source": "inav/src/main/io/osd.h",
+ "OSD_ADSB_WARNING_STYLE_COMPACT": "0",
+ "OSD_ADSB_WARNING_STYLE_EXTENDED": "1"
+ },
+ "osd_ahi_style_e": {
+ "_source": "inav/src/main/io/osd.h",
+ "OSD_AHI_STYLE_DEFAULT": "0",
+ "OSD_AHI_STYLE_LINE": "1"
+ },
+ "osd_alignment_e": {
+ "_source": "inav/src/main/io/osd.h",
+ "OSD_ALIGN_LEFT": "0",
+ "OSD_ALIGN_RIGHT": "1"
+ },
+ "osd_crosshairs_style_e": {
+ "_source": "inav/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": "inav/src/main/io/osd.h",
+ "OSD_CRSF_LQ_TYPE1": "0",
+ "OSD_CRSF_LQ_TYPE2": "1",
+ "OSD_CRSF_LQ_TYPE3": "2"
+ },
+ "osd_items_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/io/osd.h",
+ "OSD_STATS_ENERGY_UNIT_MAH": "0",
+ "OSD_STATS_ENERGY_UNIT_WH": "1"
+ },
+ "osd_unit_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/io/osd_common.h",
+ "OSD_DRAW_POINT_TYPE_GRID": "0",
+ "OSD_DRAW_POINT_TYPE_PIXEL": "1"
+ },
+ "osdDriver_e": {
+ "_source": "inav/src/main/drivers/osd.h",
+ "OSD_DRIVER_NONE": "0",
+ "OSD_DRIVER_MAX7456": "1"
+ },
+ "osdSpeedSource_e": {
+ "_source": "inav/src/main/io/osd_common.h",
+ "OSD_SPEED_SOURCE_GROUND": "0",
+ "OSD_SPEED_SOURCE_3D": "1",
+ "OSD_SPEED_SOURCE_AIR": "2"
+ },
+ "outputMode_e": {
+ "_source": "inav/src/main/flight/mixer.h",
+ "OUTPUT_MODE_AUTO": "0",
+ "OUTPUT_MODE_MOTORS": "1",
+ "OUTPUT_MODE_SERVOS": "2",
+ "OUTPUT_MODE_LED": "3"
+ },
+ "pageId_e": {
+ "_source": "inav/src/main/io/dashboard.h",
+ "PAGE_WELCOME": "0",
+ "PAGE_ARMED": "1",
+ "PAGE_STATUS": "2"
+ },
+ "persistentObjectId_e": {
+ "_source": "inav/src/main/drivers/persistent.h",
+ "PERSISTENT_OBJECT_MAGIC": "0",
+ "PERSISTENT_OBJECT_RESET_REASON": "1",
+ "PERSISTENT_OBJECT_COUNT": "2"
+ },
+ "pidAutotuneState_e": {
+ "_source": "inav/src/main/flight/pid_autotune.c",
+ "DEMAND_TOO_LOW": "0",
+ "DEMAND_UNDERSHOOT": "1",
+ "DEMAND_OVERSHOOT": "2",
+ "TUNE_UPDATED": "3"
+ },
+ "pidControllerFlags_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/flight/pid.h",
+ "PID_TYPE_NONE": "0",
+ "PID_TYPE_PID": "1",
+ "PID_TYPE_PIFF": "2",
+ "PID_TYPE_AUTO": "3"
+ },
+ "pinLabel_e": {
+ "_source": "inav/src/main/drivers/pwm_mapping.h",
+ "PIN_LABEL_NONE": "0",
+ "PIN_LABEL_LED": "1"
+ },
+ "pitotSensor_e": {
+ "_source": "inav/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": "inav/src/main/io/smartport_master.c",
+ "PT_ACTIVE_ID": "0",
+ "PT_INACTIVE_ID": "1"
+ },
+ "portMode_t": {
+ "_source": "inav/src/main/drivers/serial.h",
+ "MODE_RX": "1 << 0",
+ "MODE_TX": "1 << 1",
+ "MODE_RXTX": "MODE_RX | MODE_TX"
+ },
+ "portOptions_t": {
+ "_source": "inav/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": "inav/src/main/io/serial.h",
+ "PORTSHARING_UNUSED": "0",
+ "PORTSHARING_NOT_SHARED": "1",
+ "PORTSHARING_SHARED": "2"
+ },
+ "pwmInitError_e": {
+ "_source": "inav/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": "inav/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": "inav/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"
+ },
+ "QUADSPIDevice": {
+ "_source": "inav/src/main/drivers/bus_quadspi.h",
+ "QUADSPIINVALID": "-1",
+ "QUADSPIDEV_1": "0"
+ },
+ "quadSpiMode_e": {
+ "_source": "inav/src/main/drivers/bus_quadspi.h",
+ "QUADSPI_MODE_BK1_ONLY": "0",
+ "QUADSPI_MODE_BK2_ONLY": "1",
+ "QUADSPI_MODE_DUAL_FLASH": "2"
+ },
+ "rangefinderType_e": {
+ "_source": "inav/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"
+ },
+ "rc_alias_e": {
+ "_source": "inav/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": "inav/src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN": "1",
+ "RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE": "2"
+ },
+ "rcdevice_5key_simulation_operation_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_RCSPLIT_VERSION": "0",
+ "RCDEVICE_PROTOCOL_VERSION_1_0": "1",
+ "RCDEVICE_PROTOCOL_UNKNOWN": "2"
+ },
+ "rcdeviceCamSimulationKeyEvent_e": {
+ "_source": "inav/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": "inav/src/main/io/rcdevice.h",
+ "RCDEVICE_RESP_SUCCESS": "0",
+ "RCDEVICE_RESP_INCORRECT_CRC": "1",
+ "RCDEVICE_RESP_TIMEOUT": "2"
+ },
+ "resolutionType_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/flight/mixer.h",
+ "MOTOR_DIRECTION_FORWARD": "0",
+ "MOTOR_DIRECTION_BACKWARD": "1",
+ "MOTOR_DIRECTION_DEADBAND": "2"
+ },
+ "rollPitchStatus_e": {
+ "_source": "inav/src/main/fc/rc_controls.h",
+ "NOT_CENTERED": "0",
+ "CENTERED": "1"
+ },
+ "rssiSource_e": {
+ "_source": "inav/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": "inav/src/main/flight/failsafe.h",
+ "RTH_IDLE": "0",
+ "RTH_IN_PROGRESS": "1",
+ "RTH_HAS_LANDED": "2"
+ },
+ "rthTargetMode_e": {
+ "_source": "inav/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": "inav/src/main/navigation/navigation.h",
+ "RTH_TRACKBACK_OFF": "0",
+ "RTH_TRACKBACK_ON": "1",
+ "RTH_TRACKBACK_FS": "2"
+ },
+ "rxFrameState_e": {
+ "_source": "inav/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": "inav/src/main/rx/rx.h",
+ "RX_TYPE_NONE": "0",
+ "RX_TYPE_SERIAL": "1",
+ "RX_TYPE_MSP": "2",
+ "RX_TYPE_SIM": "3"
+ },
+ "rxSerialReceiverType_e": {
+ "_source": "inav/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": "inav/src/main/navigation/navigation.h",
+ "SAFEHOME_USAGE_OFF": "0",
+ "SAFEHOME_USAGE_RTH": "1",
+ "SAFEHOME_USAGE_RTH_FS": "2"
+ },
+ "sbasMode_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/drivers/sdcard/sdcard.h",
+ "SDCARD_BLOCK_OPERATION_READ": "0",
+ "SDCARD_BLOCK_OPERATION_WRITE": "1",
+ "SDCARD_BLOCK_OPERATION_ERASE": "2"
+ },
+ "sdcardOperationStatus_e": {
+ "_source": "inav/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": "inav/src/main/drivers/sdcard/sdcard_spi.c",
+ "SDCARD_RECEIVE_SUCCESS": "0",
+ "SDCARD_RECEIVE_BLOCK_IN_PROGRESS": "1",
+ "SDCARD_RECEIVE_ERROR": "2"
+ },
+ "sdcardState_e": {
+ "_source": "inav/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": "inav/src/main/drivers/sdio.h",
+ "SDIOINVALID": "-1",
+ "SDIODEV_1": "0",
+ "SDIODEV_2": "1"
+ },
+ "sensor_align_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/sensors/sensors.h",
+ "SENSOR_TEMP_CAL_INITIALISE": "0",
+ "SENSOR_TEMP_CAL_IN_PROGRESS": "1",
+ "SENSOR_TEMP_CAL_COMPLETE": "2"
+ },
+ "serialPortFunction_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/flight/servos.c",
+ "AUTOTRIM_IDLE": "0",
+ "AUTOTRIM_COLLECTING": "1",
+ "AUTOTRIM_SAVE_PENDING": "2",
+ "AUTOTRIM_DONE": "3"
+ },
+ "servoIndex_e": {
+ "_source": "inav/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": "inav/src/main/drivers/pwm_mapping.h",
+ "SERVO_TYPE_PWM": "0",
+ "SERVO_TYPE_SBUS": "1",
+ "SERVO_TYPE_SBUS_PWM": "2"
+ },
+ "setting_mode_e": {
+ "_source": "inav/src/main/fc/settings.h",
+ "MODE_DIRECT": "(0 << SETTING_MODE_OFFSET)",
+ "MODE_LOOKUP": "(1 << SETTING_MODE_OFFSET)"
+ },
+ "setting_section_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/telemetry/sim.c",
+ "SIM_AT_OK": "0",
+ "SIM_AT_ERROR": "1",
+ "SIM_AT_WAITING_FOR_RESPONSE": "2"
+ },
+ "simModuleState_e": {
+ "_source": "inav/src/main/telemetry/sim.c",
+ "SIM_MODULE_NOT_DETECTED": "0",
+ "SIM_MODULE_NOT_REGISTERED": "1",
+ "SIM_MODULE_REGISTERED": "2"
+ },
+ "simReadState_e": {
+ "_source": "inav/src/main/telemetry/sim.c",
+ "SIM_READSTATE_RESPONSE": "0",
+ "SIM_READSTATE_SMS": "1",
+ "SIM_READSTATE_SKIP": "2"
+ },
+ "simTelemetryState_e": {
+ "_source": "inav/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": "inav/src/main/telemetry/sim.c",
+ "SIM_TX_NO": "0",
+ "SIM_TX_FS": "1",
+ "SIM_TX": "2"
+ },
+ "simTxFlags_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/io/vtx_smartaudio.h",
+ "SA_UNKNOWN": "0",
+ "SA_1_0": "1",
+ "SA_2_0": "2",
+ "SA_2_1": "3"
+ },
+ "smartportFuelUnit_e": {
+ "_source": "inav/src/main/telemetry/telemetry.h",
+ "SMARTPORT_FUEL_UNIT_PERCENT": "0",
+ "SMARTPORT_FUEL_UNIT_MAH": "1",
+ "SMARTPORT_FUEL_UNIT_MWH": "2"
+ },
+ "softSerialPortIndex_e": {
+ "_source": "inav/src/main/drivers/serial_softserial.h",
+ "SOFTSERIAL1": "0",
+ "SOFTSERIAL2": "1"
+ },
+ "SPIClockSpeed_e": {
+ "_source": "inav/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"
+ },
+ "SPIDevice": {
+ "_source": "inav/src/main/drivers/bus_spi.h",
+ "SPIINVALID": "-1",
+ "SPIDEV_1": "0",
+ "SPIDEV_2": "1",
+ "SPIDEV_3": "2",
+ "SPIDEV_4": "3"
+ },
+ "Srxl2BindRequest": {
+ "_source": "inav/src/main/rx/srxl2_types.h",
+ "EnterBindMode": "235",
+ "RequestBindStatus": "181",
+ "BoundDataReport": "219",
+ "SetBindInfo": "91"
+ },
+ "Srxl2BindType": {
+ "_source": "inav/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": "inav/src/main/rx/srxl2_types.h",
+ "ChannelData": "0",
+ "FailsafeChannelData": "1",
+ "VTXData": "2"
+ },
+ "Srxl2DeviceId": {
+ "_source": "inav/src/main/rx/srxl2_types.h",
+ "FlightControllerDefault": "48",
+ "FlightControllerMax": "63",
+ "Broadcast": "255"
+ },
+ "Srxl2DeviceType": {
+ "_source": "inav/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": "inav/src/main/rx/srxl2_types.h",
+ "Handshake": "33",
+ "BindInfo": "65",
+ "ParameterConfiguration": "80",
+ "SignalQuality": "85",
+ "TelemetrySensorData": "128",
+ "ControlData": "205"
+ },
+ "Srxl2State": {
+ "_source": "inav/src/main/rx/srxl2_types.h",
+ "Disabled": "0",
+ "ListenForActivity": "1",
+ "SendHandshake": "2",
+ "ListenForHandshake": "3",
+ "Running": "4"
+ },
+ "stateFlags_t": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/src/main/drivers/timer.h",
+ "TCH_DMA_IDLE": "0",
+ "TCH_DMA_READY": "1",
+ "TCH_DMA_ACTIVE": "2"
+ },
+ "tempSensorType_e": {
+ "_source": "inav/src/main/sensors/temperature.h",
+ "TEMP_SENSOR_NONE": "0",
+ "TEMP_SENSOR_LM75": "1",
+ "TEMP_SENSOR_DS18B20": "2"
+ },
+ "throttleStatus_e": {
+ "_source": "inav/src/main/fc/rc_controls.h",
+ "THROTTLE_LOW": "0",
+ "THROTTLE_HIGH": "1"
+ },
+ "throttleStatusType_e": {
+ "_source": "inav/src/main/fc/rc_controls.h",
+ "THROTTLE_STATUS_TYPE_RC": "0",
+ "THROTTLE_STATUS_TYPE_COMMAND": "1"
+ },
+ "timerMode_e": {
+ "_source": "inav/src/main/drivers/serial_softserial.c",
+ "TIMER_MODE_SINGLE": "0",
+ "TIMER_MODE_DUAL": "1"
+ },
+ "timerUsageFlag_e": {
+ "_source": "inav/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": "inav/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": "inav/src/main/common/tristate.h",
+ "TRISTATE_AUTO": "0",
+ "TRISTATE_ON": "1",
+ "TRISTATE_OFF": "2"
+ },
+ "tz_automatic_dst_e": {
+ "_source": "inav/src/main/common/time.h",
+ "TZ_AUTO_DST_OFF": "0",
+ "TZ_AUTO_DST_EU": "1",
+ "TZ_AUTO_DST_USA": "2"
+ },
+ "UARTDevice_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/io/gps_ublox.h",
+ "NAV_STATUS_FIX_VALID": "1"
+ },
+ "ubx_protocol_bytes_t": {
+ "_source": "inav/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": "inav/src/main/drivers/rangefinder/rangefinder_vl53l0x.c",
+ "VcselPeriodPreRange": "0",
+ "VcselPeriodFinalRange": "1"
+ },
+ "videoSystem_e": {
+ "_source": "inav/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": "inav/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": "inav/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": "inav/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": "inav/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": "inav/src/main/drivers/vtx_common.h",
+ "FREQUENCYGROUP_5G8": "0",
+ "FREQUENCYGROUP_2G4": "1",
+ "FREQUENCYGROUP_1G3": "2"
+ },
+ "vtxLowerPowerDisarm_e": {
+ "_source": "inav/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": "inav/src/main/io/vtx_tramp.c",
+ "VTX_RESPONSE_TYPE_NONE": "0",
+ "VTX_RESPONSE_TYPE_CAPABILITIES": "1",
+ "VTX_RESPONSE_TYPE_STATUS": "2"
+ },
+ "vtxProtoState_e": {
+ "_source": "inav/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": "inav/src/main/io/vtx.c",
+ "VTX_PARAM_POWER": "0",
+ "VTX_PARAM_BANDCHAN": "1",
+ "VTX_PARAM_PITMODE": "2",
+ "VTX_PARAM_COUNT": "3"
+ },
+ "warningFlags_e": {
+ "_source": "inav/src/main/io/ledstrip.c",
+ "WARNING_ARMING_DISABLED": "0",
+ "WARNING_LOW_BATTERY": "1",
+ "WARNING_FAILSAFE": "2",
+ "WARNING_HW_ERROR": "3"
+ },
+ "warningLedState_e": {
+ "_source": "inav/src/main/io/statusindicator.c",
+ "WARNING_LED_OFF": "0",
+ "WARNING_LED_ON": "1",
+ "WARNING_LED_FLASH": "2"
+ },
+ "widgetAHIOptions_t": {
+ "_source": "inav/src/main/drivers/display_widgets.h",
+ "DISPLAY_WIDGET_AHI_OPTION_SHOW_CORNERS": "1 << 0"
+ },
+ "widgetAHIStyle_e": {
+ "_source": "inav/src/main/drivers/display_widgets.h",
+ "DISPLAY_WIDGET_AHI_STYLE_STAIRCASE": "0",
+ "DISPLAY_WIDGET_AHI_STYLE_LINE": "1"
+ },
+ "wpFwTurnSmoothing_e": {
+ "_source": "inav/src/main/navigation/navigation.h",
+ "WP_TURN_SMOOTHING_OFF": "0",
+ "WP_TURN_SMOOTHING_ON": "1",
+ "WP_TURN_SMOOTHING_CUT": "2"
+ },
+ "wpMissionPlannerStatus_e": {
+ "_source": "inav/src/main/navigation/navigation.h",
+ "WP_PLAN_WAIT": "0",
+ "WP_PLAN_SAVE": "1",
+ "WP_PLAN_OK": "2",
+ "WP_PLAN_FULL": "3"
+ },
+ "zeroCalibrationState_e": {
+ "_source": "inav/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/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md
index 2d60f270183..864efcd8a7e 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`
@@ -2371,6 +2583,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`
@@ -2845,6 +3072,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`
@@ -4301,6 +4545,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`
@@ -4358,6 +4635,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`
@@ -4389,6 +4676,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`
@@ -5130,6 +5459,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`
diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum
index 98dc134e990..ff3e21a1d69 100644
--- a/docs/development/msp/msp_messages.checksum
+++ b/docs/development/msp/msp_messages.checksum
@@ -1 +1 @@
-7db80f38dda2265704e7852630a02a83
+82a3d2eee9d0d1fe609363a08405ed21
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index db8dbe22833..e4c2a39993f 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -9056,6 +9056,7 @@
"MSP2_INAV_LOGIC_CONDITIONS": {
"code": 8226,
"mspv": 2,
+ "not_implemented": true,
"request": null,
"reply": {
"payload": [
@@ -9115,8 +9116,8 @@
"repeating": "MAX_LOGIC_CONDITIONS"
},
"variable_len": "MAX_LOGIC_CONDITIONS",
- "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. See `logicCondition_t` structure.",
- "description": "Retrieves the configuration of all defined Logic Conditions."
+ "notes": "Deprecated, causes buffer overflow for 14*64 bytes",
+ "description": "Retrieves the configuration of all defined Logic Conditions. Requires `USE_PROGRAMMING_FRAMEWORK`. See `logicCondition_t` structure."
},
"MSP2_INAV_SET_LOGIC_CONDITIONS": {
"code": 8227,
diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md
index 5a413a1506c..d01b978d2eb 100644
--- a/docs/development/msp/msp_ref.md
+++ b/docs/development/msp/msp_ref.md
@@ -10,8 +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**
@@ -67,7 +66,7 @@ For current generation code, see [documentation project](https://github.com/xznh
**reply**: null or dict of data received\
**variable_len**: Optional boolean, if true, message does not have a predefined fixed length and needs appropriate handling\
**variants**: Optional special case, message has different cases of reply/request. Key/description is not a strict expression or code; just a readable condition\
-**not_implemented**: Optional special case, message is not implemented\
+**not_implemented**: Optional special case, message is not implemented (never or deprecated)\
**notes**: String with details of message
## Data dict fields:
@@ -3805,7 +3804,7 @@ For current generation code, see [documentation project](https://github.com/xznh
**Notes:** Expects 7 bytes. Returns error if index invalid. Calls `loadCustomServoMixer()`.
## `MSP2_INAV_LOGIC_CONDITIONS (8226 / 0x2022)`
-**Description:** Retrieves the configuration of all defined Logic Conditions.
+**Description:** Retrieves the configuration of all defined Logic Conditions. Requires `USE_PROGRAMMING_FRAMEWORK`. See `logicCondition_t` structure.
**Request Payload:** **None**
@@ -3821,7 +3820,7 @@ For current generation code, see [documentation project](https://github.com/xznh
| `operandBValue` | `int32_t` | 4 | - | Value/ID of the second operand |
| `flags` | `uint8_t` | 1 | Bitmask | Bitmask: Condition flags (`logicConditionFlags_e`) |
-**Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. See `logicCondition_t` structure.
+**Notes:** Deprecated, causes buffer overflow for 14*64 bytes
## `MSP2_INAV_SET_LOGIC_CONDITIONS (8227 / 0x2023)`
**Description:** Sets the configuration for a single Logic Condition by its index.
diff --git a/docs/development/msp/original_msp_ref.md b/docs/development/msp/original_msp_ref.md
deleted file mode 100644
index d635bbc6843..00000000000
--- a/docs/development/msp/original_msp_ref.md
+++ /dev/null
@@ -1,3514 +0,0 @@
-
-# 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**
-
-For details on the structure of MSP, see [The wiki page](https://github.com/iNavFlight/inav/wiki/MSP-V2)
-
-
-**Basic Concepts:**
-
-* **MSP Versions:**
- * **MSPv1:** The original protocol. Uses command IDs from 0 to 254.
- * **MSPv2:** An extended version. Uses command IDs from 0x1000 onwards. Can be encapsulated within an MSPv1 frame (`MSP_V2_FRAME` ID 255) or used natively.
-* **Direction:**
- * **Out:** Message sent *from* the Flight Controller (FC) *to* the Ground Control Station (GCS), OSD, or other peripheral. Usually a request for data or status.
- * **In:** Message sent *from* the GCS/OSD *to* the FC. Usually a command to set a parameter, perform an action, or provide data to the FC.
- * **In/Out:** Can function in both directions, often used for getting/setting related data where the request might specify a subset (e.g., get specific waypoint, get specific setting info).
-* **Payload:** The data carried by the message, following the command ID. The structure (order, type, size of fields) is critical.
-* **Data Types:** Common C data types are used (`uint8_t`, `int16_t`, `uint32_t`, `float`, etc.). Pay close attention to signed vs. unsigned types and sizes.
-* **Packing:** Data fields are packed sequentially in the order listed. `__attribute__((packed))` is often used in struct definitions to prevent compiler padding.
-
----
-
-## MSPv1 Core & Versioning Commands (0-5)
-
-### `MSP_API_VERSION` (1 / 0x01)
-
-* **Direction:** Out
-* **Description:** Provides the MSP protocol version and the INAV API version.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `mspProtocolVersion` | `uint8_t` | 1 | MSP Protocol version (`MSP_PROTOCOL_VERSION`, typically 0) |
- | `apiVersionMajor` | `uint8_t` | 1 | INAV API Major version (`API_VERSION_MAJOR`) |
- | `apiVersionMinor` | `uint8_t` | 1 | INAV API Minor version (`API_VERSION_MINOR`) |
-* **Notes:** Used by configurators to check compatibility.
-
-### `MSP_FC_VARIANT` (2 / 0x02)
-
-* **Direction:** Out
-* **Description:** Identifies the flight controller firmware variant (e.g., INAV, Betaflight).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `fcVariantIdentifier` | `char[4]` | 4 | 4-character identifier string (e.g., "INAV"). Defined by `flightControllerIdentifier` |
-* **Notes:** See `FLIGHT_CONTROLLER_IDENTIFIER_LENGTH`.
-
-### `MSP_FC_VERSION` (3 / 0x03)
-
-* **Direction:** Out
-* **Description:** Provides the specific version number of the flight controller firmware.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `fcVersionMajor` | `uint8_t` | 1 | Firmware Major version (`FC_VERSION_MAJOR`) |
- | `fcVersionMinor` | `uint8_t` | 1 | Firmware Minor version (`FC_VERSION_MINOR`) |
- | `fcVersionPatch` | `uint8_t` | 1 | Firmware Patch level (`FC_VERSION_PATCH_LEVEL`) |
-
-### `MSP_BOARD_INFO` (4 / 0x04)
-
-* **Direction:** Out
-* **Description:** Provides information about the specific hardware board and its capabilities.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `boardIdentifier` | `char[4]` | 4 | 4-character UPPER CASE board identifier (`TARGET_BOARD_IDENTIFIER`) |
- | `hardwareRevision` | `uint16_t` | 2 | Hardware revision number. 0 if not detected (`USE_HARDWARE_REVISION_DETECTION`) |
- | `osdSupport` | `uint8_t` | 1 | OSD chip type: 0=None, 2=Onboard (`USE_OSD`). INAV does not support slave OSD (1) |
- | `commCapabilities` | `uint8_t` | 1 | Communication capabilities bitmask: Bit 0=VCP support (`USE_VCP`), Bit 1=SoftSerial support (`USE_SOFTSERIAL1`/`2`) |
- | `targetNameLength` | `uint8_t` | 1 | Length of the target name string that follows |
- | `targetName` | `char[]` | Variable | Target name string (e.g., "MATEKF405"). Length given by previous field |
-* **Notes:** `BOARD_IDENTIFIER_LENGTH` is 4.
-
-### `MSP_BUILD_INFO` (5 / 0x05)
-
-* **Direction:** Out
-* **Description:** Provides build date, time, and Git revision of the firmware.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `buildDate` | `char[11]` | 11 | Build date string (e.g., "Dec 31 2023"). `BUILD_DATE_LENGTH` |
- | `buildTime` | `char[8]` | 8 | Build time string (e.g., "23:59:59"). `BUILD_TIME_LENGTH` |
- | `gitRevision` | `char[7]` | 7 | Short Git revision string. `GIT_SHORT_REVISION_LENGTH` |
-
----
-
-## MSPv1 INAV Configuration Commands (6-24)
-
-### `MSP_INAV_PID` (6 / 0x06)
-
-* **Direction:** Out
-* **Description:** Retrieves legacy INAV-specific PID controller related settings. Many fields are now obsolete or placeholders.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `legacyAsyncProcessing` | `uint8_t` | 1 | - | Legacy, unused. Always 0 |
- | `legacyAsyncValue1` | `uint16_t` | 2 | - | Legacy, unused. Always 0 |
- | `legacyAsyncValue2` | `uint16_t` | 2 | - | Legacy, unused. Always 0 |
- | `headingHoldRateLimit` | `uint8_t` | 1 | deg/s | Max rate for heading hold P term (`pidProfile()->heading_hold_rate_limit`) |
- | `headingHoldLpfFreq` | `uint8_t` | 1 | Hz | Fixed LPF frequency for heading hold error (`HEADING_HOLD_ERROR_LPF_FREQ`) |
- | `legacyYawJumpLimit` | `uint16_t` | 2 | - | Legacy, unused. Always 0 |
- | `legacyGyroLpf` | `uint8_t` | 1 | Hz | Fixed value `GYRO_LPF_256HZ` |
- | `accLpfHz` | `uint8_t` | 1 | Hz | Accelerometer LPF frequency (`accelerometerConfig()->acc_lpf_hz`) cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz |
- | `reserved1` | `uint8_t` | 1 | - | Reserved. Always 0 |
- | `reserved2` | `uint8_t` | 1 | - | Reserved. Always 0 |
- | `reserved3` | `uint8_t` | 1 | - | Reserved. Always 0 |
- | `reserved4` | `uint8_t` | 1 | - | Reserved. Always 0 |
-* **Notes:** Superseded by `MSP2_PID` for core PIDs and other specific messages for filter settings.
-
-### `MSP_SET_INAV_PID` (7 / 0x07)
-
-* **Direction:** In
-* **Description:** Sets legacy INAV-specific PID controller related settings.
-* **Payload:** (Matches `MSP_INAV_PID` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `legacyAsyncProcessing` | `uint8_t` | 1 | - | Legacy, ignored |
- | `legacyAsyncValue1` | `uint16_t` | 2 | - | Legacy, ignored |
- | `legacyAsyncValue2` | `uint16_t` | 2 | - | Legacy, ignored |
- | `headingHoldRateLimit` | `uint8_t` | 1 | deg/s | Sets `pidProfileMutable()->heading_hold_rate_limit` |
- | `headingHoldLpfFreq` | `uint8_t` | 1 | Hz | Ignored (fixed value `HEADING_HOLD_ERROR_LPF_FREQ` used) |
- | `legacyYawJumpLimit` | `uint16_t` | 2 | - | Legacy, ignored |
- | `legacyGyroLpf` | `uint8_t` | 1 | Enum | Ignored (was gyro LPF) |
- | `accLpfHz` | `uint8_t` | 1 | Hz | Sets `accelerometerConfigMutable()->acc_lpf_hz` |
- | `reserved1` | `uint8_t` | 1 | - | Ignored |
- | `reserved2` | `uint8_t` | 1 | - | Ignored |
- | `reserved3` | `uint8_t` | 1 | - | Ignored |
- | `reserved4` | `uint8_t` | 1 | - | Ignored |
-* **Notes:** Expects 15 bytes.
-
-### `MSP_NAME` (10 / 0x0A)
-
-* **Direction:** Out
-* **Description:** Returns the user-defined craft name.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `craftName` | `char[]` | Variable | The craft name string (`systemConfig()->craftName`). Null termination is *not* explicitly sent, the length is determined by the payload size |
-
-### `MSP_SET_NAME` (11 / 0x0B)
-
-* **Direction:** In
-* **Description:** Sets the user-defined craft name.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `craftName` | `char[]` | 1 to `MAX_NAME_LENGTH` | The new craft name string. Automatically null-terminated by the FC |
-* **Notes:** Maximum length is `MAX_NAME_LENGTH`.
-
-### `MSP_NAV_POSHOLD` (12 / 0x0C)
-
-* **Direction:** Out
-* **Description:** Retrieves navigation position hold and general manual/auto flight parameters. Some parameters depend on the platform type (Multirotor vs Fixed Wing).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `userControlMode` | `uint8_t` | 1 | - | Navigation user control mode NAV_GPS_ATTI (0) or NAV_GPS_CRUISE (1) |
- | `maxAutoSpeed` | `uint16_t` | 2 | cm/s | Max speed in autonomous modes (`navConfig()->general.max_auto_speed`) |
- | `maxAutoClimbRate` | `uint16_t` | 2 | cm/s | Max climb rate in autonomous modes (uses `fw.max_auto_climb_rate` or `mc.max_auto_climb_rate` based on platform) |
- | `maxManualSpeed` | `uint16_t` | 2 | cm/s | Max speed in manual modes with GPS aiding (`navConfig()->general.max_manual_speed`) |
- | `maxManualClimbRate` | `uint16_t` | 2 | cm/s | Max climb rate in manual modes with GPS aiding (uses `fw.max_manual_climb_rate` or `mc.max_manual_climb_rate`) |
- | `mcMaxBankAngle` | `uint8_t` | 1 | degrees | Max bank angle for multirotor position hold (`navConfig()->mc.max_bank_angle`) |
- | `mcAltHoldThrottleType` | `uint8_t` | 1 | Enum | Enum `navMcAltHoldThrottle_e` Sets 'navConfigMutable()->mc.althold_throttle_type' |
- | `mcHoverThrottle` | `uint16_t` | 2 | PWM | Multirotor hover throttle (`currentBatteryProfile->nav.mc.hover_throttle`) |
-
-### `MSP_SET_NAV_POSHOLD` (13 / 0x0D)
-
-* **Direction:** In
-* **Description:** Sets navigation position hold and general manual/auto flight parameters.
-* **Payload:** (Matches `MSP_NAV_POSHOLD` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `userControlMode` | `uint8_t` | 1 | Enum | Sets `navConfigMutable()->general.flags.user_control_mode` |
- | `maxAutoSpeed` | `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->general.max_auto_speed` |
- | `maxAutoClimbRate` | `uint16_t` | 2 | cm/s | Sets `fw.max_auto_climb_rate` or `mc.max_auto_climb_rate` based on current platform type |
- | `maxManualSpeed` | `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->general.max_manual_speed` |
- | `maxManualClimbRate` | `uint16_t` | 2 | cm/s | Sets `fw.max_manual_climb_rate` or `mc.max_manual_climb_rate` |
- | `mcMaxBankAngle` | `uint8_t` | 1 | degrees | Sets `navConfigMutable()->mc.max_bank_angle` |
- | `mcAltHoldThrottleType` | `uint8_t` | 1 | Enum | Enum `navMcAltHoldThrottle_e` Sets 'navConfigMutable()->mc.althold_throttle_type' |
- | `mcHoverThrottle` | `uint16_t` | 2 | PWM | Sets `currentBatteryProfileMutable->nav.mc.hover_throttle` |
-* **Notes:** Expects 13 bytes.
-
-### `MSP_CALIBRATION_DATA` (14 / 0x0E)
-
-* **Direction:** Out
-* **Description:** Retrieves sensor calibration data (Accelerometer zero/gain, Magnetometer zero/gain, Optical Flow scale).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `accCalibAxisFlags` | `uint8_t` | 1 | Bitmask | Flags indicating which axes of the accelerometer have been calibrated (`accGetCalibrationAxisFlags()`) |
- | `accZeroX` | `uint16_t` | 2 | Raw ADC | Accelerometer zero offset for X-axis (`accelerometerConfig()->accZero.raw[X]`) |
- | `accZeroY` | `uint16_t` | 2 | Raw ADC | Accelerometer zero offset for Y-axis (`accelerometerConfig()->accZero.raw[Y]`) |
- | `accZeroZ` | `uint16_t` | 2 | Raw ADC | Accelerometer zero offset for Z-axis (`accelerometerConfig()->accZero.raw[Z]`) |
- | `accGainX` | `uint16_t` | 2 | Raw ADC | Accelerometer gain/scale for X-axis (`accelerometerConfig()->accGain.raw[X]`) |
- | `accGainY` | `uint16_t` | 2 | Raw ADC | Accelerometer gain/scale for Y-axis (`accelerometerConfig()->accGain.raw[Y]`) |
- | `accGainZ` | `uint16_t` | 2 | Raw ADC | Accelerometer gain/scale for Z-axis (`accelerometerConfig()->accGain.raw[Z]`) |
- | `magZeroX` | `uint16_t` | 2 | Raw ADC | Magnetometer zero offset for X-axis (`compassConfig()->magZero.raw[X]`). 0 if `USE_MAG` disabled |
- | `magZeroY` | `uint16_t` | 2 | Raw ADC | Magnetometer zero offset for Y-axis (`compassConfig()->magZero.raw[Y]`). 0 if `USE_MAG` disabled |
- | `magZeroZ` | `uint16_t` | 2 | Raw ADC | Magnetometer zero offset for Z-axis (`compassConfig()->magZero.raw[Z]`). 0 if `USE_MAG` disabled |
- | `opflowScale` | `uint16_t` | 2 | Scale * 256 | Optical flow scale factor (`opticalFlowConfig()->opflow_scale * 256`). 0 if `USE_OPFLOW` disabled |
- | `magGainX` | `uint16_t` | 2 | Raw ADC | Magnetometer gain/scale for X-axis (`compassConfig()->magGain[X]`). 0 if `USE_MAG` disabled |
- | `magGainY` | `uint16_t` | 2 | Raw ADC | Magnetometer gain/scale for Y-axis (`compassConfig()->magGain[Y]`). 0 if `USE_MAG` disabled |
- | `magGainZ` | `uint16_t` | 2 | Raw ADC | Magnetometer gain/scale for Z-axis (`compassConfig()->magGain[Z]`). 0 if `USE_MAG` disabled |
-* **Notes:** Total size 27 bytes. Fields related to optional sensors are zero if the sensor is not used.
-
-### `MSP_SET_CALIBRATION_DATA` (15 / 0x0F)
-
-* **Direction:** In
-* **Description:** Sets sensor calibration data.
-* **Payload:** (Matches `MSP_CALIBRATION_DATA` structure, excluding `accCalibAxisFlags`)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `accZeroX` | `uint16_t` | 2 | Raw ADC | Sets `accelerometerConfigMutable()->accZero.raw[X]` |
- | `accZeroY` | `uint16_t` | 2 | Raw ADC | Sets `accelerometerConfigMutable()->accZero.raw[Y]` |
- | `accZeroZ` | `uint16_t` | 2 | Raw ADC | Sets `accelerometerConfigMutable()->accZero.raw[Z]` |
- | `accGainX` | `uint16_t` | 2 | Raw ADC | Sets `accelerometerConfigMutable()->accGain.raw[X]` |
- | `accGainY` | `uint16_t` | 2 | Raw ADC | Sets `accelerometerConfigMutable()->accGain.raw[Y]` |
- | `accGainZ` | `uint16_t` | 2 | Raw ADC | Sets `accelerometerConfigMutable()->accGain.raw[Z]` |
- | `magZeroX` | `uint16_t` | 2 | Raw ADC | Sets `compassConfigMutable()->magZero.raw[X]` (if `USE_MAG`) |
- | `magZeroY` | `uint16_t` | 2 | Raw ADC | Sets `compassConfigMutable()->magZero.raw[Y]` (if `USE_MAG`) |
- | `magZeroZ` | `uint16_t` | 2 | Raw ADC | Sets `compassConfigMutable()->magZero.raw[Z]` (if `USE_MAG`) |
- | `opflowScale` | `uint16_t` | 2 | Scale * 256 | Sets `opticalFlowConfigMutable()->opflow_scale = value / 256.0f` (if `USE_OPFLOW`) |
- | `magGainX` | `uint16_t` | 2 | Raw ADC | Sets `compassConfigMutable()->magGain[X]` (if `USE_MAG`) |
- | `magGainY` | `uint16_t` | 2 | Raw ADC | Sets `compassConfigMutable()->magGain[Y]` (if `USE_MAG`) |
- | `magGainZ` | `uint16_t` | 2 | Raw ADC | Sets `compassConfigMutable()->magGain[Z]` (if `USE_MAG`) |
-* **Notes:** Expects 26 bytes. Ignores values for sensors not enabled by `USE_*` defines.
-
-### `MSP_POSITION_ESTIMATION_CONFIG` (16 / 0x10)
-
-* **Direction:** Out
-* **Description:** Retrieves parameters related to the INAV position estimation fusion weights and GPS minimum satellite count.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `weightZBaroP` | `uint16_t` | 2 | Weight * 100 | Barometer Z position fusion weight (`positionEstimationConfig()->w_z_baro_p * 100`) |
- | `weightZGPSP` | `uint16_t` | 2 | Weight * 100 | GPS Z position fusion weight (`positionEstimationConfig()->w_z_gps_p * 100`) |
- | `weightZGPSV` | `uint16_t` | 2 | Weight * 100 | GPS Z velocity fusion weight (`positionEstimationConfig()->w_z_gps_v * 100`) |
- | `weightXYGPSP` | `uint16_t` | 2 | Weight * 100 | GPS XY position fusion weight (`positionEstimationConfig()->w_xy_gps_p * 100`) |
- | `weightXYGPSV` | `uint16_t` | 2 | Weight * 100 | GPS XY velocity fusion weight (`positionEstimationConfig()->w_xy_gps_v * 100`) |
- | `minSats` | `uint8_t` | 1 | Count | Minimum satellites required for GPS use (`gpsConfigMutable()->gpsMinSats`) |
- | `useGPSVelNED` | `uint8_t` | 1 | Boolean | Legacy flag, always 1 (GPS velocity is always used if available) |
-
-### `MSP_SET_POSITION_ESTIMATION_CONFIG` (17 / 0x11)
-
-* **Direction:** In
-* **Description:** Sets parameters related to the INAV position estimation fusion weights and GPS minimum satellite count.
-* **Payload:** (Matches `MSP_POSITION_ESTIMATION_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `weightZBaroP` | `uint16_t` | 2 | Weight * 100 | Sets `positionEstimationConfigMutable()->w_z_baro_p = value / 100.0f` (constrained 0.0-10.0) |
- | `weightZGPSP` | `uint16_t` | 2 | Weight * 100 | Sets `positionEstimationConfigMutable()->w_z_gps_p = value / 100.0f` (constrained 0.0-10.0) |
- | `weightZGPSV` | `uint16_t` | 2 | Weight * 100 | Sets `positionEstimationConfigMutable()->w_z_gps_v = value / 100.0f` (constrained 0.0-10.0) |
- | `weightXYGPSP` | `uint16_t` | 2 | Weight * 100 | Sets `positionEstimationConfigMutable()->w_xy_gps_p = value / 100.0f` (constrained 0.0-10.0) |
- | `weightXYGPSV` | `uint16_t` | 2 | Weight * 100 | Sets `positionEstimationConfigMutable()->w_xy_gps_v = value / 100.0f` (constrained 0.0-10.0) |
- | `minSats` | `uint8_t` | 1 | Count | Sets `gpsConfigMutable()->gpsMinSats` (constrained 5-10) |
- | `useGPSVelNED` | `uint8_t` | 1 | Boolean | Legacy flag, ignored |
-* **Notes:** Expects 12 bytes.
-
-### `MSP_WP_MISSION_LOAD` (18 / 0x12)
-
-* **Direction:** In
-* **Description:** Commands the FC to load the waypoint mission stored in non-volatile memory (e.g., EEPROM or FlashFS) into the active mission buffer.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `missionID` | `uint8_t` | 1 | Reserved for future use, currently ignored |
-* **Notes:** Only functional if `NAV_NON_VOLATILE_WAYPOINT_STORAGE` is defined. Requires 1 byte payload. Returns error if loading fails.
-
-### `MSP_WP_MISSION_SAVE` (19 / 0x13)
-
-* **Direction:** In
-* **Description:** Commands the FC to save the currently active waypoint mission from RAM to non-volatile memory (e.g., EEPROM or FlashFS).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `missionID` | `uint8_t` | 1 | Reserved for future use, currently ignored |
-* **Notes:** Only functional if `NAV_NON_VOLATILE_WAYPOINT_STORAGE` is defined. Requires 1 byte payload. Returns error if saving fails.
-
-### `MSP_WP_GETINFO` (20 / 0x14)
-
-* **Direction:** Out
-* **Description:** Retrieves information about the waypoint mission capabilities and the status of the currently loaded mission.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `wpCapabilities` | `uint8_t` | 1 | Reserved for future waypoint capabilities flags. Currently always 0 |
- | `maxWaypoints` | `uint8_t` | 1 | Maximum number of waypoints supported (`NAV_MAX_WAYPOINTS`) |
- | `missionValid` | `uint8_t` | 1 | Boolean flag indicating if the current mission in RAM is valid (`isWaypointListValid()`) |
- | `waypointCount` | `uint8_t` | 1 | Number of waypoints currently defined in the mission (`getWaypointCount()`) |
-
-### `MSP_RTH_AND_LAND_CONFIG` (21 / 0x15)
-
-* **Direction:** Out
-* **Description:** Retrieves configuration parameters related to Return-to-Home (RTH) and automatic landing behaviors.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `minRthDistance` | `uint16_t` | 2 | meters | Minimum distance from home required for RTH to engage (`navConfig()->general.min_rth_distance`) |
- | `rthClimbFirst` | `uint8_t` | 1 | Boolean | Flag: Climb to RTH altitude before returning (`navConfig()->general.flags.rth_climb_first`) |
- | `rthClimbIgnoreEmerg` | `uint8_t` | 1 | Boolean | Flag: Climb even in emergency RTH (`navConfig()->general.flags.rth_climb_ignore_emerg`) |
- | `rthTailFirst` | `uint8_t` | 1 | Boolean | Flag: Multirotor returns tail-first (`navConfig()->general.flags.rth_tail_first`) |
- | `rthAllowLanding` | `uint8_t` | 1 | Boolean | Flag: Allow automatic landing after RTH (`navConfig()->general.flags.rth_allow_landing`) |
- | `rthAltControlMode` | `uint8_t` | 1 | Enum | RTH altitude control mode (`navConfig()->general.flags.rth_alt_control_mode`) |
- | `rthAbortThreshold` | `uint16_t` | 2 | cm/s | Stick input threshold to abort RTH (`navConfig()->general.rth_abort_threshold`) |
- | `rthAltitude` | `uint16_t` | 2 | meters | Target RTH altitude (`navConfig()->general.rth_altitude`) |
- | `landMinAltVspd` | `uint16_t` | 2 | cm/s | Landing vertical speed at minimum slowdown altitude (`navConfig()->general.land_minalt_vspd`) |
- | `landMaxAltVspd` | `uint16_t` | 2 | cm/s | Landing vertical speed at maximum slowdown altitude (`navConfig()->general.land_maxalt_vspd`) |
- | `landSlowdownMinAlt` | `uint16_t` | 2 | meters | Altitude below which `landMinAltVspd` applies (`navConfig()->general.land_slowdown_minalt`) |
- | `landSlowdownMaxAlt` | `uint16_t` | 2 | meters | Altitude above which `landMaxAltVspd` applies (`navConfig()->general.land_slowdown_maxalt`) |
- | `emergDescentRate` | `uint16_t` | 2 | cm/s | Vertical speed during emergency landing descent (`navConfig()->general.emerg_descent_rate`) |
-
-### `MSP_SET_RTH_AND_LAND_CONFIG` (22 / 0x16)
-
-* **Direction:** In
-* **Description:** Sets configuration parameters related to Return-to-Home (RTH) and automatic landing behaviors.
-* **Payload:** (Matches `MSP_RTH_AND_LAND_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `minRthDistance` | `uint16_t` | 2 | meters | Sets `navConfigMutable()->general.min_rth_distance` |
- | `rthClimbFirst` | `uint8_t` | 1 | Boolean | Sets `navConfigMutable()->general.flags.rth_climb_first` |
- | `rthClimbIgnoreEmerg` | `uint8_t` | 1 | Boolean | Sets `navConfigMutable()->general.flags.rth_climb_ignore_emerg` |
- | `rthTailFirst` | `uint8_t` | 1 | Boolean | Sets `navConfigMutable()->general.flags.rth_tail_first` |
- | `rthAllowLanding` | `uint8_t` | 1 | Boolean | Sets `navConfigMutable()->general.flags.rth_allow_landing` |
- | `rthAltControlMode` | `uint8_t` | 1 | Enum | Sets `navConfigMutable()->general.flags.rth_alt_control_mode` |
- | `rthAbortThreshold` | `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->general.rth_abort_threshold` |
- | `rthAltitude` | `uint16_t` | 2 | meters | Sets `navConfigMutable()->general.rth_altitude` |
- | `landMinAltVspd` | `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->general.land_minalt_vspd` |
- | `landMaxAltVspd` | `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->general.land_maxalt_vspd` |
- | `landSlowdownMinAlt` | `uint16_t` | 2 | meters | Sets `navConfigMutable()->general.land_slowdown_minalt` |
- | `landSlowdownMaxAlt` | `uint16_t` | 2 | meters | Sets `navConfigMutable()->general.land_slowdown_maxalt` |
- | `emergDescentRate` | `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->general.emerg_descent_rate` |
-* **Notes:** Expects 21 bytes.
-
-### `MSP_FW_CONFIG` (23 / 0x17)
-
-* **Direction:** Out
-* **Description:** Retrieves configuration parameters specific to Fixed Wing navigation.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `cruiseThrottle` | `uint16_t` | 2 | PWM | Cruise throttle level (`currentBatteryProfile->nav.fw.cruise_throttle`) |
- | `minThrottle` | `uint16_t` | 2 | PWM | Minimum throttle during autonomous flight (`currentBatteryProfile->nav.fw.min_throttle`) |
- | `maxThrottle` | `uint16_t` | 2 | PWM | Maximum throttle during autonomous flight (`currentBatteryProfile->nav.fw.max_throttle`) |
- | `maxBankAngle` | `uint8_t` | 1 | degrees | Maximum bank angle allowed (`navConfig()->fw.max_bank_angle`) |
- | `maxClimbAngle` | `uint8_t` | 1 | degrees | Maximum pitch angle during climb (`navConfig()->fw.max_climb_angle`) |
- | `maxDiveAngle` | `uint8_t` | 1 | degrees | Maximum negative pitch angle during descent (`navConfig()->fw.max_dive_angle`) |
- | `pitchToThrottle` | `uint8_t` | 1 | Ratio (%) | Pitch-to-throttle feed-forward ratio (`currentBatteryProfile->nav.fw.pitch_to_throttle`) |
- | `loiterRadius` | `uint16_t` | 2 | meters | Default loiter radius (`navConfig()->fw.loiter_radius`) |
-
-### `MSP_SET_FW_CONFIG` (24 / 0x18)
-
-* **Direction:** In
-* **Description:** Sets configuration parameters specific to Fixed Wing navigation.
-* **Payload:** (Matches `MSP_FW_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `cruiseThrottle` | `uint16_t` | 2 | PWM | Sets `currentBatteryProfileMutable->nav.fw.cruise_throttle` |
- | `minThrottle` | `uint16_t` | 2 | PWM | Sets `currentBatteryProfileMutable->nav.fw.min_throttle` |
- | `maxThrottle` | `uint16_t` | 2 | PWM | Sets `currentBatteryProfileMutable->nav.fw.max_throttle` |
- | `maxBankAngle` | `uint8_t` | 1 | degrees | Sets `navConfigMutable()->fw.max_bank_angle` |
- | `maxClimbAngle` | `uint8_t` | 1 | degrees | Sets `navConfigMutable()->fw.max_climb_angle` |
- | `maxDiveAngle` | `uint8_t` | 1 | degrees | Sets `navConfigMutable()->fw.max_dive_angle` |
- | `pitchToThrottle` | `uint8_t` | 1 | Ratio (%) | Sets `currentBatteryProfileMutable->nav.fw.pitch_to_throttle` |
- | `loiterRadius` | `uint16_t` | 2 | meters | Sets `navConfigMutable()->fw.loiter_radius` |
-* **Notes:** Expects 12 bytes.
-
----
-
-## MSPv1 Cleanflight/Betaflight/INAV Feature Commands (34-58)
-
-These commands were often introduced by Cleanflight or Betaflight and adopted/adapted by INAV.
-
-### `MSP_MODE_RANGES` (34 / 0x22)
-
-* **Direction:** Out
-* **Description:** Returns all defined mode activation ranges (aux channel assignments for flight modes).
-* **Payload:** Repeated `MAX_MODE_ACTIVATION_CONDITION_COUNT` times:
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `modePermanentId` | `uint8_t` | 1 | ID | Permanent ID of the flight mode (maps to `boxId` via `findBoxByActiveBoxId`). 0 if entry unused |
- | `auxChannelIndex` | `uint8_t` | 1 | Index | 0-based index of the AUX channel used for activation |
- | `rangeStartStep` | `uint8_t` | 1 | 0-20 | Start step (corresponding to channel value range 900-2100 in steps of 50/25, depends on steps calculation) |
- | `rangeEndStep` | `uint8_t` | 1 | 0-20 | End step for the activation range |
-* **Notes:** The number of steps and mapping to PWM values depends on internal range calculations.
-
-### `MSP_SET_MODE_RANGE` (35 / 0x23)
-
-* **Direction:** In
-* **Description:** Sets a single mode activation range by its index.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `rangeIndex` | `uint8_t` | 1 | Index | Index of the mode range to set (0 to `MAX_MODE_ACTIVATION_CONDITION_COUNT - 1`) |
- | `modePermanentId` | `uint8_t` | 1 | ID | Permanent ID of the flight mode to assign |
- | `auxChannelIndex` | `uint8_t` | 1 | Index | 0-based index of the AUX channel |
- | `rangeStartStep` | `uint8_t` | 1 | 0-20 | Start step for activation |
- | `rangeEndStep` | `uint8_t` | 1 | 0-20 | End step for activation |
-* **Notes:** Expects 5 bytes. Updates the mode configuration and recalculates used mode flags. Returns error if `rangeIndex` or `modePermanentId` is invalid.
-
-### `MSP_FEATURE` (36 / 0x24)
-
-* **Direction:** Out
-* **Description:** Returns a bitmask of enabled features.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `featureMask` | `uint32_t` | 4 | Bitmask of active features (see `featureMask()`) |
-* **Notes:** Feature bits are defined in `feature.h`.
-
-### `MSP_SET_FEATURE` (37 / 0x25)
-
-* **Direction:** In
-* **Description:** Sets the enabled features using a bitmask. Clears all previous features first.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `featureMask` | `uint32_t` | 4 | Bitmask of features to enable |
-* **Notes:** Expects 4 bytes. Updates feature configuration and related settings (e.g., RSSI source).
-
-### `MSP_BOARD_ALIGNMENT` (38 / 0x26)
-
-* **Direction:** Out
-* **Description:** Returns the sensor board alignment angles relative to the craft frame.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `rollAlign` | `uint16_t` | 2 | deci-degrees | Board alignment roll angle (`boardAlignment()->rollDeciDegrees`) |
- | `pitchAlign` | `uint16_t` | 2 | deci-degrees | Board alignment pitch angle (`boardAlignment()->pitchDeciDegrees`) |
- | `yawAlign` | `uint16_t` | 2 | deci-degrees | Board alignment yaw angle (`boardAlignment()->yawDeciDegrees`) |
-
-### `MSP_SET_BOARD_ALIGNMENT` (39 / 0x27)
-
-* **Direction:** In
-* **Description:** Sets the sensor board alignment angles.
-* **Payload:** (Matches `MSP_BOARD_ALIGNMENT` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `rollAlign` | `uint16_t` | 2 | deci-degrees | Sets `boardAlignmentMutable()->rollDeciDegrees` |
- | `pitchAlign` | `uint16_t` | 2 | deci-degrees | Sets `boardAlignmentMutable()->pitchDeciDegrees` |
- | `yawAlign` | `uint16_t` | 2 | deci-degrees | Sets `boardAlignmentMutable()->yawDeciDegrees` |
-* **Notes:** Expects 6 bytes.
-
-### `MSP_CURRENT_METER_CONFIG` (40 / 0x28)
-
-* **Direction:** Out
-* **Description:** Retrieves the configuration for the current sensor.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `scale` | `uint16_t` | 2 | mV/10A or similar | Current sensor scale factor (`batteryMetersConfig()->current.scale`). Units depend on sensor type |
- | `offset` | `uint16_t` | 2 | mV | Current sensor offset (`batteryMetersConfig()->current.offset`) |
- | `type` | `uint8_t` | 1 | Enum | Enum `currentSensor_e` Type of current sensor hardware |
- | `capacity` | `uint16_t` | 2 | mAh (legacy) | Battery capacity (constrained 0-65535) (`currentBatteryProfile->capacity.value`). Note: This is legacy, use `MSP2_INAV_BATTERY_CONFIG` for full 32-bit capacity |
-
-### `MSP_SET_CURRENT_METER_CONFIG` (41 / 0x29)
-
-* **Direction:** In
-* **Description:** Sets the configuration for the current sensor.
-* **Payload:** (Matches `MSP_CURRENT_METER_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `scale` | `uint16_t` | 2 | mV/10A or similar | Sets `batteryMetersConfigMutable()->current.scale` |
- | `offset` | `uint16_t` | 2 | mV | Sets `batteryMetersConfigMutable()->current.offset` |
- | `type` | `uint8_t` | 1 | Enum | Enum `currentSensor_e` Sets 'batteryMetersConfigMutable()->current.type' |
- | `capacity` | `uint16_t` | 2 | mAh (legacy) | Sets `currentBatteryProfileMutable->capacity.value` (truncated to 16 bits) |
-* **Notes:** Expects 7 bytes.
-
-### `MSP_MIXER` (42 / 0x2A)
-
-* **Direction:** Out
-* **Description:** Retrieves the mixer type (Legacy, INAV always returns QuadX).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `mixerMode` | `uint8_t` | 1 | Always 3 (QuadX) in INAV for compatibility |
-* **Notes:** This command is largely obsolete. Mixer configuration is handled differently in INAV (presets, custom mixes). See `MSP2_INAV_MIXER`.
-
-### `MSP_SET_MIXER` (43 / 0x2B)
-
-* **Direction:** In
-* **Description:** Sets the mixer type (Legacy, ignored by INAV).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `mixerMode` | `uint8_t` | 1 | Mixer mode to set (ignored by INAV) |
-* **Notes:** Expects 1 byte. Calls `mixerUpdateStateFlags()` for potential side effects related to presets.
-
-### `MSP_RX_CONFIG` (44 / 0x2C)
-
-* **Direction:** Out
-* **Description:** Retrieves receiver configuration settings. Some fields are Betaflight compatibility placeholders.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `serialRxProvider` | `uint8_t` | 1 | Enum | Enum `rxSerialReceiverType_e` sets Serial RX provider type ('rxConfig()->serialrx_provider') |
- | `maxCheck` | `uint16_t` | 2 | PWM | Upper channel value threshold for stick commands (`rxConfig()->maxcheck`) |
- | `midRc` | `uint16_t` | 2 | PWM | Center channel value (`PWM_RANGE_MIDDLE`, typically 1500) |
- | `minCheck` | `uint16_t` | 2 | PWM | Lower channel value threshold for stick commands (`rxConfig()->mincheck`) |
- | `spektrumSatBind` | `uint8_t` | 1 | Count/Flag | Spektrum bind pulses (`rxConfig()->spektrum_sat_bind`). 0 if `USE_SPEKTRUM_BIND` disabled |
- | `rxMinUsec` | `uint16_t` | 2 | µs | Minimum expected pulse width (`rxConfig()->rx_min_usec`) |
- | `rxMaxUsec` | `uint16_t` | 2 | µs | Maximum expected pulse width (`rxConfig()->rx_max_usec`) |
- | `bfCompatRcInterpolation` | `uint8_t` | 1 | - | BF compatibility. Always 0 |
- | `bfCompatRcInterpolationInt` | `uint8_t` | 1 | - | BF compatibility. Always 0 |
- | `bfCompatAirModeThreshold` | `uint16_t` | 2 | - | BF compatibility. Always 0 |
- | `reserved1` | `uint8_t` | 1 | - | Reserved/Padding. Always 0 |
- | `reserved2` | `uint32_t` | 4 | - | Reserved/Padding. Always 0 |
- | `reserved3` | `uint8_t` | 1 | - | Reserved/Padding. Always 0 |
- | `bfCompatFpvCamAngle` | `uint8_t` | 1 | - | BF compatibility. Always 0 |
- | `receiverType` | `uint8_t` | 1 | Enum | Enum `rxReceiverType_e` Receiver type (Parallel PWM, PPM, Serial) ('rxConfig()->receiverType') |
-
-### `MSP_SET_RX_CONFIG` (45 / 0x2D)
-
-* **Direction:** In
-* **Description:** Sets receiver configuration settings.
-* **Payload:** (Matches `MSP_RX_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `serialRxProvider` | `uint8_t` | 1 | Enum | Enum `rxSerialReceiverType_e` Serial RX provider type ('rxConfig()->serialrx_provider') |
- | `maxCheck` | `uint16_t` | 2 | PWM | Sets `rxConfigMutable()->maxcheck` |
- | `midRc` | `uint16_t` | 2 | PWM | Ignored (`PWM_RANGE_MIDDLE` is used) |
- | `minCheck` | `uint16_t` | 2 | PWM | Sets `rxConfigMutable()->mincheck` |
- | `spektrumSatBind` | `uint8_t` | 1 | Count/Flag | Sets `rxConfigMutable()->spektrum_sat_bind` (if `USE_SPEKTRUM_BIND`) |
- | `rxMinUsec` | `uint16_t` | 2 | µs | Sets `rxConfigMutable()->rx_min_usec` |
- | `rxMaxUsec` | `uint16_t` | 2 | µs | Sets `rxConfigMutable()->rx_max_usec` |
- | `bfCompatRcInterpolation` | `uint8_t` | 1 | - | Ignored |
- | `bfCompatRcInterpolationInt` | `uint8_t` | 1 | - | Ignored |
- | `bfCompatAirModeThreshold` | `uint16_t` | 2 | - | Ignored |
- | `reserved1` | `uint8_t` | 1 | - | Ignored |
- | `reserved2` | `uint32_t` | 4 | - | Ignored |
- | `reserved3` | `uint8_t` | 1 | - | Ignored |
- | `bfCompatFpvCamAngle` | `uint8_t` | 1 | - | Ignored |
- | `receiverType` | `uint8_t` | 1 | Enum | Enum `rxReceiverType_e` Sets 'rxConfigMutable()->receiverType' |
-* **Notes:** Expects 24 bytes.
-
-### `MSP_LED_COLORS` (46 / 0x2E)
-
-* **Direction:** Out
-* **Description:** Retrieves the HSV color definitions for configurable LED colors.
-* **Payload:** Repeated `LED_CONFIGURABLE_COLOR_COUNT` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `hue` | `uint16_t` | 2 | Hue value (0-359) |
- | `saturation` | `uint8_t` | 1 | Saturation value (0-255) |
- | `value` | `uint8_t` | 1 | Value/Brightness (0-255) |
-* **Notes:** Only available if `USE_LED_STRIP` is defined.
-
-### `MSP_SET_LED_COLORS` (47 / 0x2F)
-
-* **Direction:** In
-* **Description:** Sets the HSV color definitions for configurable LED colors.
-* **Payload:** Repeated `LED_CONFIGURABLE_COLOR_COUNT` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `hue` | `uint16_t` | 2 | Hue value (0-359) |
- | `saturation` | `uint8_t` | 1 | Saturation value (0-255) |
- | `value` | `uint8_t` | 1 | Value/Brightness (0-255) |
-* **Notes:** Only available if `USE_LED_STRIP` is defined. Expects `LED_CONFIGURABLE_COLOR_COUNT * 4` bytes.
-
-### `MSP_LED_STRIP_CONFIG` (48 / 0x30)
-
-* **Direction:** Out
-* **Description:** Retrieves the configuration for each LED on the strip (legacy packed format).
-* **Payload:** Repeated `LED_MAX_STRIP_LENGTH` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `legacyLedConfig` | `uint32_t` | 4 | Packed LED configuration (position, function, overlay, color, direction, params). See C code for bit packing details |
-* **Notes:** Only available if `USE_LED_STRIP` is defined. Superseded by `MSP2_INAV_LED_STRIP_CONFIG_EX` which uses a clearer struct.
-
-### `MSP_SET_LED_STRIP_CONFIG` (49 / 0x31)
-
-* **Direction:** In
-* **Description:** Sets the configuration for a single LED on the strip using the legacy packed format.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `ledIndex` | `uint8_t` | 1 | Index of the LED to configure (0 to `LED_MAX_STRIP_LENGTH - 1`) |
- | `legacyLedConfig` | `uint32_t` | 4 | Packed LED configuration to set |
-* **Notes:** Only available if `USE_LED_STRIP` is defined. Expects 5 bytes. Calls `reevaluateLedConfig()`. Superseded by `MSP2_INAV_SET_LED_STRIP_CONFIG_EX`.
-
-### `MSP_RSSI_CONFIG` (50 / 0x32)
-
-* **Direction:** Out
-* **Description:** Retrieves the channel used for analog RSSI input.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `rssiChannel` | `uint8_t` | 1 | AUX channel index (1-based) used for RSSI, or 0 if disabled (`rxConfig()->rssi_channel`) |
-
-### `MSP_SET_RSSI_CONFIG` (51 / 0x33)
-
-* **Direction:** In
-* **Description:** Sets the channel used for analog RSSI input.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `rssiChannel` | `uint8_t` | 1 | AUX channel index (1-based) to use for RSSI, or 0 to disable |
-* **Notes:** Expects 1 byte. Input value is constrained 0 to `MAX_SUPPORTED_RC_CHANNEL_COUNT`. Updates the effective RSSI source.
-
-### `MSP_ADJUSTMENT_RANGES` (52 / 0x34)
-
-* **Direction:** Out
-* **Description:** Returns all defined RC adjustment ranges (tuning via aux channels).
-* **Payload:** Repeated `MAX_ADJUSTMENT_RANGE_COUNT` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `adjustmentIndex` | `uint8_t` | 1 | Index of the adjustment slot (0 to `MAX_SIMULTANEOUS_ADJUSTMENT_COUNT - 1`) |
- | `auxChannelIndex` | `uint8_t` | 1 | 0-based index of the AUX channel controlling the adjustment value |
- | `rangeStartStep` | `uint8_t` | 1 | Start step (0-20) of the control channel range |
- | `rangeEndStep` | `uint8_t` | 1 | End step (0-20) of the control channel range |
- | `adjustmentFunction` | `uint8_t` | 1 | Function/parameter being adjusted (e.g., PID gain, rate). See `rcAdjustments.h` |
- | `auxSwitchChannelIndex` | `uint8_t` | 1 | 0-based index of the AUX channel acting as an enable switch (or 0 if always enabled) |
-* **Notes:** See `adjustmentRange_t`.
-
-### `MSP_SET_ADJUSTMENT_RANGE` (53 / 0x35)
-
-* **Direction:** In
-* **Description:** Sets a single RC adjustment range configuration by its index.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `rangeIndex` | `uint8_t` | 1 | Index of the adjustment range to set (0 to `MAX_ADJUSTMENT_RANGE_COUNT - 1`) |
- | `adjustmentIndex` | `uint8_t` | 1 | Adjustment slot index (0 to `MAX_SIMULTANEOUS_ADJUSTMENT_COUNT - 1`) |
- | `auxChannelIndex` | `uint8_t` | 1 | 0-based index of the control AUX channel |
- | `rangeStartStep` | `uint8_t` | 1 | Start step (0-20) |
- | `rangeEndStep` | `uint8_t` | 1 | End step (0-20) |
- | `adjustmentFunction` | `uint8_t` | 1 | Function/parameter being adjusted |
- | `auxSwitchChannelIndex` | `uint8_t` | 1 | 0-based index of the enable switch AUX channel (or 0) |
-* **Notes:** Expects 7 bytes. Returns error if `rangeIndex` or `adjustmentIndex` is invalid.
-
-### `MSP_CF_SERIAL_CONFIG` (54 / 0x36)
-
-* **Direction:** Out
-* **Description:** Deprecated command to get serial port configuration.
-* **Notes:** Not implemented in INAV `fc_msp.c`. Use `MSP2_COMMON_SERIAL_CONFIG`.
-
-### `MSP_SET_CF_SERIAL_CONFIG` (55 / 0x37)
-
-* **Direction:** In
-* **Description:** Deprecated command to set serial port configuration.
-* **Notes:** Not implemented in INAV `fc_msp.c`. Use `MSP2_COMMON_SET_SERIAL_CONFIG`.
-
-### `MSP_VOLTAGE_METER_CONFIG` (56 / 0x38)
-
-* **Direction:** Out
-* **Description:** Retrieves legacy voltage meter configuration (scaled values).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `vbatScale` | `uint8_t` | 1 | Scale / 10 | Voltage sensor scale factor / 10 (`batteryMetersConfig()->voltage.scale / 10`). 0 if `USE_ADC` disabled |
- | `vbatMinCell` | `uint8_t` | 1 | 0.1V | Minimum cell voltage / 10 (`currentBatteryProfile->voltage.cellMin / 10`). 0 if `USE_ADC` disabled |
- | `vbatMaxCell` | `uint8_t` | 1 | 0.1V | Maximum cell voltage / 10 (`currentBatteryProfile->voltage.cellMax / 10`). 0 if `USE_ADC` disabled |
- | `vbatWarningCell` | `uint8_t` | 1 | 0.1V | Warning cell voltage / 10 (`currentBatteryProfile->voltage.cellWarning / 10`). 0 if `USE_ADC` disabled |
-* **Notes:** Superseded by `MSP2_INAV_BATTERY_CONFIG`.
-
-### `MSP_SET_VOLTAGE_METER_CONFIG` (57 / 0x39)
-
-* **Direction:** In
-* **Description:** Sets legacy voltage meter configuration (scaled values).
-* **Payload:** (Matches `MSP_VOLTAGE_METER_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `vbatScale` | `uint8_t` | 1 | Scale / 10 | Sets `batteryMetersConfigMutable()->voltage.scale = value * 10` (if `USE_ADC`) |
- | `vbatMinCell` | `uint8_t` | 1 | 0.1V | Sets `currentBatteryProfileMutable->voltage.cellMin = value * 10` (if `USE_ADC`) |
- | `vbatMaxCell` | `uint8_t` | 1 | 0.1V | Sets `currentBatteryProfileMutable->voltage.cellMax = value * 10` (if `USE_ADC`) |
- | `vbatWarningCell` | `uint8_t` | 1 | 0.1V | Sets `currentBatteryProfileMutable->voltage.cellWarning = value * 10` (if `USE_ADC`) |
-* **Notes:** Expects 4 bytes. Superseded by `MSP2_INAV_SET_BATTERY_CONFIG`.
-
-### `MSP_SONAR_ALTITUDE` (58 / 0x3A)
-
-* **Direction:** Out
-* **Description:** Retrieves the altitude measured by the primary rangefinder (sonar or lidar).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `rangefinderAltitude` | `uint32_t` | 4 | cm | Latest altitude reading from the rangefinder (`rangefinderGetLatestAltitude()`). 0 if `USE_RANGEFINDER` disabled or no reading |
-
----
-
-## MSPv1 Baseflight/INAV Commands (64-99, plus others)
-
-These commands originated in Baseflight or were added later in similar ranges.
-
-### `MSP_RX_MAP` (64 / 0x40)
-
-* **Direction:** Out
-* **Description:** Retrieves the RC channel mapping array (AETR, etc.).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `rcMap` | `uint8_t[MAX_MAPPABLE_RX_INPUTS]` | `MAX_MAPPABLE_RX_INPUTS` | Array defining the mapping from input channel index to logical function (Roll, Pitch, Yaw, Throttle, Aux1...) |
-* **Notes:** `MAX_MAPPABLE_RX_INPUTS` is typically 8 or more.
-
-### `MSP_SET_RX_MAP` (65 / 0x41)
-
-* **Direction:** In
-* **Description:** Sets the RC channel mapping array.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `rcMap` | `uint8_t[MAX_MAPPABLE_RX_INPUTS]` | `MAX_MAPPABLE_RX_INPUTS` | Array defining the new channel mapping |
-* **Notes:** Expects `MAX_MAPPABLE_RX_INPUTS` bytes.
-
-### `MSP_REBOOT` (68 / 0x44)
-
-* **Direction:** Out (but triggers an action)
-* **Description:** Commands the flight controller to reboot.
-* **Payload:** None
-* **Notes:** The FC sends an ACK *before* rebooting. The `mspPostProcessFn` is set to `mspRebootFn` to perform the reboot after the reply is sent. Will fail if the craft is armed.
-
-### `MSP_DATAFLASH_SUMMARY` (70 / 0x46)
-
-* **Direction:** Out
-* **Description:** Retrieves summary information about the onboard dataflash chip (if present and used for Blackbox via FlashFS).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `flashReady` | `uint8_t` | 1 | Boolean: 1 if flash chip is ready, 0 otherwise. (`flashIsReady()`). 0 if `USE_FLASHFS` disabled |
- | `sectorCount` | `uint32_t` | 4 | Total number of sectors on the flash chip (`geometry->sectors`). 0 if `USE_FLASHFS` disabled |
- | `totalSize` | `uint32_t` | 4 | Total size of the flash chip in bytes (`geometry->totalSize`). 0 if `USE_FLASHFS` disabled |
- | `usedSize` | `uint32_t` | 4 | Currently used size in bytes (FlashFS offset) (`flashfsGetOffset()`). 0 if `USE_FLASHFS` disabled |
-* **Notes:** Requires `USE_FLASHFS`.
-
-### `MSP_DATAFLASH_READ` (71 / 0x47)
-
-* **Direction:** In/Out
-* **Description:** Reads a block of data from the onboard dataflash (FlashFS).
-* **Request Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `address` | `uint32_t` | 4 | Starting address to read from within the FlashFS volume |
- | `size` | `uint16_t` | 2 | (Optional) Number of bytes to read. Defaults to 128 if not provided |
-* **Reply Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `address` | `uint32_t` | 4 | The starting address from which data was actually read |
- | `data` | `uint8_t[]` | Variable | The data read from flash. Length is MIN(requested size, remaining buffer space, remaining flashfs data) |
-* **Notes:** Requires `USE_FLASHFS`. Read length may be truncated by buffer size or end of flashfs volume.
-
-### `MSP_DATAFLASH_ERASE` (72 / 0x48)
-
-* **Direction:** In
-* **Description:** Erases the entire onboard dataflash chip (FlashFS volume).
-* **Payload:** None
-* **Notes:** Requires `USE_FLASHFS`. This is a potentially long operation. Use with caution.
-
-### `MSP_LOOP_TIME` (73 / 0x49)
-
-* **Direction:** Out
-* **Description:** Retrieves the configured loop time (PID loop frequency denominator).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `looptime` | `uint16_t` | 2 | µs | Configured loop time (`gyroConfig()->looptime`) |
-* **Notes:** This is the *configured* target loop time, not necessarily the *actual* measured cycle time (see `MSP_STATUS`).
-
-### `MSP_SET_LOOP_TIME` (74 / 0x4A)
-
-* **Direction:** In
-* **Description:** Sets the configured loop time.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `looptime` | `uint16_t` | 2 | µs | New loop time to set (`gyroConfigMutable()->looptime`) |
-* **Notes:** Expects 2 bytes.
-
-### `MSP_FAILSAFE_CONFIG` (75 / 0x4B)
-
-* **Direction:** Out
-* **Description:** Retrieves the failsafe configuration settings.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `failsafeDelay` | `uint8_t` | 1 | 0.1s | Delay before failsafe stage 1 activates (`failsafeConfig()->failsafe_delay`) |
- | `failsafeOffDelay` | `uint8_t` | 1 | 0.1s | Delay after signal recovery before returning control (`failsafeConfig()->failsafe_off_delay`) |
- | `failsafeThrottle` | `uint16_t` | 2 | PWM | Throttle level during failsafe stage 2 (`currentBatteryProfile->failsafe_throttle`) |
- | `legacyKillSwitch` | `uint8_t` | 1 | - | Legacy flag, always 0 |
- | `failsafeThrottleLowDelay` | `uint16_t` | 2 | ms | Delay for throttle-based failsafe detection (`failsafeConfig()->failsafe_throttle_low_delay`) |
- | `failsafeProcedure` | `uint8_t` | 1 | Enum | Enum `failsafeProcedure_e` Failsafe procedure (Drop, RTH, Land, etc.) ('failsafeConfig()->failsafe_procedure') |
- | `failsafeRecoveryDelay` | `uint8_t` | 1 | 0.1s | Delay after RTH finishes before attempting recovery (`failsafeConfig()->failsafe_recovery_delay`) |
- | `failsafeFWRollAngle` | `uint16_t` | 2 | deci-degrees | Fixed wing failsafe roll angle (`failsafeConfig()->failsafe_fw_roll_angle`) |
- | `failsafeFWPitchAngle` | `uint16_t` | 2 | deci-degrees | Fixed wing failsafe pitch angle (`failsafeConfig()->failsafe_fw_pitch_angle`) |
- | `failsafeFWYawRate` | `uint16_t` | 2 | deg/s | Fixed wing failsafe yaw rate (`failsafeConfig()->failsafe_fw_yaw_rate`) |
- | `failsafeStickThreshold` | `uint16_t` | 2 | PWM units | Stick movement threshold to exit failsafe (`failsafeConfig()->failsafe_stick_motion_threshold`) |
- | `failsafeMinDistance` | `uint16_t` | 2 | meters | Minimum distance from home for RTH failsafe (`failsafeConfig()->failsafe_min_distance`) |
- | `failsafeMinDistanceProc` | `uint8_t` | 1 | Enum | Enum `failsafeProcedure_e` Failsafe procedure if below min distance ('failsafeConfig()->failsafe_min_distance_procedure') |
-
-### `MSP_SET_FAILSAFE_CONFIG` (76 / 0x4C)
-
-* **Direction:** In
-* **Description:** Sets the failsafe configuration settings.
-* **Payload:** (Matches `MSP_FAILSAFE_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `failsafeDelay` | `uint8_t` | 1 | 0.1s | Sets `failsafeConfigMutable()->failsafe_delay` |
- | `failsafeOffDelay` | `uint8_t` | 1 | 0.1s | Sets `failsafeConfigMutable()->failsafe_off_delay` |
- | `failsafeThrottle` | `uint16_t` | 2 | PWM | Sets `currentBatteryProfileMutable->failsafe_throttle` |
- | `legacyKillSwitch` | `uint8_t` | 1 | - | Ignored |
- | `failsafeThrottleLowDelay` | `uint16_t` | 2 | ms | Sets `failsafeConfigMutable()->failsafe_throttle_low_delay` |
- | `failsafeProcedure` | `uint8_t` | 1 | Enum | Enum `failsafeProcedure_e` Sets 'failsafeConfigMutable()->failsafe_procedure' |
- | `failsafeRecoveryDelay` | `uint8_t` | 1 | 0.1s | Sets `failsafeConfigMutable()->failsafe_recovery_delay` |
- | `failsafeFWRollAngle` | `uint16_t` | 2 | deci-degrees | Sets `failsafeConfigMutable()->failsafe_fw_roll_angle` (casted to `int16_t`) |
- | `failsafeFWPitchAngle` | `uint16_t` | 2 | deci-degrees | Sets `failsafeConfigMutable()->failsafe_fw_pitch_angle` (casted to `int16_t`) |
- | `failsafeFWYawRate` | `uint16_t` | 2 | deg/s | Sets `failsafeConfigMutable()->failsafe_fw_yaw_rate` (casted to `int16_t`) |
- | `failsafeStickThreshold` | `uint16_t` | 2 | PWM units | Sets `failsafeConfigMutable()->failsafe_stick_motion_threshold` |
- | `failsafeMinDistance` | `uint16_t` | 2 | meters | Sets `failsafeConfigMutable()->failsafe_min_distance` |
- | `failsafeMinDistanceProc` | `uint8_t` | 1 | Enum | Enum `failsafeProcedure_e` Sets 'failsafeConfigMutable()->failsafe_min_distance_procedure' |
-* **Notes:** Expects 20 bytes.
-
-### `MSP_SDCARD_SUMMARY` (79 / 0x4F)
-
-* **Direction:** Out
-* **Description:** Retrieves summary information about the SD card status and filesystem.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `sdCardSupported` | `uint8_t` | 1 | Bitmask: Bit 0 = 1 if SD card support compiled in (`USE_SDCARD`) |
- | `sdCardState` | `uint8_t` | 1 | Enum (`mspSDCardState_e`): Current state (Not Present, Fatal, Card Init, FS Init, Ready). 0 if `USE_SDCARD` disabled |
- | `fsError` | `uint8_t` | 1 | Last filesystem error code (`afatfs_getLastError()`). 0 if `USE_SDCARD` disabled |
- | `freeSpaceKB` | `uint32_t` | 4 | Free space in KiB (`afatfs_getContiguousFreeSpace() / 1024`). 0 if `USE_SDCARD` disabled |
- | `totalSpaceKB` | `uint32_t` | 4 | Total space in KiB (`sdcard_getMetadata()->numBlocks / 2`). 0 if `USE_SDCARD` disabled |
-* **Notes:** Requires `USE_SDCARD` and `USE_ASYNCFATFS`.
-
-### `MSP_BLACKBOX_CONFIG` (80 / 0x50)
-
-* **Direction:** Out
-* **Description:** Legacy command to retrieve Blackbox configuration. Superseded by `MSP2_BLACKBOX_CONFIG`.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `blackboxDevice` | `uint8_t` | 1 | Always 0 (API no longer supported) |
- | `blackboxRateNum` | `uint8_t` | 1 | Always 0 |
- | `blackboxRateDenom` | `uint8_t` | 1 | Always 0 |
- | `blackboxPDenom` | `uint8_t` | 1 | Always 0 |
-* **Notes:** Returns fixed zero values. Use `MSP2_BLACKBOX_CONFIG`.
-
-### `MSP_SET_BLACKBOX_CONFIG` (81 / 0x51)
-
-* **Direction:** In
-* **Description:** Legacy command to set Blackbox configuration. Superseded by `MSP2_SET_BLACKBOX_CONFIG`.
-* **Payload:** (Ignored)
-* **Notes:** Not implemented in `fc_msp.c`. Use `MSP2_SET_BLACKBOX_CONFIG`.
-
-### `MSP_TRANSPONDER_CONFIG` (82 / 0x52)
-
-* **Direction:** Out
-* **Description:** Get VTX Transponder settings (likely specific to RaceFlight/Betaflight, not standard INAV VTX).
-* **Notes:** Not implemented in INAV `fc_msp.c`.
-
-### `MSP_SET_TRANSPONDER_CONFIG` (83 / 0x53)
-
-* **Direction:** In
-* **Description:** Set VTX Transponder settings.
-* **Notes:** Not implemented in INAV `fc_msp.c`.
-
-### `MSP_OSD_CONFIG` (84 / 0x54)
-
-* **Direction:** Out
-* **Description:** Retrieves OSD configuration settings and layout for screen 0.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `osdDriverType` | `uint8_t` | 1 | Enum | Enum `OSD_DRIVER_MAX7456` if `USE_OSD`, else `OSD_DRIVER_NONE` |
- | `videoSystem` | `uint8_t` | 1 | Enum | Enum `videoSystem_e`: Video system (Auto/PAL/NTSC) (`osdConfig()->video_system`). Sent even if OSD disabled |
- | `units` | `uint8_t` | 1 | Enum | Enum `osd_unit_e` Measurement units (Metric/Imperial) (`osdConfig()->units`). Sent even if OSD disabled |
- | `rssiAlarm` | `uint8_t` | 1 | % | RSSI alarm threshold (`osdConfig()->rssi_alarm`). Sent even if OSD disabled |
- | `capAlarm` | `uint16_t` | 2 | mAh/mWh | Capacity alarm threshold (`currentBatteryProfile->capacity.warning`). Sent even if OSD disabled |
- | `timerAlarm` | `uint16_t` | 2 | seconds | Timer alarm threshold (`osdConfig()->time_alarm`). Sent even if OSD disabled |
- | `altAlarm` | `uint16_t` | 2 | meters | Altitude alarm threshold (`osdConfig()->alt_alarm`). Sent even if OSD disabled |
- | `distAlarm` | `uint16_t` | 2 | meters | Distance alarm threshold (`osdConfig()->dist_alarm`). Sent even if OSD disabled |
- | `negAltAlarm` | `uint16_t` | 2 | meters | Negative altitude alarm threshold (`osdConfig()->neg_alt_alarm`). Sent even if OSD disabled |
- | `itemPositions` | `uint16_t[OSD_ITEM_COUNT]` | `OSD_ITEM_COUNT * 2` | Coordinates | Packed X/Y position for each OSD item on screen 0 (`osdLayoutsConfig()->item_pos[0][i]`). Sent even if OSD disabled |
-* **Notes:** Requires `USE_OSD` for meaningful data, but payload is always sent. Coordinates are packed: `(Y << 8) | X`. See `MSP2_INAV_OSD_*` commands for more detail and multi-layout support.
-
-### `MSP_SET_OSD_CONFIG` (85 / 0x55)
-
-* **Direction:** In
-* **Description:** Sets OSD configuration or a single item's position on screen 0.
-* **Payload Format 1 (Set General Config):**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `addr` | `uint8_t` | 1 | - | Must be 0xFF (-1) |
- | `videoSystem` | `uint8_t` | 1 | Enum | Enum `videoSystem_e` Sets `osdConfigMutable()->video_system` |
- | `units` | `uint8_t` | 1 | Enum | Enum `osd_unit_e` Sets `osdConfigMutable()->units` |
- | `rssiAlarm` | `uint8_t` | 1 | % | Sets `osdConfigMutable()->rssi_alarm` |
- | `capAlarm` | `uint16_t` | 2 | mAh/mWh | Sets `currentBatteryProfileMutable->capacity.warning` |
- | `timerAlarm` | `uint16_t` | 2 | seconds | Sets `osdConfigMutable()->time_alarm` |
- | `altAlarm` | `uint16_t` | 2 | meters | Sets `osdConfigMutable()->alt_alarm` |
- | `distAlarm` | `uint16_t` | 2 | meters | (Optional) Sets `osdConfigMutable()->dist_alarm` |
- | `negAltAlarm` | `uint16_t` | 2 | meters | (Optional) Sets `osdConfigMutable()->neg_alt_alarm` |
-* **Payload Format 2 (Set Item Position):**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `itemIndex` | `uint8_t` | 1 | Index | Index of the OSD item to position (0 to `OSD_ITEM_COUNT - 1`) |
- | `itemPosition` | `uint16_t` | 2 | Coordinates | Packed X/Y position (`(Y << 8) | X`) for the item on screen 0 |
-* **Notes:** Requires `USE_OSD`. Distinguishes formats based on the first byte. Format 1 requires at least 10 bytes. Format 2 requires 3 bytes. Triggers an OSD redraw. See `MSP2_INAV_OSD_SET_*` for more advanced control.
-
-### `MSP_OSD_CHAR_READ` (86 / 0x56)
-
-* **Direction:** Out
-* **Description:** Reads character data from the OSD font memory.
-* **Notes:** Not implemented in INAV `fc_msp.c`. Requires direct hardware access, typically done via DisplayPort.
-
-### `MSP_OSD_CHAR_WRITE` (87 / 0x57)
-
-* **Direction:** In
-* **Description:** Writes character data to the OSD font memory.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `address` | `uint8_t` or `uint16_t` | 1 or 2 | Starting address in font memory. Size depends on total payload size |
- | `charData` | `uint8_t[]` | Variable | Character bitmap data (54 or 64 bytes per char, depending on format) |
-* **Notes:** Requires `USE_OSD`. Payload size determines address size (8/16 bit) and character data size (visible bytes only or full char with metadata). Uses `displayWriteFontCharacter()`. Requires OSD hardware (like MAX7456) to be present and functional.
-
-### `MSP_VTX_CONFIG` (88 / 0x58)
-
-* **Direction:** Out
-* **Description:** Retrieves the current VTX (Video Transmitter) configuration and capabilities.
-* **Payload:** (Only sent if `USE_VTX_CONTROL` is defined and a VTX device is configured)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `vtxDeviceType` | `uint8_t` | 1 | Enum (`vtxDevType_e`): Type of VTX device detected/configured. `VTXDEV_UNKNOWN` if none |
- | `band` | `uint8_t` | 1 | VTX band number (from `vtxSettingsConfig`) |
- | `channel` | `uint8_t` | 1 | VTX channel number (from `vtxSettingsConfig`) |
- | `power` | `uint8_t` | 1 | VTX power level index (from `vtxSettingsConfig`) |
- | `pitMode` | `uint8_t` | 1 | Boolean: 1 if VTX is currently in pit mode, 0 otherwise |
- | `vtxReady` | `uint8_t` | 1 | Boolean: 1 if VTX device reported ready, 0 otherwise |
- | `lowPowerDisarm` | `uint8_t` | 1 | Boolean: 1 if low power on disarm is enabled (from `vtxSettingsConfig`) |
- | `vtxTableAvailable` | `uint8_t` | 1 | Boolean: 1 if VTX tables (band/power) are available for query |
- | `bandCount` | `uint8_t` | 1 | Number of bands supported by the VTX device |
- | `channelCount` | `uint8_t` | 1 | Number of channels per band supported by the VTX device |
- | `powerCount` | `uint8_t` | 1 | Number of power levels supported by the VTX device |
-* **Notes:** BF compatibility field `frequency` (uint16) is missing compared to some BF versions. Use `MSP_VTXTABLE_BAND` and `MSP_VTXTABLE_POWERLEVEL` for details.
-
-### `MSP_SET_VTX_CONFIG` (89 / 0x59)
-
-* **Direction:** In
-* **Description:** Sets the VTX configuration (band, channel, power, pit mode). Supports multiple protocol versions/extensions based on payload size.
-* **Payload (Minimum):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `bandChannelEncoded` | `uint16_t` | 2 | Encoded band/channel value: `(band-1)*8 + (channel-1)`. If <= `VTXCOMMON_MSP_BANDCHAN_CHKVAL` |
-* **Payload (Extended):** (Fields added sequentially based on size)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `power` | `uint8_t` | 1 | Power level index to set (`vtxSettingsConfigMutable()->power`) |
- | `pitMode` | `uint8_t` | 1 | Pit mode state to set (0=off, 1=on). Directly calls `vtxCommonSetPitMode` |
- | `lowPowerDisarm` | `uint8_t` | 1 | Low power on disarm setting (`vtxSettingsConfigMutable()->lowPowerDisarm`) |
- | `pitModeFreq` | `uint16_t` | 2 | *Ignored*. Betaflight extension |
- | `band` | `uint8_t` | 1 | Explicit band number to set (`vtxSettingsConfigMutable()->band`). Overrides encoded value if present |
- | `channel` | `uint8_t` | 1 | Explicit channel number to set (`vtxSettingsConfigMutable()->channel`). Overrides encoded value if present |
- | `frequency` | `uint16_t` | 2 | *Ignored*. Betaflight extension |
- | `bandCount` | `uint8_t` | 1 | *Ignored*. Betaflight extension |
- | `channelCount` | `uint8_t` | 1 | *Ignored*. Betaflight extension |
- | `powerCount` | `uint8_t` | 1 | *Ignored*. Betaflight extension (can potentially reduce reported power count if valid) |
-* **Notes:** Requires `USE_VTX_CONTROL`. Minimum size 2 bytes. Applies settings to `vtxSettingsConfig` and potentially directly to the device (pit mode).
-
-### `MSP_ADVANCED_CONFIG` (90 / 0x5A)
-
-* **Direction:** Out
-* **Description:** Retrieves advanced hardware-related configuration (PWM protocols, rates). Some fields are BF compatibility placeholders.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `gyroSyncDenom` | `uint8_t` | 1 | Always 1 (BF compatibility) |
- | `pidProcessDenom` | `uint8_t` | 1 | Always 1 (BF compatibility) |
- | `useUnsyncedPwm` | `uint8_t` | 1 | Always 1 (BF compatibility, INAV uses async PWM based on protocol) |
- | `motorPwmProtocol` | `uint8_t` | 1 | Motor PWM protocol type (`motorConfig()->motorPwmProtocol`) |
- | `motorPwmRate` | `uint16_t` | 2 | Hz: Motor PWM rate (if applicable) (`motorConfig()->motorPwmRate`) |
- | `servoPwmRate` | `uint16_t` | 2 | Hz: Servo PWM rate (`servoConfig()->servoPwmRate`) |
- | `legacyGyroSync` | `uint8_t` | 1 | Always 0 (BF compatibility) |
-
-### `MSP_SET_ADVANCED_CONFIG` (91 / 0x5B)
-
-* **Direction:** In
-* **Description:** Sets advanced hardware-related configuration (PWM protocols, rates).
-* **Payload:** (Matches `MSP_ADVANCED_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `gyroSyncDenom` | `uint8_t` | 1 | Ignored |
- | `pidProcessDenom` | `uint8_t` | 1 | Ignored |
- | `useUnsyncedPwm` | `uint8_t` | 1 | Ignored |
- | `motorPwmProtocol` | `uint8_t` | 1 | Sets `motorConfigMutable()->motorPwmProtocol` |
- | `motorPwmRate` | `uint16_t` | 2 | Sets `motorConfigMutable()->motorPwmRate` |
- | `servoPwmRate` | `uint16_t` | 2 | Sets `servoConfigMutable()->servoPwmRate` |
- | `legacyGyroSync` | `uint8_t` | 1 | Ignored |
-* **Notes:** Expects 9 bytes.
-
-### `MSP_FILTER_CONFIG` (92 / 0x5C)
-
-* **Direction:** Out
-* **Description:** Retrieves filter configuration settings (Gyro, D-term, Yaw, Accel). Some fields are BF compatibility placeholders or legacy.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `gyroMainLpfHz` | `uint8_t` | 1 | Hz | Gyro main low-pass filter cutoff frequency (`gyroConfig()->gyro_main_lpf_hz`) |
- | `dtermLpfHz` | `uint16_t` | 2 | Hz | D-term low-pass filter cutoff frequency (`pidProfile()->dterm_lpf_hz`) |
- | `yawLpfHz` | `uint16_t` | 2 | Hz | Yaw low-pass filter cutoff frequency (`pidProfile()->yaw_lpf_hz`) |
- | `legacyGyroNotchHz` | `uint16_t` | 2 | - | Always 0 (Legacy) |
- | `legacyGyroNotchCutoff` | `uint16_t` | 2 | - | Always 1 (Legacy) |
- | `bfCompatDtermNotchHz` | `uint16_t` | 2 | - | Always 0 (BF compatibility) |
- | `bfCompatDtermNotchCutoff` | `uint16_t` | 2 | - | Always 1 (BF compatibility) |
- | `bfCompatGyroNotch2Hz` | `uint16_t` | 2 | - | Always 0 (BF compatibility) |
- | `bfCompatGyroNotch2Cutoff` | `uint16_t` | 2 | - | Always 1 (BF compatibility) |
- | `accNotchHz` | `uint16_t` | 2 | Hz | Accelerometer notch filter center frequency (`accelerometerConfig()->acc_notch_hz`) |
- | `accNotchCutoff` | `uint16_t` | 2 | Hz | Accelerometer notch filter cutoff frequency (`accelerometerConfig()->acc_notch_cutoff`) |
- | `legacyGyroStage2LpfHz` | `uint16_t` | 2 | - | Always 0 (Legacy) |
-
-### `MSP_SET_FILTER_CONFIG` (93 / 0x5D)
-
-* **Direction:** In
-* **Description:** Sets filter configuration settings. Handles different payload lengths for backward compatibility.
-* **Payload:** (Fields added sequentially based on size)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `gyroMainLpfHz` | `uint8_t` | 1 | Hz | Sets `gyroConfigMutable()->gyro_main_lpf_hz`. (Size >= 5) |
- | `dtermLpfHz` | `uint16_t` | 2 | Hz | Sets `pidProfileMutable()->dterm_lpf_hz` (constrained 0-500). (Size >= 5) |
- | `yawLpfHz` | `uint16_t` | 2 | Hz | Sets `pidProfileMutable()->yaw_lpf_hz` (constrained 0-255). (Size >= 5) |
- | `legacyGyroNotchHz` | `uint16_t` | 2 | - | Ignored. (Size >= 9) |
- | `legacyGyroNotchCutoff` | `uint16_t` | 2 | - | Ignored. (Size >= 9) |
- | `bfCompatDtermNotchHz` | `uint16_t` | 2 | - | Ignored. (Size >= 13) |
- | `bfCompatDtermNotchCutoff` | `uint16_t` | 2 | - | Ignored. (Size >= 13) |
- | `bfCompatGyroNotch2Hz` | `uint16_t` | 2 | - | Ignored. (Size >= 17) |
- | `bfCompatGyroNotch2Cutoff` | `uint16_t` | 2 | - | Ignored. (Size >= 17) |
- | `accNotchHz` | `uint16_t` | 2 | Hz | Sets `accelerometerConfigMutable()->acc_notch_hz` (constrained 0-255). (Size >= 21) |
- | `accNotchCutoff` | `uint16_t` | 2 | Hz | Sets `accelerometerConfigMutable()->acc_notch_cutoff` (constrained 1-255). (Size >= 21) |
- | `legacyGyroStage2LpfHz` | `uint16_t` | 2 | - | Ignored. (Size >= 22) |
-* **Notes:** Requires specific payload sizes (5, 9, 13, 17, 21, or 22 bytes) to be accepted. Calls `pidInitFilters()` if size >= 13.
-
-### `MSP_PID_ADVANCED` (94 / 0x5E)
-
-* **Direction:** Out
-* **Description:** Retrieves advanced PID tuning parameters. Many fields are BF compatibility placeholders.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `legacyRollPitchItermIgnore` | `uint16_t` | 2 | - | Always 0 (Legacy) |
- | `legacyYawItermIgnore` | `uint16_t` | 2 | - | Always 0 (Legacy) |
- | `legacyYawPLimit` | `uint16_t` | 2 | - | Always 0 (Legacy) |
- | `bfCompatDeltaMethod` | `uint8_t` | 1 | - | Always 0 (BF compatibility) |
- | `bfCompatVbatPidComp` | `uint8_t` | 1 | - | Always 0 (BF compatibility) |
- | `bfCompatSetpointRelaxRatio` | `uint8_t` | 1 | - | Always 0 (BF compatibility) |
- | `reserved1` | `uint8_t` | 1 | - | Always 0 |
- | `legacyPidSumLimit` | `uint16_t` | 2 | - | Always 0 (Legacy) |
- | `bfCompatItermThrottleGain` | `uint8_t` | 1 | - | Always 0 (BF compatibility) |
- | `accelLimitRollPitch` | `uint16_t` | 2 | dps / 10 | Axis acceleration limit for Roll/Pitch / 10 (`pidProfile()->axisAccelerationLimitRollPitch / 10`) |
- | `accelLimitYaw` | `uint16_t` | 2 | dps / 10 | Axis acceleration limit for Yaw / 10 (`pidProfile()->axisAccelerationLimitYaw / 10`) |
-* **Notes:** Acceleration limits are scaled by 10 for compatibility.
-
-### `MSP_SET_PID_ADVANCED` (95 / 0x5F)
-
-* **Direction:** In
-* **Description:** Sets advanced PID tuning parameters.
-* **Payload:** (Matches `MSP_PID_ADVANCED` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `legacyRollPitchItermIgnore` | `uint16_t` | 2 | - | Ignored |
- | `legacyYawItermIgnore` | `uint16_t` | 2 | - | Ignored |
- | `legacyYawPLimit` | `uint16_t` | 2 | - | Ignored |
- | `bfCompatDeltaMethod` | `uint8_t` | 1 | - | Ignored |
- | `bfCompatVbatPidComp` | `uint8_t` | 1 | - | Ignored |
- | `bfCompatSetpointRelaxRatio` | `uint8_t` | 1 | - | Ignored |
- | `reserved1` | `uint8_t` | 1 | - | Ignored |
- | `legacyPidSumLimit` | `uint16_t` | 2 | - | Ignored |
- | `bfCompatItermThrottleGain` | `uint8_t` | 1 | - | Ignored |
- | `accelLimitRollPitch` | `uint16_t` | 2 | dps / 10 | Sets `pidProfileMutable()->axisAccelerationLimitRollPitch = value * 10` |
- | `accelLimitYaw` | `uint16_t` | 2 | dps / 10 | Sets `pidProfileMutable()->axisAccelerationLimitYaw = value * 10` |
-* **Notes:** Expects 17 bytes.
-
-### `MSP_SENSOR_CONFIG` (96 / 0x60)
-
-* **Direction:** Out
-* **Description:** Retrieves the configured hardware type for various sensors.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `accHardware` | `uint8_t` | 1 | Enum (`accHardware_e`): Accelerometer hardware type (`accelerometerConfig()->acc_hardware`) |
- | `baroHardware` | `uint8_t` | 1 | Enum (`baroHardware_e`): Barometer hardware type (`barometerConfig()->baro_hardware`). 0 if `USE_BARO` disabled |
- | `magHardware` | `uint8_t` | 1 | Enum (`magHardware_e`): Magnetometer hardware type (`compassConfig()->mag_hardware`). 0 if `USE_MAG` disabled |
- | `pitotHardware` | `uint8_t` | 1 | Enum (`pitotHardware_e`): Pitot tube hardware type (`pitotmeterConfig()->pitot_hardware`). 0 if `USE_PITOT` disabled |
- | `rangefinderHardware` | `uint8_t` | 1 | Enum (`rangefinderHardware_e`): Rangefinder hardware type (`rangefinderConfig()->rangefinder_hardware`). 0 if `USE_RANGEFINDER` disabled |
- | `opflowHardware` | `uint8_t` | 1 | Enum (`opticalFlowHardware_e`): Optical flow hardware type (`opticalFlowConfig()->opflow_hardware`). 0 if `USE_OPFLOW` disabled |
-
-### `MSP_SET_SENSOR_CONFIG` (97 / 0x61)
-
-* **Direction:** In
-* **Description:** Sets the configured hardware type for various sensors.
-* **Payload:** (Matches `MSP_SENSOR_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `accHardware` | `uint8_t` | 1 | Sets `accelerometerConfigMutable()->acc_hardware` |
- | `baroHardware` | `uint8_t` | 1 | Sets `barometerConfigMutable()->baro_hardware` (if `USE_BARO`) |
- | `magHardware` | `uint8_t` | 1 | Sets `compassConfigMutable()->mag_hardware` (if `USE_MAG`) |
- | `pitotHardware` | `uint8_t` | 1 | Sets `pitotmeterConfigMutable()->pitot_hardware` (if `USE_PITOT`) |
- | `rangefinderHardware` | `uint8_t` | 1 | Sets `rangefinderConfigMutable()->rangefinder_hardware` (if `USE_RANGEFINDER`) |
- | `opflowHardware` | `uint8_t` | 1 | Sets `opticalFlowConfigMutable()->opflow_hardware` (if `USE_OPFLOW`) |
-* **Notes:** Expects 6 bytes.
-
-### `MSP_SPECIAL_PARAMETERS` (98 / 0x62)
-
-* **Direction:** Out
-* **Description:** Betaflight specific, likely unused/unimplemented in INAV.
-* **Notes:** Not implemented in INAV `fc_msp.c`.
-
-### `MSP_SET_SPECIAL_PARAMETERS` (99 / 0x63)
-
-* **Direction:** In
-* **Description:** Betaflight specific, likely unused/unimplemented in INAV.
-* **Notes:** Not implemented in INAV `fc_msp.c`.
-
----
-
-## MSPv1 MultiWii Original Commands (100-127, 130)
-
-These are commands originating from the MultiWii project.
-
-### `MSP_IDENT` (100 / 0x64)
-
-* **Direction:** Out
-* **Description:** Provides basic flight controller identity information. Not implemented in modern INAV, but used by legacy versions and MultiWii.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | MultiWii version | uint8_t | 1 | n/a | Scaled version major*100+minor |
- | Mixer Mode | uint8_t | 1 | Enum | Mixer type |
- | MSP Version | uint8_t | 1 | n/a | Scaled version major*100+minor |
- | Platform Capability | uint32_t | | Bitmask of MW capabilities |
-* **Notes:** Obsolete. Listed for legacy compatibility only.
-
-### `MSP_STATUS` (101 / 0x65)
-
-* **Direction:** Out
-* **Description:** Provides basic flight controller status including cycle time, errors, sensor status, active modes (first 32), and the current configuration profile.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `cycleTime` | `uint16_t` | 2 | µs | Main loop cycle time (`cycleTime`) |
- | `i2cErrors` | `uint16_t` | 2 | Count | Number of I2C errors encountered (`i2cGetErrorCounter()`). 0 if `USE_I2C` not defined |
- | `sensorStatus` | `uint16_t` | 2 | Bitmask | Bitmask indicating available/active sensors (`packSensorStatus()`). See notes |
- | `activeModesLow` | `uint32_t` | 4 | Bitmask | First 32 bits of the active flight modes bitmask (`packBoxModeFlags()`) |
- | `profile` | `uint8_t` | 1 | Index | Current configuration profile index (0-based) (`getConfigProfile()`) |
-* **Notes:** Superseded by `MSP_STATUS_EX` and `MSP2_INAV_STATUS`. `sensorStatus` bitmask: (Bit 0: ACC, 1: BARO, 2: MAG, 3: GPS, 4: RANGEFINDER, 5: GYRO). `activeModesLow` only contains the first 32 modes; use `MSP_ACTIVEBOXES` for the full set.
-
-### `MSP_RAW_IMU` (102 / 0x66)
-
-* **Direction:** Out
-* **Description:** Provides raw sensor readings from the IMU (Accelerometer, Gyroscope, Magnetometer).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `accX` | `int16_t` | 2 | ~1/512 G | Raw accelerometer X reading, scaled (`acc.accADCf[X] * 512`) |
- | `accY` | `int16_t` | 2 | ~1/512 G | Raw accelerometer Y reading, scaled (`acc.accADCf[Y] * 512`) |
- | `accZ` | `int16_t` | 2 | ~1/512 G | Raw accelerometer Z reading, scaled (`acc.accADCf[Z] * 512`) |
- | `gyroX` | `int16_t` | 2 | deg/s | Gyroscope X-axis rate (`gyroRateDps(X)`) |
- | `gyroY` | `int16_t` | 2 | deg/s | Gyroscope Y-axis rate (`gyroRateDps(Y)`) |
- | `gyroZ` | `int16_t` | 2 | deg/s | Gyroscope Z-axis rate (`gyroRateDps(Z)`) |
- | `magX` | `int16_t` | 2 | Raw units | Raw magnetometer X reading (`mag.magADC[X]`). 0 if `USE_MAG` disabled |
- | `magY` | `int16_t` | 2 | Raw units | Raw magnetometer Y reading (`mag.magADC[Y]`). 0 if `USE_MAG` disabled |
- | `magZ` | `int16_t` | 2 | Raw units | Raw magnetometer Z reading (`mag.magADC[Z]`). 0 if `USE_MAG` disabled |
-* **Notes:** Acc scaling is approximate (512 LSB/G). Mag units depend on the sensor.
-
-### `MSP_SERVO` (103 / 0x67)
-
-* **Direction:** Out
-* **Description:** Provides the current output values for all supported servos.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `servoOutputs` | `int16_t[MAX_SUPPORTED_SERVOS]` | `MAX_SUPPORTED_SERVOS * 2` | PWM | Array of current servo output values (typically 1000-2000) |
-
-### `MSP_MOTOR` (104 / 0x68)
-
-* **Direction:** Out
-* **Description:** Provides the current output values for the first 8 motors.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `motorOutputs` | `uint16_t[8]` | 16 | PWM | Array of current motor output values (typically 1000-2000). Values beyond `MAX_SUPPORTED_MOTORS` are 0 |
-
-### `MSP_RC` (105 / 0x69)
-
-* **Direction:** Out
-* **Description:** Provides the current values of the received RC channels.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `rcChannels` | `uint16_t[]` | `rxRuntimeConfig.channelCount * 2` | PWM | Array of current RC channel values (typically 1000-2000). Length depends on detected channels |
-
-### `MSP_RAW_GPS` (106 / 0x6A)
-
-* **Direction:** Out
-* **Description:** Provides raw GPS data (fix status, coordinates, altitude, speed, course).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `fixType` | `uint8_t` | 1 | Enum | Enum `gpsFixType_e` GPS fix type (`gpsSol.fixType`) |
- | `numSat` | `uint8_t` | 1 | Count | Number of satellites used in solution (`gpsSol.numSat`) |
- | `latitude` | `int32_t` | 4 | deg * 1e7 | Latitude (`gpsSol.llh.lat`) |
- | `longitude` | `int32_t` | 4 | deg * 1e7 | Longitude (`gpsSol.llh.lon`) |
- | `altitude` | `int16_t` | 2 | meters | Altitude above MSL (`gpsSol.llh.alt / 100`) |
- | `speed` | `uint16_t` | 2 | cm/s | Ground speed (`gpsSol.groundSpeed`) |
- | `groundCourse` | `uint16_t` | 2 | deci-degrees | Ground course (`gpsSol.groundCourse`) |
- | `hdop` | `uint16_t` | 2 | HDOP * 100 | Horizontal Dilution of Precision (`gpsSol.hdop`) |
-* **Notes:** Only available if `USE_GPS` is defined. Altitude is truncated to meters.
-
-### `MSP_COMP_GPS` (107 / 0x6B)
-
-* **Direction:** Out
-* **Description:** Provides computed GPS values: distance and direction to home.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `distanceToHome` | `uint16_t` | 2 | meters | Distance to the home point (`GPS_distanceToHome`) |
- | `directionToHome` | `uint16_t` | 2 | degrees | Direction to the home point (0-360) (`GPS_directionToHome`) |
- | `gpsHeartbeat` | `uint8_t` | 1 | Boolean | Indicates if GPS data is being received (`gpsSol.flags.gpsHeartbeat`) |
-* **Notes:** Only available if `USE_GPS` is defined.
-
-### `MSP_ATTITUDE` (108 / 0x6C)
-
-* **Direction:** Out
-* **Description:** Provides the current attitude estimate (roll, pitch, yaw).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `roll` | `int16_t` | 2 | deci-degrees | Roll angle (`attitude.values.roll`) |
- | `pitch` | `int16_t` | 2 | deci-degrees | Pitch angle (`attitude.values.pitch`) |
- | `yaw` | `int16_t` | 2 | degrees | Yaw/Heading angle (`DECIDEGREES_TO_DEGREES(attitude.values.yaw)`) |
-* **Notes:** Yaw is converted from deci-degrees to degrees.
-
-### `MSP_ALTITUDE` (109 / 0x6D)
-
-* **Direction:** Out
-* **Description:** Provides estimated altitude, vertical speed (variometer), and raw barometric altitude.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `estimatedAltitude` | `int32_t` | 4 | cm | Estimated altitude above home/sea level (`getEstimatedActualPosition(Z)`) |
- | `variometer` | `int16_t` | 2 | cm/s | Estimated vertical speed (`getEstimatedActualVelocity(Z)`) |
- | `baroAltitude` | `int32_t` | 4 | cm | Latest raw altitude from barometer (`baroGetLatestAltitude()`). 0 if `USE_BARO` disabled |
-
-### `MSP_ANALOG` (110 / 0x6E)
-
-* **Direction:** Out
-* **Description:** Provides analog sensor readings: battery voltage, current consumption (mAh), RSSI, and current draw (Amps).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `vbat` | `uint8_t` | 1 | 0.1V | Battery voltage, scaled (`getBatteryVoltage() / 10`), constrained 0-255 |
- | `mAhDrawn` | `uint16_t` | 2 | mAh | Consumed battery capacity (`getMAhDrawn()`), constrained 0-65535 |
- | `rssi` | `uint16_t` | 2 | 0-1023 or % | Received Signal Strength Indicator (`getRSSI()`). Units depend on source |
- | `amperage` | `int16_t` | 2 | 0.01A | Current draw (`getAmperage()`), constrained -32768 to 32767 |
-* **Notes:** Superseded by `MSP2_INAV_ANALOG` which provides higher precision and more fields.
-
-### `MSP_RC_TUNING` (111 / 0x6F)
-
-* **Direction:** Out
-* **Description:** Retrieves RC tuning parameters (rates, expos, TPA) for the current control rate profile.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `legacyRcRate` | `uint8_t` | 1 | Always 100 (Legacy, unused) |
- | `rcExpo` | `uint8_t` | 1 | Roll/Pitch RC Expo (`currentControlRateProfile->stabilized.rcExpo8`) |
- | `rollRate` | `uint8_t` | 1 | Roll Rate (`currentControlRateProfile->stabilized.rates[FD_ROLL]`) |
- | `pitchRate` | `uint8_t` | 1 | Pitch Rate (`currentControlRateProfile->stabilized.rates[FD_PITCH]`) |
- | `yawRate` | `uint8_t` | 1 | Yaw Rate (`currentControlRateProfile->stabilized.rates[FD_YAW]`) |
- | `dynamicThrottlePID` | `uint8_t` | 1 | Dynamic Throttle PID (TPA) value (`currentControlRateProfile->throttle.dynPID`) |
- | `throttleMid` | `uint8_t` | 1 | Throttle Midpoint (`currentControlRateProfile->throttle.rcMid8`) |
- | `throttleExpo` | `uint8_t` | 1 | Throttle Expo (`currentControlRateProfile->throttle.rcExpo8`) |
- | `tpaBreakpoint` | `uint16_t` | 2 | Throttle PID Attenuation (TPA) breakpoint (`currentControlRateProfile->throttle.pa_breakpoint`) |
- | `rcYawExpo` | `uint8_t` | 1 | Yaw RC Expo (`currentControlRateProfile->stabilized.rcYawExpo8`) |
-* **Notes:** Superseded by `MSP2_INAV_RATE_PROFILE` which includes manual rates/expos.
-
-### `MSP_ACTIVEBOXES` (113 / 0x71)
-
-* **Direction:** Out
-* **Description:** Provides the full bitmask of currently active flight modes (boxes).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `activeModes` | `boxBitmask_t` | `sizeof(boxBitmask_t)` | Bitmask of all active modes (`packBoxModeFlags()`). Size depends on `boxBitmask_t` definition |
-* **Notes:** Use this instead of `MSP_STATUS` or `MSP_STATUS_EX` if more than 32 modes are possible.
-
-### `MSP_MISC` (114 / 0x72)
-
-* **Direction:** Out
-* **Description:** Retrieves miscellaneous configuration settings, mostly related to RC, GPS, Mag, and Battery voltage (legacy formats).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `midRc` | `uint16_t` | 2 | PWM | Mid RC value (`PWM_RANGE_MIDDLE`, typically 1500) |
- | `legacyMinThrottle` | `uint16_t` | 2 | - | Always 0 (Legacy) |
- | `maxThrottle` | `uint16_t` | 2 | PWM | Maximum throttle command (`getMaxThrottle()`) |
- | `minCommand` | `uint16_t` | 2 | PWM | Minimum motor command when disarmed (`motorConfig()->mincommand`) |
- | `failsafeThrottle` | `uint16_t` | 2 | PWM | Failsafe throttle level (`currentBatteryProfile->failsafe_throttle`) |
- | `gpsType` | `uint8_t` | 1 | Enum | Enum `gpsProvider_e` GPS provider type (`gpsConfig()->provider`). 0 if `USE_GPS` disabled |
- | `legacyGpsBaud` | `uint8_t` | 1 | - | Always 0 (Legacy) |
- | `gpsSbasMode` | `uint8_t` | 1 | Enum | Enum `sbasMode_e` GPS SBAS mode (`gpsConfig()->sbasMode`). 0 if `USE_GPS` disabled |
- | `legacyMwCurrentOut` | `uint8_t` | 1 | - | Always 0 (Legacy) |
- | `rssiChannel` | `uint8_t` | 1 | Index | RSSI channel index (1-based) (`rxConfig()->rssi_channel`) |
- | `reserved1` | `uint8_t` | 1 | - | Always 0 |
- | `magDeclination` | `uint16_t` | 2 | 0.1 degrees | Magnetic declination / 10 (`compassConfig()->mag_declination / 10`). 0 if `USE_MAG` disabled |
- | `vbatScale` | `uint8_t` | 1 | Scale / 10 | Voltage scale / 10 (`batteryMetersConfig()->voltage.scale / 10`). 0 if `USE_ADC` disabled |
- | `vbatMinCell` | `uint8_t` | 1 | 0.1V | Min cell voltage / 10 (`currentBatteryProfile->voltage.cellMin / 10`). 0 if `USE_ADC` disabled |
- | `vbatMaxCell` | `uint8_t` | 1 | 0.1V | Max cell voltage / 10 (`currentBatteryProfile->voltage.cellMax / 10`). 0 if `USE_ADC` disabled |
- | `vbatWarningCell` | `uint8_t` | 1 | 0.1V | Warning cell voltage / 10 (`currentBatteryProfile->voltage.cellWarning / 10`). 0 if `USE_ADC` disabled |
-* **Notes:** Superseded by `MSP2_INAV_MISC` and other specific commands which offer better precision and more fields.
-
-### `MSP_BOXNAMES` (116 / 0x74)
-
-* **Direction:** Out
-* **Description:** Provides a semicolon-separated string containing the names of all available flight modes (boxes).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `boxNamesString` | `char[]` | Variable | String containing mode names separated by ';'. Null termination not guaranteed by MSP, relies on payload size. (`serializeBoxNamesReply()`) |
-* **Notes:** The exact set of names depends on compiled features and configuration. Due to the size of the payload, it is recommended that [`MSP_BOXIDS`](#msp_boxids-119--0x77) is used instead.
-
-### `MSP_PIDNAMES` (117 / 0x75)
-
-* **Direction:** Out
-* **Description:** Provides a semicolon-separated string containing the names of the PID controllers.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `pidNamesString` | `char[]` | Variable | String "ROLL;PITCH;YAW;ALT;Pos;PosR;NavR;LEVEL;MAG;VEL;". Null termination not guaranteed by MSP |
-
-### `MSP_WP` (118 / 0x76)
-
-* **Direction:** In/Out
-* **Description:** Get/Set a single waypoint from the mission plan.
-* **Request Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `waypointIndex` | `uint8_t` | 1 | Index of the waypoint to retrieve (0 to `NAV_MAX_WAYPOINTS - 1`) |
-* **Reply Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `waypointIndex` | `uint8_t` | 1 | Index | Index of the returned waypoint |
- | `action` | `uint8_t` | 1 | Enum | Enum `navWaypointActions_e` Waypoint action type |
- | `latitude` | `int32_t` | 4 | deg * 1e7 | Latitude coordinate |
- | `longitude` | `int32_t` | 4 | deg * 1e7 | Longitude coordinate |
- | `altitude` | `int32_t` | 4 | cm | Altitude coordinate (relative to home or sea level, see flag) |
- | `param1` | `uint16_t` | 2 | Varies | Parameter 1 (meaning depends on action) |
- | `param2` | `uint16_t` | 2 | Varies | Parameter 2 (meaning depends on action) |
- | `param3` | `uint16_t` | 2 | Varies | Parameter 3 (meaning depends on action) |
- | `flag` | `uint8_t` | 1 | Bitmask | Waypoint flags (`NAV_WP_FLAG_*`) |
-* **Notes:** See `navWaypoint_t` and `navWaypointActions_e`.
-
-### `MSP_BOXIDS` (119 / 0x77)
-
-* **Direction:** Out
-* **Description:** Provides a list of permanent IDs associated with the available flight modes (boxes).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `boxIds` | `uint8_t[]` | Variable | Array of permanent IDs for each configured box (`serializeBoxReply()`). Length depends on number of boxes |
-* **Notes:** Useful for mapping mode range configurations (`MSP_MODE_RANGES`) back to user-understandable modes via `MSP_BOXNAMES`.
-
-### `MSP_SERVO_CONFIGURATIONS` (120 / 0x78)
-
-* **Direction:** Out
-* **Description:** Retrieves the configuration parameters for all supported servos (min, max, middle, rate). Legacy format with unused fields.
-* **Payload:** Repeated `MAX_SUPPORTED_SERVOS` times:
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `min` | `uint16_t` | 2 | PWM | Minimum servo endpoint (`servoParams(i)->min`) |
- | `max` | `uint16_t` | 2 | PWM | Maximum servo endpoint (`servoParams(i)->max`) |
- | `middle` | `uint16_t` | 2 | PWM | Middle/Neutral servo position (`servoParams(i)->middle`) |
- | `rate` | `uint8_t` | 1 | % (-100 to 100) | Servo rate/scaling (`servoParams(i)->rate`) |
- | `reserved1` | `uint8_t` | 1 | - | Always 0 |
- | `reserved2` | `uint8_t` | 1 | - | Always 0 |
- | `legacyForwardChan` | `uint8_t` | 1 | - | Always 255 (Legacy) |
- | `legacyReversedSources` | `uint32_t` | 4 | - | Always 0 (Legacy) |
-* **Notes:** Superseded by `MSP2_INAV_SERVO_CONFIG` which has a cleaner structure.
-
-### `MSP_NAV_STATUS` (121 / 0x79)
-
-* **Direction:** Out
-* **Description:** Retrieves the current status of the navigation system.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `navMode` | `uint8_t` | 1 | Enum (`NAV_MODE_*`): Current navigation mode (None, RTH, WP, Hold, etc.) (`NAV_Status.mode`) |
- | `navState` | `uint8_t` | 1 | Enum (`NAV_STATE_*`): Current navigation state (`NAV_Status.state`) |
- | `activeWpAction` | `uint8_t` | 1 | Enum (`navWaypointActions_e`): Action of the currently executing waypoint (`NAV_Status.activeWpAction`) |
- | `activeWpNumber` | `uint8_t` | 1 | Index: Index of the currently executing waypoint (`NAV_Status.activeWpNumber`) |
- | `navError` | `uint8_t` | 1 | Enum (`NAV_ERROR_*`): Current navigation error code (`NAV_Status.error`) |
- | `targetHeading` | `int16_t` | 2 | degrees: Target heading for heading controller (`getHeadingHoldTarget()`) |
-* **Notes:** Requires `USE_GPS`.
-
-### `MSP_NAV_CONFIG` (122 / 0x7A)
-
-* **Not implemented**
-
-### `MSP_3D` (124 / 0x7C)
-
-* **Direction:** Out
-* **Description:** Retrieves settings related to 3D/reversible motor operation.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `deadbandLow` | `uint16_t` | 2 | PWM | Lower deadband limit for 3D mode (`reversibleMotorsConfig()->deadband_low`) |
- | `deadbandHigh` | `uint16_t` | 2 | PWM | Upper deadband limit for 3D mode (`reversibleMotorsConfig()->deadband_high`) |
- | `neutral` | `uint16_t` | 2 | PWM | Neutral throttle point for 3D mode (`reversibleMotorsConfig()->neutral`) |
-* **Notes:** Requires reversible motor support.
-
-### `MSP_RC_DEADBAND` (125 / 0x7D)
-
-* **Direction:** Out
-* **Description:** Retrieves RC input deadband settings.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `deadband` | `uint8_t` | 1 | PWM | General RC deadband for Roll/Pitch (`rcControlsConfig()->deadband`) |
- | `yawDeadband` | `uint8_t` | 1 | PWM | Specific deadband for Yaw (`rcControlsConfig()->yaw_deadband`) |
- | `altHoldDeadband` | `uint8_t` | 1 | PWM | Deadband for altitude hold adjustments (`rcControlsConfig()->alt_hold_deadband`) |
- | `throttleDeadband` | `uint16_t` | 2 | PWM | Deadband around throttle mid-stick (`rcControlsConfig()->mid_throttle_deadband`) |
-
-### `MSP_SENSOR_ALIGNMENT` (126 / 0x7E)
-
-* **Direction:** Out
-* **Description:** Retrieves sensor alignment settings (legacy format).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `gyroAlign` | `uint8_t` | 1 | Always 0 (Legacy alignment enum) |
- | `accAlign` | `uint8_t` | 1 | Always 0 (Legacy alignment enum) |
- | `magAlign` | `uint8_t` | 1 | Magnetometer alignment (`compassConfig()->mag_align`). 0 if `USE_MAG` disabled |
- | `opflowAlign` | `uint8_t` | 1 | Optical flow alignment (`opticalFlowConfig()->opflow_align`). 0 if `USE_OPFLOW` disabled |
-* **Notes:** Board alignment is now typically handled by `MSP_BOARD_ALIGNMENT`. This returns legacy enum values where applicable.
-
-### `MSP_LED_STRIP_MODECOLOR` (127 / 0x7F)
-
-* **Direction:** Out
-* **Description:** Retrieves the color index assigned to each LED mode and function/direction combination, including special colors.
-* **Payload:** Repeated (`LED_MODE_COUNT * LED_DIRECTION_COUNT` + `LED_SPECIAL_COLOR_COUNT`) times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `modeIndex` | `uint8_t` | 1 | Index of the LED mode Enum (`ledModeIndex_e`). `LED_MODE_COUNT` for special colors |
- | `directionOrSpecialIndex` | `uint8_t` | 1 | Index of the direction Enum (`ledDirection_e`) or special color (`ledSpecialColor_e`) |
- | `colorIndex` | `uint8_t` | 1 | Index of the color assigned from `ledStripConfig()->colors` |
-* **Notes:** Only available if `USE_LED_STRIP` is defined. Allows mapping modes/directions/specials to configured colors.
-
-### `MSP_BATTERY_STATE` (130 / 0x82)
-
-* **Direction:** Out
-* **Description:** Provides battery state information, formatted primarily for DJI FPV Goggles compatibility.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `cellCount` | `uint8_t` | 1 | Count | Number of battery cells (`getBatteryCellCount()`) |
- | `capacity` | `uint16_t` | 2 | mAh | Battery capacity (`currentBatteryProfile->capacity.value`) |
- | `vbatScaled` | `uint8_t` | 1 | 0.1V | Battery voltage / 10 (`getBatteryVoltage() / 10`) |
- | `mAhDrawn` | `uint16_t` | 2 | mAh | Consumed capacity (`getMAhDrawn()`) |
- | `amperage` | `int16_t` | 2 | 0.01A | Current draw (`getAmperage()`) |
- | `batteryState` | `uint8_t` | 1 | Enum | Enum `batteryState_e` Current battery state (`getBatteryState()`, see `BATTERY_STATE_*`) |
- | `vbatActual` | `uint16_t` | 2 | 0.01V | Actual battery voltage (`getBatteryVoltage()`) |
-* **Notes:** Only available if `USE_DJI_HD_OSD` or `USE_MSP_DISPLAYPORT` is defined. Some values are duplicated from `MSP_ANALOG` / `MSP2_INAV_ANALOG` but potentially with different scaling/types.
-
-### `MSP_VTXTABLE_BAND` (137 / 0x89)
-
-* **Direction:** In/Out (?)
-* **Description:** Retrieves information about a specific VTX band from the VTX table. (Implementation missing in provided `fc_msp.c`)
-* **Notes:** The ID is defined, but no handler exists in the provided C code. Likely intended to query band names and frequencies.
-
-### `MSP_VTXTABLE_POWERLEVEL` (138 / 0x8A)
-
-* **Direction:** In/Out
-* **Description:** Retrieves information about a specific VTX power level from the VTX table.
-* **Request Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `powerLevelIndex` | `uint8_t` | 1 | 1-based index of the power level to query |
-* **Reply Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `powerLevelIndex` | `uint8_t` | 1 | 1-based index of the returned power level |
- | `powerValue` | `uint16_t` | 2 | Always 0 (Actual power value in mW is not stored/returned via MSP) |
- | `labelLength` | `uint8_t` | 1 | Length of the power level label string that follows |
- | `label` | `char[]` | Variable | Power level label string (e.g., "25", "200"). Length given by previous field |
-* **Notes:** Requires `USE_VTX_CONTROL`. Returns error if index is out of bounds. The `powerValue` field is unused.
-
----
-
-## MSPv1 MultiWii Original Input Commands (200-221)
-
-These commands are sent *to* the FC.
-
-### `MSP_SET_RAW_RC` (200 / 0xC8)
-
-* **Direction:** In
-* **Description:** Provides raw RC channel data to the flight controller, typically used when the receiver is connected via MSP (e.g., MSP RX feature).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `rcChannels` | `uint16_t[]` | Variable (2 * channelCount) | PWM | Array of RC channel values (typically 1000-2000). Number of channels determined by payload size |
-* **Notes:** Requires `USE_RX_MSP`. Maximum channels `MAX_SUPPORTED_RC_CHANNEL_COUNT`. Calls `rxMspFrameReceive()`.
-
-### `MSP_SET_RAW_GPS` (201 / 0xC9)
-
-* **Direction:** In
-* **Description:** Provides raw GPS data to the flight controller, typically for simulation or external GPS injection.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `fixType` | `uint8_t` | 1 | Enum | Enum `gpsFixType_e` GPS fix type |
- | `numSat` | `uint8_t` | 1 | Count | Number of satellites |
- | `latitude` | `int32_t` | 4 | deg * 1e7 | Latitude |
- | `longitude` | `int32_t` | 4 | deg * 1e7 | Longitude |
- | `altitude` | `int16_t` | 2 | meters | Altitude (converted to cm internally) |
- | `speed` | `uint16_t` | 2 | cm/s | Ground speed |
- | `groundCourse` | `uint16_t` | 2 | ??? | Ground course (units unclear from code, likely degrees or deci-degrees, ignored in current code) |
-* **Notes:** Requires `USE_GPS`. Expects 14 bytes. Updates `gpsSol` structure and calls `onNewGPSData()`. Note the altitude unit mismatch (meters in MSP, cm internal). Does not provide velocity components.
-
-### `MSP_SET_BOX` (203 / 0xCB)
-
-* **Direction:** In
-* **Description:** Sets the state of flight modes (boxes). (Likely unused/obsolete in INAV).
-* **Notes:** Not implemented in INAV `fc_msp.c`. Mode changes are typically handled via RC channels (`MSP_MODE_RANGES`).
-
-### `MSP_SET_RC_TUNING` (204 / 0xCC)
-
-* **Direction:** In
-* **Description:** Sets RC tuning parameters (rates, expos, TPA) for the current control rate profile.
-* **Payload:** (Matches `MSP_RC_TUNING` outgoing structure)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `legacyRcRate` | `uint8_t` | 1 | Ignored |
- | `rcExpo` | `uint8_t` | 1 | Sets `currentControlRateProfile->stabilized.rcExpo8` |
- | `rollRate` | `uint8_t` | 1 | Sets `currentControlRateProfile->stabilized.rates[FD_ROLL]` (constrained) |
- | `pitchRate` | `uint8_t` | 1 | Sets `currentControlRateProfile->stabilized.rates[FD_PITCH]` (constrained) |
- | `yawRate` | `uint8_t` | 1 | Sets `currentControlRateProfile->stabilized.rates[FD_YAW]` (constrained) |
- | `dynamicThrottlePID` | `uint8_t` | 1 | Sets `currentControlRateProfile->throttle.dynPID` (constrained) |
- | `throttleMid` | `uint8_t` | 1 | Sets `currentControlRateProfile->throttle.rcMid8` |
- | `throttleExpo` | `uint8_t` | 1 | Sets `currentControlRateProfile->throttle.rcExpo8` |
- | `tpaBreakpoint` | `uint16_t` | 2 | Sets `currentControlRateProfile->throttle.pa_breakpoint` |
- | `rcYawExpo` | `uint8_t` | 1 | (Optional) Sets `currentControlRateProfile->stabilized.rcYawExpo8` |
-* **Notes:** Expects 10 or 11 bytes. Calls `schedulePidGainsUpdate()`. Superseded by `MSP2_INAV_SET_RATE_PROFILE`.
-
-### `MSP_ACC_CALIBRATION` (205 / 0xCD)
-
-* **Direction:** In
-* **Description:** Starts the accelerometer calibration procedure.
-* **Payload:** None
-* **Notes:** Will fail if armed. Calls `accStartCalibration()`.
-
-### `MSP_MAG_CALIBRATION` (206 / 0xCE)
-
-* **Direction:** In
-* **Description:** Starts the magnetometer calibration procedure.
-* **Payload:** None
-* **Notes:** Will fail if armed. Enables the `CALIBRATE_MAG` state flag.
-
-### `MSP_SET_MISC` (207 / 0xCF)
-
-* **Direction:** In
-* **Description:** Sets miscellaneous configuration settings (legacy formats/scaling).
-* **Payload:** (Matches `MSP_MISC` outgoing structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `midRc` | `uint16_t` | 2 | PWM | Ignored |
- | `legacyMinThrottle` | `uint16_t` | 2 | - | Ignored |
- | `legacyMaxThrottle` | `uint16_t` | 2 | - | Ignored |
- | `minCommand` | `uint16_t` | 2 | PWM | Sets `motorConfigMutable()->mincommand` (constrained 0-PWM_RANGE_MAX) |
- | `failsafeThrottle` | `uint16_t` | 2 | PWM | Sets `currentBatteryProfileMutable->failsafe_throttle` (constrained PWM_RANGE_MIN/MAX) |
- | `gpsType` | `uint8_t` | 1 | Enum | Enum `gpsProvider_e` (Sets `gpsConfigMutable()->provider`)|
- | `legacyGpsBaud` | `uint8_t` | 1 | - | Ignored |
- | `gpsSbasMode` | `uint8_t` | 1 | Enum | Enum `sbasMode_e` (Sets `gpsConfigMutable()->sbasMode`) |
- | `legacyMwCurrentOut` | `uint8_t` | 1 | - | Ignored |
- | `rssiChannel` | `uint8_t` | 1 | Index | Sets `rxConfigMutable()->rssi_channel` (constrained 0-MAX_SUPPORTED_RC_CHANNEL_COUNT). Updates source |
- | `reserved1` | `uint8_t` | 1 | - | Ignored |
- | `magDeclination` | `uint16_t` | 2 | 0.1 degrees | Sets `compassConfigMutable()->mag_declination = value * 10` (if `USE_MAG`) |
- | `vbatScale` | `uint8_t` | 1 | Scale / 10 | Sets `batteryMetersConfigMutable()->voltage.scale = value * 10` (if `USE_ADC`) |
- | `vbatMinCell` | `uint8_t` | 1 | 0.1V | Sets `currentBatteryProfileMutable->voltage.cellMin = value * 10` (if `USE_ADC`) |
- | `vbatMaxCell` | `uint8_t` | 1 | 0.1V | Sets `currentBatteryProfileMutable->voltage.cellMax = value * 10` (if `USE_ADC`) |
- | `vbatWarningCell` | `uint8_t` | 1 | 0.1V | Sets `currentBatteryProfileMutable->voltage.cellWarning = value * 10` (if `USE_ADC`) |
-* **Notes:** Expects 22 bytes. Superseded by `MSP2_INAV_SET_MISC`.
-
-### `MSP_RESET_CONF` (208 / 0xD0)
-
-* **Direction:** In
-* **Description:** Resets all configuration settings to their default values and saves to EEPROM.
-* **Payload:** None
-* **Notes:** Will fail if armed. Suspends RX, calls `resetEEPROM()`, `writeEEPROM()`, `readEEPROM()`, resumes RX. Use with caution!
-
-### `MSP_SET_WP` (209 / 0xD1)
-
-* **Direction:** In
-* **Description:** Sets a single waypoint in the mission plan.
-* **Payload:** (Matches `MSP_WP` reply structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `waypointIndex` | `uint8_t` | 1 | Index | Index of the waypoint to set (0 to `NAV_MAX_WAYPOINTS - 1`) |
- | `action` | `uint8_t` | 1 | Enum | Enum `navWaypointActions_e` Waypoint action type |
- | `latitude` | `int32_t` | 4 | deg * 1e7 | Latitude coordinate |
- | `longitude` | `int32_t` | 4 | deg * 1e7 | Longitude coordinate |
- | `altitude` | `int32_t` | 4 | cm | Altitude coordinate |
- | `param1` | `uint16_t` | 2 | Varies | Parameter 1 |
- | `param2` | `uint16_t` | 2 | Varies | Parameter 2 |
- | `param3` | `uint16_t` | 2 | Varies | Parameter 3 |
- | `flag` | `uint8_t` | 1 | Bitmask | Waypoint flags |
-* **Notes:** Expects 21 bytes. Calls `setWaypoint()`. If `USE_FW_AUTOLAND` is enabled, this also interacts with autoland approach settings based on waypoint index and flags.
-
-### `MSP_SELECT_SETTING` (210 / 0xD2)
-
-* **Direction:** In
-* **Description:** Selects the active configuration profile and saves it.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `profileIndex` | `uint8_t` | 1 | Index of the profile to activate (0-based) |
-* **Notes:** Will fail if armed. Calls `setConfigProfileAndWriteEEPROM()`.
-
-### `MSP_SET_HEAD` (211 / 0xD3)
-
-* **Direction:** In
-* **Description:** Sets the target heading for the heading hold controller (e.g., during MAG mode).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `heading` | `int16_t` | 2 | degrees | Target heading (0-359) |
-* **Notes:** Expects 2 bytes. Calls `updateHeadingHoldTarget()`.
-
-### `MSP_SET_SERVO_CONFIGURATION` (212 / 0xD4)
-
-* **Direction:** In
-* **Description:** Sets the configuration for a single servo (legacy format).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `servoIndex` | `uint8_t` | 1 | Index | Index of the servo to configure (0 to `MAX_SUPPORTED_SERVOS - 1`) |
- | `min` | `uint16_t` | 2 | PWM | Minimum servo endpoint |
- | `max` | `uint16_t` | 2 | PWM | Maximum servo endpoint |
- | `middle` | `uint16_t` | 2 | PWM | Middle/Neutral servo position |
- | `rate` | `uint8_t` | 1 | % | Servo rate/scaling |
- | `reserved1` | `uint8_t` | 1 | - | Ignored |
- | `reserved2` | `uint8_t` | 1 | - | Ignored |
- | `legacyForwardChan` | `uint8_t` | 1 | - | Ignored |
- | `legacyReversedSources` | `uint32_t` | 4 | - | Ignored |
-* **Notes:** Expects 15 bytes. Returns error if index is invalid. Calls `servoComputeScalingFactors()`. Superseded by `MSP2_INAV_SET_SERVO_CONFIG`.
-
-### `MSP_SET_MOTOR` (214 / 0xD6)
-
-* **Direction:** In
-* **Description:** Sets the disarmed motor values, typically used for motor testing or propeller balancing functions in a configurator.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `motorValues` | `uint16_t[8]` | 16 | PWM | Array of motor values to set when disarmed. Only affects first `MAX_SUPPORTED_MOTORS` |
-* **Notes:** Expects 16 bytes. Modifies the `motor_disarmed` array. These values are *not* saved persistently.
-
-### `MSP_SET_NAV_CONFIG` (215 / 0xD7)
-
-* **Not implemented**
-
-### `MSP_SET_3D` (217 / 0xD9)
-
-* **Direction:** In
-* **Description:** Sets parameters related to 3D/reversible motor operation.
-* **Payload:** (Matches `MSP_3D` outgoing structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `deadbandLow` | `uint16_t` | 2 | PWM | Sets `reversibleMotorsConfigMutable()->deadband_low` |
- | `deadbandHigh` | `uint16_t` | 2 | PWM | Sets `reversibleMotorsConfigMutable()->deadband_high` |
- | `neutral` | `uint16_t` | 2 | PWM | Sets `reversibleMotorsConfigMutable()->neutral` |
-* **Notes:** Expects 6 bytes. Requires reversible motor support.
-
-### `MSP_SET_RC_DEADBAND` (218 / 0xDA)
-
-* **Direction:** In
-* **Description:** Sets RC input deadband values.
-* **Payload:** (Matches `MSP_RC_DEADBAND` outgoing structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `deadband` | `uint8_t` | 1 | PWM | Sets `rcControlsConfigMutable()->deadband` |
- | `yawDeadband` | `uint8_t` | 1 | PWM | Sets `rcControlsConfigMutable()->yaw_deadband` |
- | `altHoldDeadband` | `uint8_t` | 1 | PWM | Sets `rcControlsConfigMutable()->alt_hold_deadband` |
- | `throttleDeadband` | `uint16_t` | 2 | PWM | Sets `rcControlsConfigMutable()->mid_throttle_deadband` |
-* **Notes:** Expects 5 bytes.
-
-### `MSP_SET_RESET_CURR_PID` (219 / 0xDB)
-
-* **Direction:** In
-* **Description:** Resets the PIDs of the *current* profile to their default values. Does not save.
-* **Payload:** None
-* **Notes:** Calls `PG_RESET_CURRENT(pidProfile)`. To save, follow with `MSP_EEPROM_WRITE`.
-
-### `MSP_SET_SENSOR_ALIGNMENT` (220 / 0xDC)
-
-* **Direction:** In
-* **Description:** Sets sensor alignment (legacy format).
-* **Payload:** (Matches `MSP_SENSOR_ALIGNMENT` outgoing structure)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `gyroAlign` | `uint8_t` | 1 | Ignored |
- | `accAlign` | `uint8_t` | 1 | Ignored |
- | `magAlign` | `uint8_t` | 1 | Sets `compassConfigMutable()->mag_align` (if `USE_MAG`) |
- | `opflowAlign` | `uint8_t` | 1 | Sets `opticalFlowConfigMutable()->opflow_align` (if `USE_OPFLOW`) |
-* **Notes:** Expects 4 bytes. Use `MSP_SET_BOARD_ALIGNMENT` for primary board orientation.
-
-### `MSP_SET_LED_STRIP_MODECOLOR` (221 / 0xDD)
-
-* **Direction:** In
-* **Description:** Sets the color index for a specific LED mode/function combination.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `modeIndex` | `uint8_t` | 1 | Index of the LED mode (`ledModeIndex_e` or `LED_MODE_COUNT` for special) |
- | `directionOrSpecialIndex` | `uint8_t` | 1 | Index of the direction or special color |
- | `colorIndex` | `uint8_t` | 1 | Index of the color to assign from `ledStripConfig()->colors` |
-* **Notes:** Only available if `USE_LED_STRIP` is defined. Expects 3 bytes. Returns error if setting fails (invalid index).
-
----
-
-## MSPv1 System & Debug Commands (239-254)
-
-### `MSP_SET_ACC_TRIM` (239 / 0xEF)
-
-* **Direction:** In
-* **Description:** Sets the accelerometer trim values (leveling calibration).
-* **Notes:** Not implemented in INAV `fc_msp.c`. Use `MSP_ACC_CALIBRATION`.
-
-### `MSP_ACC_TRIM` (240 / 0xF0)
-
-* **Direction:** Out
-* **Description:** Gets the accelerometer trim values.
-* **Notes:** Not implemented in INAV `fc_msp.c`. Calibration data via `MSP_CALIBRATION_DATA`.
-
-### `MSP_SERVO_MIX_RULES` (241 / 0xF1)
-
-* **Direction:** Out
-* **Description:** Retrieves the custom servo mixer rules (legacy format).
-* **Payload:** Repeated `MAX_SERVO_RULES` times:
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `targetChannel` | `uint8_t` | 1 | Index | Servo output channel index (0-based) |
- | `inputSource` | `uint8_t` | 1 | Enum | Enum `inputSource_e` Input source for the mix (RC chan, Roll, Pitch...) |
- | `rate` | `uint16_t` | 2 | % * 100? | Mixing rate/weight. Needs scaling check |
- | `speed` | `uint8_t` | 1 | 0-100 | Speed/Slew rate limit |
- | `reserved1` | `uint8_t` | 1 | - | Always 0 |
- | `legacyMax` | `uint8_t` | 1 | - | Always 100 (Legacy) |
- | `legacyBox` | `uint8_t` | 1 | - | Always 0 (Legacy) |
-* **Notes:** Superseded by `MSP2_INAV_SERVO_MIXER`.
-
-### `MSP_SET_SERVO_MIX_RULE` (242 / 0xF2)
-
-* **Direction:** In
-* **Description:** Sets a single custom servo mixer rule (legacy format).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `ruleIndex` | `uint8_t` | 1 | Index | Index of the rule to set (0 to `MAX_SERVO_RULES - 1`) |
- | `targetChannel` | `uint8_t` | 1 | Index | Servo output channel index |
- | `inputSource` | `uint8_t` | 1 | Enum | Enum `inputSource_e` Input source for the mix |
- | `rate` | `uint16_t` | 2 | % * 100? | Mixing rate/weight |
- | `speed` | `uint8_t` | 1 | 0-100 | Speed/Slew rate limit |
- | `legacyMinMax` | `uint16_t` | 2 | - | Ignored |
- | `legacyBox` | `uint8_t` | 1 | - | Ignored |
-* **Notes:** Expects 9 bytes. Returns error if index invalid. Calls `loadCustomServoMixer()`. Superseded by `MSP2_INAV_SET_SERVO_MIXER`.
-
-### `MSP_SET_PASSTHROUGH` (245 / 0xF5)
-
-* **Direction:** In/Out (Special: In command triggers passthrough mode, Reply confirms start)
-* **Description:** Enables serial passthrough mode to peripherals like ESCs (BLHeli 4-way) or other serial devices.
-* **Request Payload (Legacy - 4way):** None
-* **Request Payload (Extended):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `passthroughMode` | `uint8_t` | 1 | Type of passthrough Enum (`mspPassthroughType_e`: Serial ID, Serial Function, ESC 4way) |
- | `passthroughArgument` | `uint8_t` | 1 | Argument for the mode (e.g., Serial Port Identifier, Serial Function ID). Defaults to 0 if not sent |
-* **Reply Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `status` | `uint8_t` | 1 | 1 if passthrough started successfully, 0 on error (e.g., port not found). For 4way, returns number of ESCs found |
-* **Notes:** If successful, sets `mspPostProcessFn` to the appropriate handler (`mspSerialPassthroughFn` or `esc4wayProcess`). This handler takes over the serial port after the reply is sent. Requires `USE_SERIAL_4WAY_BLHELI_INTERFACE` for ESC passthrough.
-
-### `MSP_RTC` (246 / 0xF6)
-
-* **Direction:** Out
-* **Description:** Retrieves the current Real-Time Clock time.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `seconds` | `int32_t` | 4 | Seconds | Seconds since epoch (or relative time if not set). 0 if RTC time unknown |
- | `millis` | `uint16_t` | 2 | Milliseconds | Millisecond part of the time. 0 if RTC time unknown |
-* **Notes:** Requires RTC hardware/support. Returns (0, 0) if time is not available/set.
-
-### `MSP_SET_RTC` (247 / 0xF7)
-
-* **Direction:** In
-* **Description:** Sets the Real-Time Clock time.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `seconds` | `int32_t` | 4 | Seconds | Seconds component of time to set |
- | `millis` | `uint16_t` | 2 | Milliseconds | Millisecond component of time to set |
-* **Notes:** Requires RTC hardware/support. Expects 6 bytes. Uses `rtcSet()`.
-
-### `MSP_EEPROM_WRITE` (250 / 0xFA)
-
-* **Direction:** In
-* **Description:** Saves the current configuration from RAM to non-volatile memory (EEPROM/Flash).
-* **Payload:** None
-* **Notes:** Will fail if armed. Suspends RX, calls `writeEEPROM()`, `readEEPROM()`, resumes RX.
-
-### `MSP_DEBUGMSG` (253 / 0xFD)
-
-* **Direction:** Out
-* **Description:** Retrieves debug ("serial printf") messages from the firmware.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | Message Text | `char[]` | Variable | `NUL` terminated [debug message](https://github.com/iNavFlight/inav/blob/master/docs/development/serial_printf_debugging.md) text |
-
-### `MSP_DEBUG` (254 / 0xFE)
-
-* **Direction:** Out
-* **Description:** Retrieves values from the firmware's `debug[]` array (legacy 16-bit version).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `debugValues` | `uint16_t[4]` | 8 | First 4 values from the `debug` array |
-* **Notes:** Useful for developers. See `MSP2_INAV_DEBUG` for 32-bit values.
-
-### `MSP_V2_FRAME` (255 / 0xFF)
-
-* **Direction:** N/A (Indicator)
-* **Description:** This ID is used as a *payload indicator* within an MSPv1 message structure (`$M>`) to signify that the following payload conforms to the MSPv2 format. It's not a command itself.
-* **Notes:** See MSPv2 documentation for the actual frame structure that follows this indicator.
-
----
-
-## MSPv1 Extended/INAV Commands (150-166)
-
-### `MSP_STATUS_EX` (150 / 0x96)
-
-* **Direction:** Out
-* **Description:** Provides extended flight controller status, including CPU load, arming flags, and calibration status, in addition to `MSP_STATUS` fields.
-* **Payload:** (Starts with `MSP_STATUS` fields)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `cycleTime` | `uint16_t` | 2 | µs | Main loop cycle time |
- | `i2cErrors` | `uint16_t` | 2 | Count | I2C errors |
- | `sensorStatus` | `uint16_t` | 2 | Bitmask | Sensor status bitmask |
- | `activeModesLow` | `uint32_t` | 4 | Bitmask | First 32 active modes |
- | `profile` | `uint8_t` | 1 | Index | Current config profile index |
- | `cpuLoad` | `uint16_t` | 2 | % | Average system load percentage (`averageSystemLoadPercent`) |
- | `armingFlags` | `uint16_t` | 2 | Bitmask | Flight controller arming flags (`armingFlags`). Note: Truncated to 16 bits |
- | `accCalibAxisFlags` | `uint8_t` | 1 | Bitmask | Accelerometer calibrated axes flags (`accGetCalibrationAxisFlags()`) |
-* **Notes:** Superseded by `MSP2_INAV_STATUS` which provides the full 32-bit `armingFlags` and other enhancements.
-
-### `MSP_SENSOR_STATUS` (151 / 0x97)
-
-* **Direction:** Out
-* **Description:** Provides the hardware status for each individual sensor system.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `overallHealth` | `uint8_t` | 1 | Boolean | 1 if all essential hardware is healthy, 0 otherwise (`isHardwareHealthy()`) |
- | `gyroStatus` | `uint8_t` | 1 | Enum | Enum `hardwareSensorStatus_e` Gyro hardware status (`getHwGyroStatus()`) |
- | `accStatus` | `uint8_t` | 1 | Enum | Enum `hardwareSensorStatus_e` Accelerometer hardware status (`getHwAccelerometerStatus()`) |
- | `magStatus` | `uint8_t` | 1 | Enum | Enum `hardwareSensorStatus_e` Compass hardware status (`getHwCompassStatus()`) |
- | `baroStatus` | `uint8_t` | 1 | Enum | Enum `hardwareSensorStatus_e` Barometer hardware status (`getHwBarometerStatus()`) |
- | `gpsStatus` | `uint8_t` | 1 | Enum | Enum `hardwareSensorStatus_e` GPS hardware status (`getHwGPSStatus()`) |
- | `rangefinderStatus` | `uint8_t` | 1 | Enum | Enum `hardwareSensorStatus_e` Rangefinder hardware status (`getHwRangefinderStatus()`) |
- | `pitotStatus` | `uint8_t` | 1 | Enum | Enum `hardwareSensorStatus_e` Pitot hardware status (`getHwPitotmeterStatus()`) |
- | `opflowStatus` | `uint8_t` | 1 | Enum | Enum `hardwareSensorStatus_e` Optical Flow hardware status (`getHwOpticalFlowStatus()`) |
-* **Notes:** Status values likely correspond to `SENSOR_STATUS_*` enums (e.g., OK, Unhealthy, Not Present).
-
-### `MSP_UID` (160 / 0xA0)
-
-* **Direction:** Out
-* **Description:** Provides the unique identifier of the microcontroller.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `uid0` | `uint32_t` | 4 | First 32 bits of the unique ID (`U_ID_0`) |
- | `uid1` | `uint32_t` | 4 | Middle 32 bits of the unique ID (`U_ID_1`) |
- | `uid2` | `uint32_t` | 4 | Last 32 bits of the unique ID (`U_ID_2`) |
-* **Notes:** Total 12 bytes, representing a 96-bit unique ID.
-
-### `MSP_GPSSVINFO` (164 / 0xA4)
-
-* **Direction:** Out
-* **Description:** Provides satellite signal strength information (legacy U-Blox compatibility stub).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `protocolVersion` | `uint8_t` | 1 | Always 1 (Stub version) |
- | `numChannels` | `uint8_t` | 1 | Always 0 (Number of SV info channels reported) |
- | `hdopHundreds` | `uint8_t` | 1 | HDOP / 100 (`gpsSol.hdop / 100`) |
- | `hdopUnits` | `uint8_t` | 1 | HDOP / 100 (`gpsSol.hdop / 100`) |
-* **Notes:** Requires `USE_GPS`. This is just a stub in INAV and does not provide actual per-satellite signal info. `hdopUnits` duplicates `hdopHundreds`.
-
-### `MSP_GPSSTATISTICS` (166 / 0xA6)
-
-* **Direction:** Out
-* **Description:** Provides debugging statistics for the GPS communication link.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `lastMessageDt` | `uint16_t` | 2 | ms | Time since last valid GPS message (`gpsStats.lastMessageDt`) |
- | `errors` | `uint32_t` | 4 | Count | Number of GPS communication errors (`gpsStats.errors`) |
- | `timeouts` | `uint32_t` | 4 | Count | Number of GPS communication timeouts (`gpsStats.timeouts`) |
- | `packetCount` | `uint32_t` | 4 | Count | Number of valid GPS packets received (`gpsStats.packetCount`) |
- | `hdop` | `uint16_t` | 2 | HDOP * 100 | Horizontal Dilution of Precision (`gpsSol.hdop`) |
- | `eph` | `uint16_t` | 2 | cm | Estimated Horizontal Position Accuracy (`gpsSol.eph`) |
- | `epv` | `uint16_t` | 2 | cm | Estimated Vertical Position Accuracy (`gpsSol.epv`) |
-* **Notes:** Requires `USE_GPS`.
-
-### `MSP_TX_INFO` (187 / 0xBB)
-
-* **Direction:** Out
-* **Description:** Provides information potentially useful for transmitter LUA scripts.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `rssiSource` | `uint8_t` | 1 | Enum: Source of the RSSI value (`getRSSISource()`) |
- | `rtcDateTimeIsSet` | `uint8_t` | 1 | Boolean: 1 if the RTC has been set, 0 otherwise |
-* **Notes:** See `rssiSource_e`.
-
-### `MSP_SET_TX_INFO` (186 / 0xBA)
-
-* **Direction:** In
-* **Description:** Allows a transmitter LUA script (or similar) to send runtime information (currently only RSSI) to the firmware.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `rssi` | `uint8_t` | 1 | % | RSSI value (0-100) provided by the external source |
-* **Notes:** Calls `setRSSIFromMSP()`. Expects 1 byte.
-
----
-
-## MSPv2 Common Commands (0x1000 Range)
-
-These commands are part of the MSPv2 specification and are intended for general configuration and interaction.
-
-### `MSP2_COMMON_TZ` (0x1001 / 4097)
-
-* **Direction:** Out
-* **Description:** Gets the time zone offset configuration.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `tzOffsetMinutes` | `int16_t` | 2 | Minutes | Time zone offset from UTC (`timeConfig()->tz_offset`) |
- | `tzAutoDst` | `uint8_t` | 1 | Boolean | Automatic daylight saving time enabled (`timeConfig()->tz_automatic_dst`) |
-
-### `MSP2_COMMON_SET_TZ` (0x1002 / 4098)
-
-* **Direction:** In
-* **Description:** Sets the time zone offset configuration.
-* **Payload (Format 1 - Offset only):**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `tzOffsetMinutes` | `int16_t` | 2 | Minutes | Sets `timeConfigMutable()->tz_offset` |
-* **Payload (Format 2 - Offset + DST):**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `tzOffsetMinutes` | `int16_t` | 2 | Minutes | Sets `timeConfigMutable()->tz_offset` |
- | `tzAutoDst` | `uint8_t` | 1 | Boolean | Sets `timeConfigMutable()->tz_automatic_dst` |
-* **Notes:** Accepts 2 or 3 bytes.
-
-### `MSP2_COMMON_SETTING` (0x1003 / 4099)
-
-* **Direction:** In/Out
-* **Description:** Gets the value of a specific configuration setting, identified by name or index.
-* **Request Payload (By Name):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `settingName` | `char[]` | Variable | Null-terminated string containing the setting name (e.g., "gyro_main_lpf_hz") |
-* **Request Payload (By Index):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `zeroByte` | `uint8_t` | 1 | Must be 0 |
- | `settingIndex` | `uint16_t` | 2 | Absolute index of the setting |
-* **Reply Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `settingValue` | `uint8_t[]` | Variable | Raw byte value of the setting. Size depends on the setting's type (`settingGetValueSize()`) |
-* **Notes:** Returns error if setting not found. Use `MSP2_COMMON_SETTING_INFO` to discover settings, types, and sizes.
-
-### `MSP2_COMMON_SET_SETTING` (0x1004 / 4100)
-
-* **Direction:** In
-* **Description:** Sets the value of a specific configuration setting, identified by name or index.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `settingIdentifier` | Varies | Variable | Setting name (null-terminated string) OR Index (0x00 followed by `uint16_t` index) |
- | `settingValue` | `uint8_t[]` | Variable | Raw byte value to set for the setting. Size must match the setting's type |
-* **Notes:** Performs type checking and range validation (min/max). Returns error if setting not found, value size mismatch, or value out of range. Handles different data types (`uint8`, `int16`, `float`, `string`, etc.) internally.
-
-### `MSP2_COMMON_MOTOR_MIXER` (0x1005 / 4101)
-
-* **Direction:** Out
-* **Description:** Retrieves the current motor mixer configuration (throttle, roll, pitch, yaw weights for each motor) for the primary and secondary mixer profiles.
-* **Payload (Profile 1):** Repeated `MAX_SUPPORTED_MOTORS` times:
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `throttleWeight` | `uint16_t` | 2 | Scaled (0-4000) | Throttle weight * 1000, offset by 2000. (Range -2.0 to +2.0 -> 0 to 4000) |
- | `rollWeight` | `uint16_t` | 2 | Scaled (0-4000) | Roll weight * 1000, offset by 2000 |
- | `pitchWeight` | `uint16_t` | 2 | Scaled (0-4000) | Pitch weight * 1000, offset by 2000 |
- | `yawWeight` | `uint16_t` | 2 | Scaled (0-4000) | Yaw weight * 1000, offset by 2000 |
- | `throttleWeight` | `uint16_t` | 2 | (Optional) Scaled (0-4000) | Profile 2 Throttle weight |
- | `rollWeight` | `uint16_t` | 2 | (Optional) Scaled (0-4000) | Profile 2 Roll weight |
- | `pitchWeight` | `uint16_t` | 2 | (Optional) Scaled (0-4000) | Profile 2 Pitch weight |
- | `yawWeight` | `uint16_t` | 2 | (Optional) Scaled (0-4000) | Profile 2 Yaw weight |
-* **Notes:** Scaling is `(float_weight + 2.0) * 1000`. `primaryMotorMixer()` provides the data.
-
-### `MSP2_COMMON_SET_MOTOR_MIXER` (0x1006 / 4102)
-
-* **Direction:** In
-* **Description:** Sets the motor mixer weights for a single motor in the primary mixer profile.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `motorIndex` | `uint8_t` | 1 | Index | Index of the motor to configure (0 to `MAX_SUPPORTED_MOTORS - 1`) |
- | `throttleWeight` | `uint16_t` | 2 | Scaled (0-4000) | Sets throttle weight from `(value / 1000.0) - 2.0` |
- | `rollWeight` | `uint16_t` | 2 | Scaled (0-4000) | Sets roll weight from `(value / 1000.0) - 2.0` |
- | `pitchWeight` | `uint16_t` | 2 | Scaled (0-4000) | Sets pitch weight from `(value / 1000.0) - 2.0` |
- | `yawWeight` | `uint16_t` | 2 | Scaled (0-4000) | Sets yaw weight from `(value / 1000.0) - 2.0` |
-* **Notes:** Expects 9 bytes. Modifies `primaryMotorMixerMutable()`. Returns error if index is invalid.
-
-### `MSP2_COMMON_SETTING_INFO` (0x1007 / 4103)
-
-* **Direction:** In/Out
-* **Description:** Gets detailed information about a specific configuration setting (name, type, range, flags, current value, etc.).
-* **Request Payload:** Same as `MSP2_COMMON_SETTING` request (name string or index).
-* **Reply Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `settingName` | `char[]` | Variable | Null-terminated setting name |
- | `pgn` | `uint16_t` | 2 | Parameter Group Number (PGN) ID |
- | `type` | `uint8_t` | 1 | Variable type (`VAR_UINT8`, `VAR_FLOAT`, etc.) |
- | `section` | `uint8_t` | 1 | Setting section (`MASTER_VALUE`, `PROFILE_VALUE`, etc.) |
- | `mode` | `uint8_t` | 1 | Setting mode (`MODE_NORMAL`, `MODE_LOOKUP`, etc.) |
- | `minValue` | `int32_t` | 4 | Minimum allowed value (as signed 32-bit) |
- | `maxValue` | `uint32_t` | 4 | Maximum allowed value (as unsigned 32-bit) |
- | `settingIndex` | `uint16_t` | 2 | Absolute index of the setting |
- | `profileIndex` | `uint8_t` | 1 | Current profile index (if applicable, else 0) |
- | `profileCount` | `uint8_t` | 1 | Total number of profiles (if applicable, else 0) |
- | `lookupNames` | `char[]` | Variable | (If `mode == MODE_LOOKUP`) Series of null-terminated strings for each possible value from min to max |
- | `settingValue` | `uint8_t[]` | Variable | Current raw byte value of the setting |
-* **Notes:**
-
- * Very useful for configurators to dynamically build interfaces. Returns error if setting not found.
- * This is a variable length message, depending on the name length, `mode`, and `type`.
-
-### `MSP2_COMMON_PG_LIST` (0x1008 / 4104)
-
-* **Direction:** In/Out
-* **Description:** Gets a list of Parameter Group Numbers (PGNs) used by settings, along with the start and end setting indexes for each group. Can request info for a single PGN.
-* **Request Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `pgn` | `uint16_t` | 2 | (Optional) PGN ID to query. If omitted, returns all used PGNs |
-* **Reply Payload:** Repeated for each PGN found:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `pgn` | `uint16_t` | 2 | Parameter Group Number (PGN) ID |
- | `startIndex` | `uint16_t` | 2 | Absolute index of the first setting in this group |
- | `endIndex` | `uint16_t` | 2 | Absolute index of the last setting in this group |
-* **Notes:** Allows efficient fetching of related settings by group.
-
-### `MSP2_COMMON_SERIAL_CONFIG` (0x1009 / 4105)
-
-* **Direction:** Out
-* **Description:** Retrieves the configuration for all available serial ports.
-* **Payload:** Repeated for each available serial port:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `identifier` | `uint8_t` | 1 | Port identifier Enum (`serialPortIdentifier_e`) |
- | `functionMask` | `uint32_t` | 4 | Bitmask of enabled functions (`FUNCTION_*`) |
- | `mspBaudIndex` | `uint8_t` | 1 | Baud rate index for MSP function |
- | `gpsBaudIndex` | `uint8_t` | 1 | Baud rate index for GPS function |
- | `telemetryBaudIndex` | `uint8_t` | 1 | Baud rate index for Telemetry function |
- | `peripheralBaudIndex` | `uint8_t` | 1 | Baud rate index for other peripheral functions |
-* **Notes:** Baud rate indexes map to actual baud rates (e.g., 9600, 115200). See `baudRates` array.
-
-### `MSP2_COMMON_SET_SERIAL_CONFIG` (0x100A / 4106)
-
-* **Direction:** In
-* **Description:** Sets the configuration for one or more serial ports.
-* **Payload:** Repeated for each port being configured:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `identifier` | `uint8_t` | 1 | Port identifier Enum (`serialPortIdentifier_e`) |
- | `functionMask` | `uint32_t` | 4 | Bitmask of functions to enable |
- | `mspBaudIndex` | `uint8_t` | 1 | Baud rate index for MSP |
- | `gpsBaudIndex` | `uint8_t` | 1 | Baud rate index for GPS |
- | `telemetryBaudIndex` | `uint8_t` | 1 | Baud rate index for Telemetry |
- | `peripheralBaudIndex` | `uint8_t` | 1 | Baud rate index for peripherals |
-* **Notes:** Payload size must be a multiple of the size of one port config entry (1 + 4 + 4 = 9 bytes). Returns error if identifier is invalid or size is incorrect. Baud rate indexes are constrained `BAUD_MIN` to `BAUD_MAX`.
-
-### `MSP2_COMMON_SET_RADAR_POS` (0x100B / 4107)
-
-* **Direction:** In
-* **Description:** Sets the position and status information for a "radar" Point of Interest (POI). Used for displaying other craft/objects on the OSD map.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `poiIndex` | `uint8_t` | 1 | Index | Index of the POI slot (0 to `RADAR_MAX_POIS - 1`) |
- | `state` | `uint8_t` | 1 | Enum | Status of the POI (0=undefined, 1=armed, 2=lost) |
- | `latitude` | `int32_t` | 4 | deg * 1e7 | Latitude of the POI |
- | `longitude` | `int32_t` | 4 | deg * 1e7 | Longitude of the POI |
- | `altitude` | `int32_t` | 4 | cm | Altitude of the POI |
- | `heading` | `int16_t` | 2 | degrees | Heading of the POI |
- | `speed` | `uint16_t` | 2 | cm/s | Speed of the POI |
- | `linkQuality` | `uint8_t` | 1 | 0-4 | Link quality indicator |
-* **Notes:** Expects 19 bytes. Updates the `radar_pois` array.
-
-### `MSP2_COMMON_SET_RADAR_ITD` (0x100C / 4108)
-
-* **Direction:** In
-* **Description:** Sets radar information to display (likely internal/unused).
-* **Notes:** Not implemented in INAV `fc_msp.c`.
-
-### `MSP2_COMMON_SET_MSP_RC_LINK_STATS` (0x100D / 4109)
-
-* **Direction:** In
-* **Description:** Provides RC link statistics (RSSI, LQ) to the FC, typically from an MSP-based RC link (like ExpressLRS). Sent periodically by the RC link.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `sublinkID` | `uint8_t` | 1 | - | Sublink identifier (usually 0) |
- | `validLink` | `uint8_t` | 1 | Boolean | Indicates if the link is currently valid (not in failsafe) |
- | `rssiPercent` | `uint8_t` | 1 | % | Uplink RSSI percentage (0-100) |
- | `uplinkRSSI_dBm` | `uint8_t` | 1 | -dBm | Uplink RSSI in dBm (sent as positive, e.g., 70 means -70dBm) |
- | `downlinkLQ` | `uint8_t` | 1 | % | Downlink Link Quality (0-100) |
- | `uplinkLQ` | `uint8_t` | 1 | % | Uplink Link Quality (0-100) |
- | `uplinkSNR` | `int8_t` | 1 | dB | Uplink Signal-to-Noise Ratio |
-* **Notes:** Requires `USE_RX_MSP`. Expects at least 7 bytes. Updates `rxLinkStatistics` and sets RSSI via `setRSSIFromMSP_RC()` only if `sublinkID` is 0. This message expects **no reply** (`MSP_RESULT_NO_REPLY`).
-
-### `MSP2_COMMON_SET_MSP_RC_INFO` (0x100E / 4110)
-
-* **Direction:** In
-* **Description:** Provides additional RC link information (power levels, band, mode) to the FC from an MSP-based RC link. Sent less frequently than link stats.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `sublinkID` | `uint8_t` | 1 | - | Sublink identifier (usually 0) |
- | `uplinkTxPower` | `uint16_t` | 2 | mW? | Uplink transmitter power level |
- | `downlinkTxPower` | `uint16_t` | 2 | mW? | Downlink transmitter power level |
- | `band` | `char[4]` | 4 | - | Operating band string (e.g., "2G4", "900") |
- | `mode` | `char[6]` | 6 | - | Operating mode/rate string (e.g., "100HZ", "F1000") |
-* **Notes:** Requires `USE_RX_MSP`. Expects at least 15 bytes. Updates `rxLinkStatistics` only if `sublinkID` is 0. Converts band/mode strings to uppercase. This message expects **no reply** (`MSP_RESULT_NO_REPLY`).
-
----
-
-## MSPv2 INAV Specific Commands (0x2000 Range)
-
-These commands are specific extensions added by the INAV project.
-
-### `MSP2_INAV_STATUS` (0x2000 / 8192)
-
-* **Direction:** Out
-* **Description:** Provides comprehensive flight controller status, extending `MSP_STATUS_EX` with full arming flags, battery profile, and mixer profile.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `cycleTime` | `uint16_t` | 2 | µs | Main loop cycle time |
- | `i2cErrors` | `uint16_t` | 2 | Count | I2C errors |
- | `sensorStatus` | `uint16_t` | 2 | Bitmask | Sensor status bitmask |
- | `cpuLoad` | `uint16_t` | 2 | % | Average system load percentage |
- | `profileAndBattProfile` | `uint8_t` | 1 | Packed | Bits 0-3: Config profile index (`getConfigProfile()`), Bits 4-7: Battery profile index (`getConfigBatteryProfile()`) |
- | `armingFlags` | `uint32_t` | 4 | Bitmask | Full 32-bit flight controller arming flags (`armingFlags`) |
- | `activeModes` | `boxBitmask_t` | `sizeof(boxBitmask_t)` | Bitmask | Full bitmask of active flight modes (`packBoxModeFlags()`) |
- | `mixerProfile` | `uint8_t` | 1 | Index | Current mixer profile index (`getConfigMixerProfile()`) |
-
-### `MSP2_INAV_OPTICAL_FLOW` (0x2001 / 8193)
-
-* **Direction:** Out
-* **Description:** Provides data from the optical flow sensor.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `quality` | `uint8_t` | 1 | 0-255 | Raw quality indicator from the sensor (`opflow.rawQuality`). 0 if `USE_OPFLOW` disabled |
- | `flowRateX` | `int16_t` | 2 | degrees/s | Optical flow rate X (roll axis) (`RADIANS_TO_DEGREES(opflow.flowRate[X])`). 0 if `USE_OPFLOW` disabled |
- | `flowRateY` | `int16_t` | 2 | degrees/s | Optical flow rate Y (pitch axis) (`RADIANS_TO_DEGREES(opflow.flowRate[Y])`). 0 if `USE_OPFLOW` disabled |
- | `bodyRateX` | `int16_t` | 2 | degrees/s | Compensated body rate X (roll axis) (`RADIANS_TO_DEGREES(opflow.bodyRate[X])`). 0 if `USE_OPFLOW` disabled |
- | `bodyRateY` | `int16_t` | 2 | degrees/s | Compensated body rate Y (pitch axis) (`RADIANS_TO_DEGREES(opflow.bodyRate[Y])`). 0 if `USE_OPFLOW` disabled |
-* **Notes:** Requires `USE_OPFLOW`.
-
-### `MSP2_INAV_ANALOG` (0x2002 / 8194)
-
-* **Direction:** Out
-* **Description:** Provides detailed analog sensor readings, superseding `MSP_ANALOG` with higher precision and additional fields.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `batteryFlags` | `uint8_t` | 1 | Bitmask | Battery status flags: Bit 0=Full on plug-in, Bit 1=Use capacity threshold, Bit 2-3=Battery State enum (`getBatteryState()`), Bit 4-7=Cell Count (`getBatteryCellCount()`) |
- | `vbat` | `uint16_t` | 2 | 0.01V | Battery voltage (`getBatteryVoltage()`) |
- | `amperage` | `uint16_t` | 2 | 0.01A | Current draw (`getAmperage()`) |
- | `powerDraw` | `uint32_t` | 4 | mW | Power draw (`getPower()`) |
- | `mAhDrawn` | `uint32_t` | 4 | mAh | Consumed capacity (`getMAhDrawn()`) |
- | `mWhDrawn` | `uint32_t` | 4 | mWh | Consumed energy (`getMWhDrawn()`) |
- | `remainingCapacity` | `uint32_t` | 4 | mAh/mWh | Estimated remaining capacity (`getBatteryRemainingCapacity()`) |
- | `percentageRemaining` | `uint8_t` | 1 | % | Estimated remaining capacity percentage (`calculateBatteryPercentage()`) |
- | `rssi` | `uint16_t` | 2 | 0-1023 or % | RSSI value (`getRSSI()`) |
-
-### `MSP2_INAV_MISC` (0x2003 / 8195)
-
-* **Direction:** Out
-* **Description:** Retrieves miscellaneous configuration settings, superseding `MSP_MISC` with higher precision and capacity fields.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `midRc` | `uint16_t` | 2 | PWM | Mid RC value (`PWM_RANGE_MIDDLE`) |
- | `legacyMinThrottle` | `uint16_t` | 2 | - | Always 0 (Legacy) |
- | `maxThrottle` | `uint16_t` | 2 | PWM | Maximum throttle command (`getMaxThrottle()`) |
- | `minCommand` | `uint16_t` | 2 | PWM | Minimum motor command (`motorConfig()->mincommand`) |
- | `failsafeThrottle` | `uint16_t` | 2 | PWM | Failsafe throttle level (`currentBatteryProfile->failsafe_throttle`) |
- | `gpsType` | `uint8_t` | 1 | Enum | Enum `gpsProvider_e` GPS provider type (`gpsConfig()->provider`). 0 if `USE_GPS` disabled |
- | `legacyGpsBaud` | `uint8_t` | 1 | - | Always 0 (Legacy) |
- | `gpsSbasMode` | `uint8_t` | 1 | Enum | Enum `sbasMode_e` GPS SBAS mode (`gpsConfig()->sbasMode`). 0 if `USE_GPS` disabled |
- | `rssiChannel` | `uint8_t` | 1 | Index | RSSI channel index (1-based) (`rxConfig()->rssi_channel`) |
- | `magDeclination` | `uint16_t` | 2 | 0.1 degrees | Magnetic declination / 10 (`compassConfig()->mag_declination / 10`). 0 if `USE_MAG` disabled |
- | `vbatScale` | `uint16_t` | 2 | Scale | Voltage scale (`batteryMetersConfig()->voltage.scale`). 0 if `USE_ADC` disabled |
- | `vbatSource` | `uint8_t` | 1 | Enum | Enum `batVoltageSource_e` Voltage source (`batteryMetersConfig()->voltageSource`). 0 if `USE_ADC` disabled |
- | `cellCount` | `uint8_t` | 1 | Count | Configured cell count (`currentBatteryProfile->cells`). 0 if `USE_ADC` disabled |
- | `vbatCellDetect` | `uint16_t` | 2 | 0.01V | Cell detection voltage (`currentBatteryProfile->voltage.cellDetect`). 0 if `USE_ADC` disabled |
- | `vbatMinCell` | `uint16_t` | 2 | 0.01V | Min cell voltage (`currentBatteryProfile->voltage.cellMin`). 0 if `USE_ADC` disabled |
- | `vbatMaxCell` | `uint16_t` | 2 | 0.01V | Max cell voltage (`currentBatteryProfile->voltage.cellMax`). 0 if `USE_ADC` disabled |
- | `vbatWarningCell` | `uint16_t` | 2 | 0.01V | Warning cell voltage (`currentBatteryProfile->voltage.cellWarning`). 0 if `USE_ADC` disabled |
- | `capacityValue` | `uint32_t` | 4 | mAh/mWh | Battery capacity (`currentBatteryProfile->capacity.value`) |
- | `capacityWarning` | `uint32_t` | 4 | mAh/mWh | Capacity warning threshold (`currentBatteryProfile->capacity.warning`) |
- | `capacityCritical` | `uint32_t` | 4 | mAh/mWh | Capacity critical threshold (`currentBatteryProfile->capacity.critical`) |
- | `capacityUnit` | `uint8_t` | 1 | Enum | Enum `batCapacityUnit_e` Capacity unit ('batteryMetersConfig()->capacity_unit') |
-
-### `MSP2_INAV_SET_MISC` (0x2004 / 8196)
-
-* **Direction:** In
-* **Description:** Sets miscellaneous configuration settings, superseding `MSP_SET_MISC`.
-* **Payload:** (Matches `MSP2_INAV_MISC` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `midRc` | `uint16_t` | 2 | PWM | Ignored |
- | `legacyMinThrottle` | `uint16_t` | 2 | - | Ignored |
- | `legacyMaxThrottle` | `uint16_t` | 2 | - | Ignored |
- | `minCommand` | `uint16_t` | 2 | PWM | Sets `motorConfigMutable()->mincommand` (constrained) |
- | `failsafeThrottle` | `uint16_t` | 2 | PWM | Sets `currentBatteryProfileMutable->failsafe_throttle` (constrained) |
- | `gpsType` | `uint8_t` | 1 | Enum | Enum `gpsProvider_e` Sets `gpsConfigMutable()->provider` (if `USE_GPS`) |
- | `legacyGpsBaud` | `uint8_t` | 1 | - | Ignored |
- | `gpsSbasMode` | `uint8_t` | 1 | Enum | Enum `sbasMode_e` Sets `gpsConfigMutable()->sbasMode` (if `USE_GPS`) |
- | `rssiChannel` | `uint8_t` | 1 | Index | Sets `rxConfigMutable()->rssi_channel` (constrained). Updates source |
- | `magDeclination` | `uint16_t` | 2 | 0.1 degrees | Sets `compassConfigMutable()->mag_declination = value * 10` (if `USE_MAG`) |
- | `vbatScale` | `uint16_t` | 2 | Scale | Sets `batteryMetersConfigMutable()->voltage.scale` (if `USE_ADC`) |
- | `vbatSource` | `uint8_t` | 1 | Enum | Enum `batVoltageSource_e` Sets `batteryMetersConfigMutable()->voltageSource` (if `USE_ADC`, validated) |
- | `cellCount` | `uint8_t` | 1 | Count | Sets `currentBatteryProfileMutable->cells` (if `USE_ADC`) |
- | `vbatCellDetect` | `uint16_t` | 2 | 0.01V | Sets `currentBatteryProfileMutable->voltage.cellDetect` (if `USE_ADC`) |
- | `vbatMinCell` | `uint16_t` | 2 | 0.01V | Sets `currentBatteryProfileMutable->voltage.cellMin` (if `USE_ADC`) |
- | `vbatMaxCell` | `uint16_t` | 2 | 0.01V | Sets `currentBatteryProfileMutable->voltage.cellMax` (if `USE_ADC`) |
- | `vbatWarningCell` | `uint16_t` | 2 | 0.01V | Sets `currentBatteryProfileMutable->voltage.cellWarning` (if `USE_ADC`) |
- | `capacityValue` | `uint32_t` | 4 | mAh/mWh | Sets `currentBatteryProfileMutable->capacity.value` |
- | `capacityWarning` | `uint32_t` | 4 | mAh/mWh | Sets `currentBatteryProfileMutable->capacity.warning` |
- | `capacityCritical` | `uint32_t` | 4 | mAh/mWh | Sets `currentBatteryProfileMutable->capacity.critical` |
- | `capacityUnit` | `uint8_t` | 1 | Enum | Enum `batCapacityUnit_e` sets Capacity unit ('batteryMetersConfig()->capacity_unit'). Updates OSD energy unit if changed |
-* **Notes:** Expects 41 bytes. Performs validation on `vbatSource` and `capacityUnit`.
-
-### `MSP2_INAV_BATTERY_CONFIG` (0x2005 / 8197)
-
-* **Direction:** Out
-* **Description:** Retrieves the configuration specific to the battery voltage and current sensors and capacity settings for the current battery profile.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `vbatScale` | `uint16_t` | 2 | Scale | Voltage scale (`batteryMetersConfig()->voltage.scale`) |
- | `vbatSource` | `uint8_t` | 1 | Enum | Enum `batVoltageSource_e` Voltage source (`batteryMetersConfig()->voltageSource`) |
- | `cellCount` | `uint8_t` | 1 | Count | Configured cell count (`currentBatteryProfile->cells`) |
- | `vbatCellDetect` | `uint16_t` | 2 | 0.01V | Cell detection voltage (`currentBatteryProfile->voltage.cellDetect`) |
- | `vbatMinCell` | `uint16_t` | 2 | 0.01V | Min cell voltage (`currentBatteryProfile->voltage.cellMin`) |
- | `vbatMaxCell` | `uint16_t` | 2 | 0.01V | Max cell voltage (`currentBatteryProfile->voltage.cellMax`) |
- | `vbatWarningCell` | `uint16_t` | 2 | 0.01V | Warning cell voltage (`currentBatteryProfile->voltage.cellWarning`) |
- | `currentOffset` | `uint16_t` | 2 | mV | Current sensor offset (`batteryMetersConfig()->current.offset`) |
- | `currentScale` | `uint16_t` | 2 | Scale | Current sensor scale (`batteryMetersConfig()->current.scale`) |
- | `capacityValue` | `uint32_t` | 4 | mAh/mWh | Battery capacity (`currentBatteryProfile->capacity.value`) |
- | `capacityWarning` | `uint32_t` | 4 | mAh/mWh | Capacity warning threshold (`currentBatteryProfile->capacity.warning`) |
- | `capacityCritical` | `uint32_t` | 4 | mAh/mWh | Capacity critical threshold (`currentBatteryProfile->capacity.critical`) |
- | `capacityUnit` | `uint8_t` | 1 | Enum | Enum `batCapacityUnit_e` Capacity unit ('batteryMetersConfig()->capacity_unit') |
-* **Notes:** Fields are 0 if `USE_ADC` is not defined.
-
-### `MSP2_INAV_SET_BATTERY_CONFIG` (0x2006 / 8198)
-
-* **Direction:** In
-* **Description:** Sets the battery voltage/current sensor configuration and capacity settings for the current battery profile.
-* **Payload:** (Matches `MSP2_INAV_BATTERY_CONFIG` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `vbatScale` | `uint16_t` | 2 | Scale | Sets `batteryMetersConfigMutable()->voltage.scale` (if `USE_ADC`) |
- | `vbatSource` | `uint8_t` | 1 | Enum | Enum `batVoltageSource_e` Sets `batteryMetersConfigMutable()->voltageSource` (if `USE_ADC`, validated) |
- | `cellCount` | `uint8_t` | 1 | Count | Sets `currentBatteryProfileMutable->cells` (if `USE_ADC`) |
- | `vbatCellDetect` | `uint16_t` | 2 | 0.01V | Sets `currentBatteryProfileMutable->voltage.cellDetect` (if `USE_ADC`) |
- | `vbatMinCell` | `uint16_t` | 2 | 0.01V | Sets `currentBatteryProfileMutable->voltage.cellMin` (if `USE_ADC`) |
- | `vbatMaxCell` | `uint16_t` | 2 | 0.01V | Sets `currentBatteryProfileMutable->voltage.cellMax` (if `USE_ADC`) |
- | `vbatWarningCell` | `uint16_t` | 2 | 0.01V | Sets `currentBatteryProfileMutable->voltage.cellWarning` (if `USE_ADC`) |
- | `currentOffset` | `uint16_t` | 2 | mV | Sets `batteryMetersConfigMutable()->current.offset` |
- | `currentScale` | `uint16_t` | 2 | Scale | Sets `batteryMetersConfigMutable()->current.scale` |
- | `capacityValue` | `uint32_t` | 4 | mAh/mWh | Sets `currentBatteryProfileMutable->capacity.value` |
- | `capacityWarning` | `uint32_t` | 4 | mAh/mWh | Sets `currentBatteryProfileMutable->capacity.warning` |
- | `capacityCritical` | `uint32_t` | 4 | mAh/mWh | Sets `currentBatteryProfileMutable->capacity.critical` |
- | `capacityUnit` | `uint8_t` | 1 | Enum | Enum `batCapacityUnit_e` sets Capacity unit ('batteryMetersConfig()->capacity_unit') Updates OSD energy unit if changed |
-* **Notes:** Expects 29 bytes. Performs validation on `vbatSource` and `capacityUnit`.
-
-### `MSP2_INAV_RATE_PROFILE` (0x2007 / 8199)
-
-* **Direction:** Out
-* **Description:** Retrieves the rates and expos for the current control rate profile, including both stabilized and manual flight modes. Supersedes `MSP_RC_TUNING`.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `throttleMid` | `uint8_t` | 1 | Throttle Midpoint (`currentControlRateProfile->throttle.rcMid8`) |
- | `throttleExpo` | `uint8_t` | 1 | Throttle Expo (`currentControlRateProfile->throttle.rcExpo8`) |
- | `dynamicThrottlePID` | `uint8_t` | 1 | TPA value (`currentControlRateProfile->throttle.dynPID`) |
- | `tpaBreakpoint` | `uint16_t` | 2 | TPA breakpoint (`currentControlRateProfile->throttle.pa_breakpoint`) |
- | `stabRcExpo` | `uint8_t` | 1 | Stabilized Roll/Pitch Expo (`currentControlRateProfile->stabilized.rcExpo8`) |
- | `stabRcYawExpo` | `uint8_t` | 1 | Stabilized Yaw Expo (`currentControlRateProfile->stabilized.rcYawExpo8`) |
- | `stabRollRate` | `uint8_t` | 1 | Stabilized Roll Rate (`currentControlRateProfile->stabilized.rates[FD_ROLL]`) |
- | `stabPitchRate` | `uint8_t` | 1 | Stabilized Pitch Rate (`currentControlRateProfile->stabilized.rates[FD_PITCH]`) |
- | `stabYawRate` | `uint8_t` | 1 | Stabilized Yaw Rate (`currentControlRateProfile->stabilized.rates[FD_YAW]`) |
- | `manualRcExpo` | `uint8_t` | 1 | Manual Roll/Pitch Expo (`currentControlRateProfile->manual.rcExpo8`) |
- | `manualRcYawExpo` | `uint8_t` | 1 | Manual Yaw Expo (`currentControlRateProfile->manual.rcYawExpo8`) |
- | `manualRollRate` | `uint8_t` | 1 | Manual Roll Rate (`currentControlRateProfile->manual.rates[FD_ROLL]`) |
- | `manualPitchRate` | `uint8_t` | 1 | Manual Pitch Rate (`currentControlRateProfile->manual.rates[FD_PITCH]`) |
- | `manualYawRate` | `uint8_t` | 1 | Manual Yaw Rate (`currentControlRateProfile->manual.rates[FD_YAW]`) |
-
-### `MSP2_INAV_SET_RATE_PROFILE` (0x2008 / 8200)
-
-* **Direction:** In
-* **Description:** Sets the rates and expos for the current control rate profile (stabilized and manual). Supersedes `MSP_SET_RC_TUNING`.
-* **Payload:** (Matches `MSP2_INAV_RATE_PROFILE` structure)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `throttleMid` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->throttle.rcMid8` |
- | `throttleExpo` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->throttle.rcExpo8` |
- | `dynamicThrottlePID` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->throttle.dynPID` |
- | `tpaBreakpoint` | `uint16_t` | 2 | Sets `currentControlRateProfile_p->throttle.pa_breakpoint` |
- | `stabRcExpo` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->stabilized.rcExpo8` |
- | `stabRcYawExpo` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->stabilized.rcYawExpo8` |
- | `stabRollRate` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->stabilized.rates[FD_ROLL]` (constrained) |
- | `stabPitchRate` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->stabilized.rates[FD_PITCH]` (constrained) |
- | `stabYawRate` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->stabilized.rates[FD_YAW]` (constrained) |
- | `manualRcExpo` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->manual.rcExpo8` |
- | `manualRcYawExpo` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->manual.rcYawExpo8` |
- | `manualRollRate` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->manual.rates[FD_ROLL]` (constrained) |
- | `manualPitchRate` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->manual.rates[FD_PITCH]` (constrained) |
- | `manualYawRate` | `uint8_t` | 1 | Sets `currentControlRateProfile_p->manual.rates[FD_YAW]` (constrained) |
-* **Notes:** Expects 15 bytes. Constraints applied to rates based on axis.
-
-### `MSP2_INAV_AIR_SPEED` (0x2009 / 8201)
-
-* **Direction:** Out
-* **Description:** Retrieves the estimated or measured airspeed.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `airspeed` | `uint32_t` | 4 | cm/s | Estimated/measured airspeed (`getAirspeedEstimate()`). 0 if `USE_PITOT` disabled or no valid data |
-* **Notes:** Requires `USE_PITOT` for measured airspeed. May return GPS ground speed if pitot unavailable but GPS is present and configured.
-
-### `MSP2_INAV_OUTPUT_MAPPING` (0x200A / 8202)
-
-* **Direction:** Out
-* **Description:** Retrieves the output mapping configuration (identifies which timer outputs are used for Motors/Servos). Legacy version sending only 8-bit usage flags.
-* **Payload:** Repeated for each Motor/Servo timer:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `usageFlags` | `uint8_t` | 1 | Timer usage flags (truncated). `TIM_USE_MOTOR` or `TIM_USE_SERVO` |
-* **Notes:** Superseded by `MSP2_INAV_OUTPUT_MAPPING_EXT2`. Only includes timers *not* used for PPM/PWM input.
-
-### `MSP2_INAV_MC_BRAKING` (0x200B / 8203)
-
-* **Direction:** Out
-* **Description:** Retrieves configuration parameters for the multirotor braking mode feature.
-* **Payload:** (Only if `USE_MR_BRAKING_MODE` defined)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `brakingSpeedThreshold` | `uint16_t` | 2 | cm/s | Speed above which braking engages (`navConfig()->mc.braking_speed_threshold`) |
- | `brakingDisengageSpeed` | `uint16_t` | 2 | cm/s | Speed below which braking disengages (`navConfig()->mc.braking_disengage_speed`) |
- | `brakingTimeout` | `uint16_t` | 2 | ms | Timeout before braking force reduces (`navConfig()->mc.braking_timeout`) |
- | `brakingBoostFactor` | `uint8_t` | 1 | % | Boost factor applied during braking (`navConfig()->mc.braking_boost_factor`) |
- | `brakingBoostTimeout` | `uint16_t` | 2 | ms | Timeout for the boost factor (`navConfig()->mc.braking_boost_timeout`) |
- | `brakingBoostSpeedThreshold`| `uint16_t` | 2 | cm/s | Speed threshold for boost engagement (`navConfig()->mc.braking_boost_speed_threshold`) |
- | `brakingBoostDisengageSpeed`| `uint16_t` | 2 | cm/s | Speed threshold for boost disengagement (`navConfig()->mc.braking_boost_disengage_speed`) |
- | `brakingBankAngle` | `uint8_t` | 1 | degrees | Maximum bank angle allowed during braking (`navConfig()->mc.braking_bank_angle`) |
-* **Notes:** Payload is empty if `USE_MR_BRAKING_MODE` is not defined.
-
-### `MSP2_INAV_SET_MC_BRAKING` (0x200C / 8204)
-
-* **Direction:** In
-* **Description:** Sets configuration parameters for the multirotor braking mode feature.
-* **Payload:** (Matches `MSP2_INAV_MC_BRAKING` structure, requires `USE_MR_BRAKING_MODE`)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `brakingSpeedThreshold` | `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->mc.braking_speed_threshold` |
- | `brakingDisengageSpeed` | `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->mc.braking_disengage_speed` |
- | `brakingTimeout` | `uint16_t` | 2 | ms | Sets `navConfigMutable()->mc.braking_timeout` |
- | `brakingBoostFactor` | `uint8_t` | 1 | % | Sets `navConfigMutable()->mc.braking_boost_factor` |
- | `brakingBoostTimeout` | `uint16_t` | 2 | ms | Sets `navConfigMutable()->mc.braking_boost_timeout` |
- | `brakingBoostSpeedThreshold`| `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->mc.braking_boost_speed_threshold` |
- | `brakingBoostDisengageSpeed`| `uint16_t` | 2 | cm/s | Sets `navConfigMutable()->mc.braking_boost_disengage_speed` |
- | `brakingBankAngle` | `uint8_t` | 1 | degrees | Sets `navConfigMutable()->mc.braking_bank_angle` |
-* **Notes:** Expects 14 bytes. Returns error if `USE_MR_BRAKING_MODE` is not defined.
-
-### `MSP2_INAV_OUTPUT_MAPPING_EXT` (0x200D / 8205)
-
-* **Direction:** Out
-* **Description:** Retrieves extended output mapping configuration (timer ID and usage flags). Obsolete, use `MSP2_INAV_OUTPUT_MAPPING_EXT2`.
-* **Payload:** Repeated for each Motor/Servo timer:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `timerId` | `uint8_t` | 1 | Hardware timer identifier (e.g., `TIM1`, `TIM2`). Value depends on target |
- | `usageFlags` | `uint8_t` | 1 | Timer usage flags (truncated). `TIM_USE_MOTOR` or `TIM_USE_SERVO` |
-* **Notes:** Usage flags are truncated to 8 bits. `timerId` mapping is target-specific.
-
-### `MSP2_INAV_TIMER_OUTPUT_MODE` (0x200E / 8206)
-
-* **Direction:** In/Out
-* **Description:** Get or list the output mode override for hardware timers (e.g., force ONESHOT, DSHOT).
-* **Request Payload (Get All):** None
-* **Request Payload (Get One):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `timerIndex` | `uint8_t` | 1 | Index of the hardware timer definition (0 to `HARDWARE_TIMER_DEFINITION_COUNT - 1`) |
-* **Reply Payload (List All):** Repeated `HARDWARE_TIMER_DEFINITION_COUNT` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `timerIndex` | `uint8_t` | 1 | Timer index |
- | `outputMode` | `uint8_t` | 1 | Output mode override (`TIMER_OUTPUT_MODE_*` enum) |
-* **Reply Payload (Get One):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `timerIndex` | `uint8_t` | 1 | Timer index requested |
- | `outputMode` | `uint8_t` | 1 | Output mode override for the requested timer |
-* **Notes:** Only available on non-SITL builds. `HARDWARE_TIMER_DEFINITION_COUNT` varies by target.
-
-### `MSP2_INAV_SET_TIMER_OUTPUT_MODE` (0x200F / 8207)
-
-* **Direction:** In
-* **Description:** Set the output mode override for a specific hardware timer.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `timerIndex` | `uint8_t` | 1 | Index of the hardware timer definition |
- | `outputMode` | `uint8_t` | 1 | Output mode override (`TIMER_OUTPUT_MODE_*` enum) to set |
-* **Notes:** Only available on non-SITL builds. Expects 2 bytes. Returns error if `timerIndex` is invalid.
-
-### `MSP2_INAV_OUTPUT_MAPPING_EXT2` (0x210D / 8461)
-
-* **Direction:** Out
-* **Description:** Retrieves the full extended output mapping configuration (timer ID, full 32-bit usage flags, and pin label). Supersedes `MSP2_INAV_OUTPUT_MAPPING_EXT`.
-* **Payload:** Repeated for each Motor/Servo timer:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `timerId` | `uint8_t` | 1 | Hardware timer identifier (e.g., `TIM1`, `TIM2`). SITL uses index |
- | `usageFlags` | `uint32_t` | 4 | Full 32-bit timer usage flags (`TIM_USE_*`) |
- | `pinLabel` | `uint8_t` | 1 | Label for special pin usage (`PIN_LABEL_*` enum, e.g., `PIN_LABEL_LED`). 0 (`PIN_LABEL_NONE`) otherwise |
-* **Notes:** Provides complete usage flags and helps identify pins repurposed for functions like LED strip.
-
-### `MSP2_INAV_MIXER` (0x2010 / 8208)
-
-* **Direction:** Out
-* **Description:** Retrieves INAV-specific mixer configuration details.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `motorDirectionInverted` | `uint8_t` | 1 | Boolean: 1 if motor direction is reversed globally (`mixerConfig()->motorDirectionInverted`) |
- | `reserved1` | `uint8_t` | 1 | Always 0 (Was yaw jump prevention limit) |
- | `motorStopOnLow` | `uint8_t` | 1 | Boolean: 1 if motors stop at minimum throttle (`mixerConfig()->motorstopOnLow`) |
- | `platformType` | `uint8_t` | 1 | Enum (`platformType_e`): Vehicle platform type (Multirotor, Airplane, etc.) (`mixerConfig()->platformType`) |
- | `hasFlaps` | `uint8_t` | 1 | Boolean: 1 if the current mixer configuration includes flaps (`mixerConfig()->hasFlaps`) |
- | `appliedMixerPreset` | `uint16_t` | 2 | Enum (`mixerPreset_e`): Mixer preset currently applied (`mixerConfig()->appliedMixerPreset`) |
- | `maxMotors` | `uint8_t` | 1 | Constant: Maximum motors supported (`MAX_SUPPORTED_MOTORS`) |
- | `maxServos` | `uint8_t` | 1 | Constant: Maximum servos supported (`MAX_SUPPORTED_SERVOS`) |
-
-### `MSP2_INAV_SET_MIXER` (0x2011 / 8209)
-
-* **Direction:** In
-* **Description:** Sets INAV-specific mixer configuration details.
-* **Payload:** (Matches `MSP2_INAV_MIXER` structure)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `motorDirectionInverted` | `uint8_t` | 1 | Sets `mixerConfigMutable()->motorDirectionInverted` |
- | `reserved1` | `uint8_t` | 1 | Ignored |
- | `motorStopOnLow` | `uint8_t` | 1 | Sets `mixerConfigMutable()->motorstopOnLow` |
- | `platformType` | `uint8_t` | 1 | Sets `mixerConfigMutable()->platformType` |
- | `hasFlaps` | `uint8_t` | 1 | Sets `mixerConfigMutable()->hasFlaps` |
- | `appliedMixerPreset` | `uint16_t` | 2 | Sets `mixerConfigMutable()->appliedMixerPreset` |
- | `maxMotors` | `uint8_t` | 1 | Ignored |
- | `maxServos` | `uint8_t` | 1 | Ignored |
-* **Notes:** Expects 9 bytes. Calls `mixerUpdateStateFlags()`.
-
-### `MSP2_INAV_OSD_LAYOUTS` (0x2012 / 8210)
-
-* **Direction:** In/Out
-* **Description:** Gets OSD layout information (counts, positions for a specific layout, or position for a specific item).
-* **Request Payload (Get Counts):** None
-* **Request Payload (Get Layout):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `layoutIndex` | `uint8_t` | 1 | Index of the OSD layout (0 to `OSD_LAYOUT_COUNT - 1`) |
-* **Request Payload (Get Item):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `layoutIndex` | `uint8_t` | 1 | Index of the OSD layout |
- | `itemIndex` | `uint16_t` | 2 | Index of the OSD item (`OSD_ITEM_*` enum, 0 to `OSD_ITEM_COUNT - 1`) |
-* **Reply Payload (Get Counts):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `layoutCount` | `uint8_t` | 1 | Number of OSD layouts (`OSD_LAYOUT_COUNT`) |
- | `itemCount` | `uint8_t` | 1 | Number of OSD items per layout (`OSD_ITEM_COUNT`) |
-* **Reply Payload (Get Layout):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `itemPositions` | `uint16_t[OSD_ITEM_COUNT]` | `OSD_ITEM_COUNT * 2` | Packed X/Y positions for all items in the requested layout |
-* **Reply Payload (Get Item):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `itemPosition` | `uint16_t` | 2 | Packed X/Y position for the requested item in the requested layout |
-* **Notes:** Requires `USE_OSD`. Returns error if indexes are invalid.
-
-### `MSP2_INAV_OSD_SET_LAYOUT_ITEM` (0x2013 / 8211)
-
-* **Direction:** In
-* **Description:** Sets the position of a single OSD item within a specific layout.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `layoutIndex` | `uint8_t` | 1 | Index | Index of the OSD layout (0 to `OSD_LAYOUT_COUNT - 1`) |
- | `itemIndex` | `uint8_t` | 1 | Index | Index of the OSD item (`OSD_ITEM_*` enum) |
- | `itemPosition` | `uint16_t` | 2 | Coordinates | Packed X/Y position (`(Y << 8) | X`) to set |
-* **Notes:** Requires `USE_OSD`. Expects 4 bytes. Returns error if indexes are invalid. If the modified layout is not the currently active one, it temporarily overrides the active layout for 10 seconds to show the change. Otherwise, triggers a full OSD redraw.
-
-### `MSP2_INAV_OSD_ALARMS` (0x2014 / 8212)
-
-* **Direction:** Out
-* **Description:** Retrieves OSD alarm threshold settings.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `rssiAlarm` | `uint8_t` | 1 | % | RSSI alarm threshold (`osdConfig()->rssi_alarm`) |
- | `timerAlarm` | `uint16_t` | 2 | seconds | Timer alarm threshold (`osdConfig()->time_alarm`) |
- | `altAlarm` | `uint16_t` | 2 | meters | Altitude alarm threshold (`osdConfig()->alt_alarm`) |
- | `distAlarm` | `uint16_t` | 2 | meters | Distance alarm threshold (`osdConfig()->dist_alarm`) |
- | `negAltAlarm` | `uint16_t` | 2 | meters | Negative altitude alarm threshold (`osdConfig()->neg_alt_alarm`) |
- | `gForceAlarm` | `uint16_t` | 2 | G * 1000 | G-force alarm threshold (`osdConfig()->gforce_alarm * 1000`) |
- | `gForceAxisMinAlarm`| `int16_t` | 2 | G * 1000 | Min G-force per-axis alarm (`osdConfig()->gforce_axis_alarm_min * 1000`) |
- | `gForceAxisMaxAlarm`| `int16_t` | 2 | G * 1000 | Max G-force per-axis alarm (`osdConfig()->gforce_axis_alarm_max * 1000`) |
- | `currentAlarm` | `uint8_t` | 1 | 0.1 A ? | Current draw alarm threshold (`osdConfig()->current_alarm`). Units may need verification |
- | `imuTempMinAlarm` | `uint16_t` | 2 | degrees C | Min IMU temperature alarm (`osdConfig()->imu_temp_alarm_min`) |
- | `imuTempMaxAlarm` | `uint16_t` | 2 | degrees C | Max IMU temperature alarm (`osdConfig()->imu_temp_alarm_max`) |
- | `baroTempMinAlarm` | `uint16_t` | 2 | degrees C | Min Baro temperature alarm (`osdConfig()->baro_temp_alarm_min`). 0 if `USE_BARO` disabled |
- | `baroTempMaxAlarm` | `uint16_t` | 2 | degrees C | Max Baro temperature alarm (`osdConfig()->baro_temp_alarm_max`). 0 if `USE_BARO` disabled |
- | `adsbWarnDistance`| `uint16_t` | 2 | meters | ADSB warning distance (`osdConfig()->adsb_distance_warning`). 0 if `USE_ADSB` disabled |
- | `adsbAlertDistance`| `uint16_t` | 2 | meters | ADSB alert distance (`osdConfig()->adsb_distance_alert`). 0 if `USE_ADSB` disabled |
-* **Notes:** Requires `USE_OSD`.
-
-### `MSP2_INAV_OSD_SET_ALARMS` (0x2015 / 8213)
-
-* **Direction:** In
-* **Description:** Sets OSD alarm threshold settings.
-* **Payload:** (Matches most of `MSP2_INAV_OSD_ALARMS` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `rssiAlarm` | `uint8_t` | 1 | % | Sets `osdConfigMutable()->rssi_alarm` |
- | `timerAlarm` | `uint16_t` | 2 | seconds | Sets `osdConfigMutable()->time_alarm` |
- | `altAlarm` | `uint16_t` | 2 | meters | Sets `osdConfigMutable()->alt_alarm` |
- | `distAlarm` | `uint16_t` | 2 | meters | Sets `osdConfigMutable()->dist_alarm` |
- | `negAltAlarm` | `uint16_t` | 2 | meters | Sets `osdConfigMutable()->neg_alt_alarm` |
- | `gForceAlarm` | `uint16_t` | 2 | G * 1000 | Sets `osdConfigMutable()->gforce_alarm = value / 1000.0f` |
- | `gForceAxisMinAlarm`| `int16_t` | 2 | G * 1000 | Sets `osdConfigMutable()->gforce_axis_alarm_min = value / 1000.0f` |
- | `gForceAxisMaxAlarm`| `int16_t` | 2 | G * 1000 | Sets `osdConfigMutable()->gforce_axis_alarm_max = value / 1000.0f` |
- | `currentAlarm` | `uint8_t` | 1 | 0.1 A ? | Sets `osdConfigMutable()->current_alarm` |
- | `imuTempMinAlarm` | `uint16_t` | 2 | degrees C | Sets `osdConfigMutable()->imu_temp_alarm_min` |
- | `imuTempMaxAlarm` | `uint16_t` | 2 | degrees C | Sets `osdConfigMutable()->imu_temp_alarm_max` |
- | `baroTempMinAlarm` | `uint16_t` | 2 | degrees C | Sets `osdConfigMutable()->baro_temp_alarm_min` (if `USE_BARO`) |
- | `baroTempMaxAlarm` | `uint16_t` | 2 | degrees C | Sets `osdConfigMutable()->baro_temp_alarm_max` (if `USE_BARO`) |
-* **Notes:** Requires `USE_OSD`. Expects 24 bytes. ADSB alarms are not settable via this message.
-
-### `MSP2_INAV_OSD_PREFERENCES` (0x2016 / 8214)
-
-* **Direction:** Out
-* **Description:** Retrieves OSD display preferences (video system, units, styles, etc.).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `videoSystem` | `uint8_t` | 1 | Enum: Video system (Auto/PAL/NTSC) (`osdConfig()->video_system`) |
- | `mainVoltageDecimals` | `uint8_t` | 1 | Count: Decimal places for main voltage display (`osdConfig()->main_voltage_decimals`) |
- | `ahiReverseRoll` | `uint8_t` | 1 | Boolean: Reverse roll direction on Artificial Horizon (`osdConfig()->ahi_reverse_roll`) |
- | `crosshairsStyle` | `uint8_t` | 1 | Enum: Style of the center crosshairs (`osdConfig()->crosshairs_style`) |
- | `leftSidebarScroll` | `uint8_t` | 1 | Boolean: Enable scrolling for left sidebar (`osdConfig()->left_sidebar_scroll`) |
- | `rightSidebarScroll` | `uint8_t` | 1 | Boolean: Enable scrolling for right sidebar (`osdConfig()->right_sidebar_scroll`) |
- | `sidebarScrollArrows` | `uint8_t` | 1 | Boolean: Show arrows for scrollable sidebars (`osdConfig()->sidebar_scroll_arrows`) |
- | `units` | `uint8_t` | 1 | Enum: `osd_unit_e` Measurement units (Metric/Imperial) (`osdConfig()->units`) |
- | `statsEnergyUnit` | `uint8_t` | 1 | Enum: Unit for energy display in post-flight stats (`osdConfig()->stats_energy_unit`) |
-* **Notes:** Requires `USE_OSD`.
-
-### `MSP2_INAV_OSD_SET_PREFERENCES` (0x2017 / 8215)
-
-* **Direction:** In
-* **Description:** Sets OSD display preferences.
-* **Payload:** (Matches `MSP2_INAV_OSD_PREFERENCES` structure)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `videoSystem` | `uint8_t` | 1 | Sets `osdConfigMutable()->video_system` |
- | `mainVoltageDecimals` | `uint8_t` | 1 | Sets `osdConfigMutable()->main_voltage_decimals` |
- | `ahiReverseRoll` | `uint8_t` | 1 | Sets `osdConfigMutable()->ahi_reverse_roll` |
- | `crosshairsStyle` | `uint8_t` | 1 | Sets `osdConfigMutable()->crosshairs_style` |
- | `leftSidebarScroll` | `uint8_t` | 1 | Sets `osdConfigMutable()->left_sidebar_scroll` |
- | `rightSidebarScroll` | `uint8_t` | 1 | Sets `osdConfigMutable()->right_sidebar_scroll` |
- | `sidebarScrollArrows` | `uint8_t` | 1 | Sets `osdConfigMutable()->sidebar_scroll_arrows` |
- | `units` | `uint8_t` | 1 | Enum `osd_unit_e` Sets `osdConfigMutable()->units` |
- | `statsEnergyUnit` | `uint8_t` | 1 | Sets `osdConfigMutable()->stats_energy_unit` |
-* **Notes:** Requires `USE_OSD`. Expects 9 bytes. Triggers a full OSD redraw.
-
-### `MSP2_INAV_SELECT_BATTERY_PROFILE` (0x2018 / 8216)
-
-* **Direction:** In
-* **Description:** Selects the active battery profile and saves configuration.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `batteryProfileIndex` | `uint8_t` | 1 | Index of the battery profile to activate (0-based) |
-* **Notes:** Expects 1 byte. Will fail if armed. Calls `setConfigBatteryProfileAndWriteEEPROM()`.
-
-### `MSP2_INAV_DEBUG` (0x2019 / 8217)
-
-* **Direction:** Out
-* **Description:** Retrieves values from the firmware's 32-bit `debug[]` array. Supersedes `MSP_DEBUG`.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `debugValues` | `uint32_t[DEBUG32_VALUE_COUNT]` | `DEBUG32_VALUE_COUNT * 4` | Values from the `debug` array (typically 8 values) |
-* **Notes:** `DEBUG32_VALUE_COUNT` is usually 8.
-
-### `MSP2_BLACKBOX_CONFIG` (0x201A / 8218)
-
-* **Direction:** Out
-* **Description:** Retrieves the Blackbox configuration. Supersedes `MSP_BLACKBOX_CONFIG`.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `blackboxSupported` | `uint8_t` | 1 | Boolean: 1 if Blackbox is supported (`USE_BLACKBOX`), 0 otherwise |
- | `blackboxDevice` | `uint8_t` | 1 | Enum (`blackboxDevice_e`): Target device for logging (`blackboxConfig()->device`). 0 if not supported |
- | `blackboxRateNum` | `uint16_t` | 2 | Numerator for logging rate divider (`blackboxConfig()->rate_num`). 0 if not supported |
- | `blackboxRateDenom` | `uint16_t` | 2 | Denominator for logging rate divider (`blackboxConfig()->rate_denom`). 0 if not supported |
- | `blackboxIncludeFlags`| `uint32_t`| 4 | Bitmask: Flags for fields included/excluded from logging (`blackboxConfig()->includeFlags`) |
-* **Notes:** Requires `USE_BLACKBOX`.
-
-### `MSP2_SET_BLACKBOX_CONFIG` (0x201B / 8219)
-
-* **Direction:** In
-* **Description:** Sets the Blackbox configuration. Supersedes `MSP_SET_BLACKBOX_CONFIG`.
-* **Payload:** (Matches `MSP2_BLACKBOX_CONFIG` structure, excluding `blackboxSupported`)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `blackboxDevice` | `uint8_t` | 1 | Sets `blackboxConfigMutable()->device` |
- | `blackboxRateNum` | `uint16_t` | 2 | Sets `blackboxConfigMutable()->rate_num` |
- | `blackboxRateDenom` | `uint16_t` | 2 | Sets `blackboxConfigMutable()->rate_denom` |
- | `blackboxIncludeFlags`| `uint32_t`| 4 | Sets `blackboxConfigMutable()->includeFlags` |
-* **Notes:** Requires `USE_BLACKBOX`. Expects 9 bytes. Returns error if Blackbox is currently logging (`!blackboxMayEditConfig()`).
-
-### `MSP2_INAV_TEMP_SENSOR_CONFIG` (0x201C / 8220)
-
-* **Direction:** Out
-* **Description:** Retrieves the configuration for all onboard temperature sensors.
-* **Payload:** Repeated `MAX_TEMP_SENSORS` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `type` | `uint8_t` | 1 | Enum (`tempSensorType_e`): Type of the temperature sensor |
- | `address` | `uint64_t` | 8 | Sensor address/ID (e.g., for 1-Wire sensors) |
- | `alarmMin` | `uint16_t` | 2 | Min temperature alarm threshold (degrees C) |
- | `alarmMax` | `uint16_t` | 2 | Max temperature alarm threshold (degrees C) |
- | `osdSymbol` | `uint8_t` | 1 | Index: OSD symbol to use for this sensor (0 to `TEMP_SENSOR_SYM_COUNT`) |
- | `label` | `char[TEMPERATURE_LABEL_LEN]` | `TEMPERATURE_LABEL_LEN` | User-defined label for the sensor |
-* **Notes:** Requires `USE_TEMPERATURE_SENSOR`.
-
-### `MSP2_INAV_SET_TEMP_SENSOR_CONFIG` (0x201D / 8221)
-
-* **Direction:** In
-* **Description:** Sets the configuration for all onboard temperature sensors.
-* **Payload:** Repeated `MAX_TEMP_SENSORS` times (matches `MSP2_INAV_TEMP_SENSOR_CONFIG` structure):
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `type` | `uint8_t` | 1 | Sets sensor type |
- | `address` | `uint64_t` | 8 | Sets sensor address/ID |
- | `alarmMin` | `uint16_t` | 2 | Sets min alarm threshold |
- | `alarmMax` | `uint16_t` | 2 | Sets max alarm threshold |
- | `osdSymbol` | `uint8_t` | 1 | Sets OSD symbol index (validated) |
- | `label` | `char[TEMPERATURE_LABEL_LEN]` | `TEMPERATURE_LABEL_LEN` | Sets sensor label (converted to uppercase) |
-* **Notes:** Requires `USE_TEMPERATURE_SENSOR`. Expects `MAX_TEMP_SENSORS * sizeof(tempSensorConfig_t)` bytes.
-
-### `MSP2_INAV_TEMPERATURES` (0x201E / 8222)
-
-* **Direction:** Out
-* **Description:** Retrieves the current readings from all configured temperature sensors.
-* **Payload:** Repeated `MAX_TEMP_SENSORS` times:
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `temperature` | `int16_t` | 2 | degrees C | Current temperature reading. -1000 if sensor is invalid or reading failed |
-* **Notes:** Requires `USE_TEMPERATURE_SENSOR`.
-
-### `MSP_SIMULATOR` (0x201F / 8223)
-
-* **Direction:** In/Out
-* **Description:** Handles Hardware-in-the-Loop (HITL) simulation data exchange. Receives simulated sensor data and options, sends back control outputs and debug info.
-* **Request Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `simulatorVersion` | `uint8_t` | 1 | Version of the simulator protocol (`SIMULATOR_MSP_VERSION`) |
- | `hitlFlags` | `uint8_t` | 1 | Bitmask: Options for HITL (`HITL_*` flags) |
- | `gpsFixType` | `uint8_t` | 1 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated GPS fix type |
- | `gpsNumSat` | `uint8_t` | 1 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated satellite count |
- | `gpsLat` | `int32_t` | 4 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated latitude (1e7 deg) |
- | `gpsLon` | `int32_t` | 4 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated longitude (1e7 deg) |
- | `gpsAlt` | `int32_t` | 4 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated altitude (cm) |
- | `gpsSpeed` | `uint16_t` | 2 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated ground speed (cm/s) |
- | `gpsCourse` | `uint16_t` | 2 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated ground course (deci-deg) |
- | `gpsVelN` | `int16_t` | 2 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated North velocity (cm/s) |
- | `gpsVelE` | `int16_t` | 2 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated East velocity (cm/s) |
- | `gpsVelD` | `int16_t` | 2 | (If `HITL_HAS_NEW_GPS_DATA`) Simulated Down velocity (cm/s) |
- | `imuRoll` | `int16_t` | 2 | (If NOT `HITL_USE_IMU`) Simulated Roll (deci-deg) |
- | `imuPitch` | `int16_t` | 2 | (If NOT `HITL_USE_IMU`) Simulated Pitch (deci-deg) |
- | `imuYaw` | `int16_t` | 2 | (If NOT `HITL_USE_IMU`) Simulated Yaw (deci-deg) |
- | `accX` | `int16_t` | 2 | mG (G * 1000) | Simulated Accelerometer X |
- | `accY` | `int16_t` | 2 | mG (G * 1000) | Simulated Accelerometer Y |
- | `accZ` | `int16_t` | 2 | mG (G * 1000) | Simulated Accelerometer Z |
- | `gyroX` | `int16_t` | 2 | dps * 16 | Simulated Gyroscope X rate |
- | `gyroY` | `int16_t` | 2 | dps * 16 | Simulated Gyroscope Y rate |
- | `gyroZ` | `int16_t` | 2 | dps * 16 | Simulated Gyroscope Z rate |
- | `baroPressure` | `uint32_t` | 4 | Pa | Simulated Barometer pressure |
- | `magX` | `int16_t` | 2 | Scaled | Simulated Magnetometer X (scaled by 20) |
- | `magY` | `int16_t` | 2 | Scaled | Simulated Magnetometer Y (scaled by 20) |
- | `magZ` | `int16_t` | 2 | Scaled | Simulated Magnetometer Z (scaled by 20) |
- | `vbat` | `uint8_t` | 1 | (If `HITL_EXT_BATTERY_VOLTAGE`) Simulated battery voltage (0.1V units) |
- | `airspeed` | `uint16_t` | 2 | (If `HITL_AIRSPEED`) Simulated airspeed (cm/s) |
- | `extFlags` | `uint8_t` | 1 | (If `HITL_EXTENDED_FLAGS`) Additional flags (upper 8 bits) |
-* **Reply Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `stabilizedRoll` | `uint16_t` | 2 | Stabilized Roll command output (-500 to 500) |
- | `stabilizedPitch`| `uint16_t` | 2 | Stabilized Pitch command output (-500 to 500) |
- | `stabilizedYaw` | `uint16_t` | 2 | Stabilized Yaw command output (-500 to 500) |
- | `stabilizedThrottle`| `uint16_t`| 2 | Stabilized Throttle command output (-500 to 500 if armed, else -500) |
- | `debugFlags` | `uint8_t` | 1 | Packed flags: Debug index (0-7), Platform type, Armed state, OSD feature status |
- | `debugValue` | `uint32_t` | 4 | Current debug value (`debug[simulatorData.debugIndex]`) |
- | `attitudeRoll` | `int16_t` | 2 | Current estimated Roll (deci-deg) |
- | `attitudePitch`| `int16_t` | 2 | Current estimated Pitch (deci-deg) |
- | `attitudeYaw` | `int16_t` | 2 | Current estimated Yaw (deci-deg) |
- | `osdHeader` | `uint8_t` | 1 | OSD RLE Header (255) |
- | `osdRows` | `uint8_t` | 1 | (If OSD supported) Number of OSD rows |
- | `osdCols` | `uint8_t` | 1 | (If OSD supported) Number of OSD columns |
- | `osdStartY` | `uint8_t` | 1 | (If OSD supported) Starting row for RLE data |
- | `osdStartX` | `uint8_t` | 1 | (If OSD supported) Starting column for RLE data |
- | `osdRleData` | `uint8_t[]` | Variable | (If OSD supported) Run-length encoded OSD character data. Terminated by `[0, 0]` |
-* **Notes:** Requires `USE_SIMULATOR`. Complex message handling state changes for enabling/disabling HITL. Sensor data is injected directly. OSD data is sent using a custom RLE scheme. See `simulatorData` struct and associated code for details.
-
-### `MSP2_INAV_SERVO_MIXER` (0x2020 / 8224)
-
-* **Direction:** Out
-* **Description:** Retrieves the custom servo mixer rules, including programming framework condition IDs, for primary and secondary mixer profiles. Supersedes `MSP_SERVO_MIX_RULES`.
-* **Payload:** Repeated `MAX_SERVO_RULES` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `targetChannel` | `uint8_t` | 1 | Servo output channel index (0-based) |
- | `inputSource` | `uint8_t` | 1 | Enum `inputSource_e` Input source |
- | `rate` | `uint16_t` | 2 | Mixing rate/weight |
- | `speed` | `uint8_t` | 1 | Speed/Slew rate limit (0-100) |
- | `conditionId` | `uint8_t` | 1 | Logic Condition ID (0 to `MAX_LOGIC_CONDITIONS - 1`, or 255/-1 if none/disabled) |
- | `targetChannel` | `uint8_t` | 1 | (Optional) Profile 2 Target channel |
- | `inputSource` | `uint8_t` | 1 | (Optional) Profile 2 Enum `inputSource_e` Input source |
- | `rate` | `uint16_t` | 2 | (Optional) Profile 2 Rate |
- | `speed` | `uint8_t` | 1 | (Optional) Profile 2 Speed |
- | `conditionId` | `uint8_t` | 1 | (Optional) Profile 2 Logic Condition ID |
-* **Notes:** `conditionId` requires `USE_PROGRAMMING_FRAMEWORK`.
-
-### `MSP2_INAV_SET_SERVO_MIXER` (0x2021 / 8225)
-
-* **Direction:** In
-* **Description:** Sets a single custom servo mixer rule, including programming framework condition ID. Supersedes `MSP_SET_SERVO_MIX_RULE`.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `ruleIndex` | `uint8_t` | 1 | Index of the rule to set (0 to `MAX_SERVO_RULES - 1`) |
- | `targetChannel` | `uint8_t` | 1 | Servo output channel index |
- | `inputSource` | `uint8_t` | 1 | Enum `inputSource_e` Input source |
- | `rate` | `uint16_t` | 2 | Mixing rate/weight |
- | `speed` | `uint8_t` | 1 | Speed/Slew rate limit (0-100) |
- | `conditionId` | `uint8_t` | 1 | Logic Condition ID (255/-1 if none). Ignored if `USE_PROGRAMMING_FRAMEWORK` is disabled |
-* **Notes:** Expects 7 bytes. Returns error if index invalid. Calls `loadCustomServoMixer()`.
-
-### `MSP2_INAV_LOGIC_CONDITIONS` (0x2022 / 8226)
-
-* **Direction:** Out
-* **Description:** Retrieves the configuration of all defined Logic Conditions.
-* **Payload:** Repeated `MAX_LOGIC_CONDITIONS` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `enabled` | `uint8_t` | 1 | Boolean: 1 if the condition is enabled |
- | `activatorId` | `uint8_t` | 1 | ID of the activator condition (if any, 255 if none) |
- | `operation` | `uint8_t` | 1 | Enum `logicConditionOp_e` Logical operation (AND, OR, XOR, etc.) |
- | `operandAType` | `uint8_t` | 1 | Enum `logicOperandType_e` Type of the first operand (Flight Mode, GVAR, etc.) |
- | `operandAValue` | `uint32_t` | 4 | Value/ID of the first operand |
- | `operandBType` | `uint8_t` | 1 | Enum `logicOperandType_e`: Type of the second operand |
- | `operandBValue` | `uint32_t` | 4 | Value/ID of the second operand |
- | `flags` | `uint8_t` | 1 | Bitmask: Condition flags (e.g., `LC_FLAG_FIRST_TIME_TRUE`) |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. See `logicCondition_t` structure.
-
-### `MSP2_INAV_SET_LOGIC_CONDITIONS` (0x2023 / 8227)
-
-* **Direction:** In
-* **Description:** Sets the configuration for a single Logic Condition by its index.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `conditionIndex` | `uint8_t` | 1 | Index of the condition to set (0 to `MAX_LOGIC_CONDITIONS - 1`) |
- | `enabled` | `uint8_t` | 1 | Boolean: 1 to enable the condition |
- | `activatorId` | `uint8_t` | 1 | Activator condition ID |
- | `operation` | `uint8_t` | 1 | Enum `logicConditionOp_e` Logical operation |
- | `operandAType` | `uint8_t` | 1 | Enum `logicOperandType_e` Type of operand A |
- | `operandAValue` | `uint32_t` | 4 | Value/ID of operand A |
- | `operandBType` | `uint8_t` | 1 | Enum `logicOperandType_e` Type of operand B |
- | `operandBValue` | `uint32_t` | 4 | Value/ID of operand B |
- | `flags` | `uint8_t` | 1 | Bitmask: Condition flags |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 15 bytes. Returns error if index is invalid.
-
-### `MSP2_INAV_GLOBAL_FUNCTIONS` (0x2024 / 8228)
-
-* **Not implemented**
-
-### `MSP2_INAV_SET_GLOBAL_FUNCTIONS` (0x2025 / 8229)
-
-* **Not implemented**
-
-### `MSP2_INAV_LOGIC_CONDITIONS_STATUS` (0x2026 / 8230)
-
-* **Direction:** Out
-* **Description:** Retrieves the current evaluated status (true/false or numerical value) of all logic conditions.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `conditionValues` | `uint32_t[MAX_LOGIC_CONDITIONS]` | `MAX_LOGIC_CONDITIONS * 4` | Array of current values for each logic condition (`logicConditionGetValue(i)`). 1 for true, 0 for false, or numerical value depending on operation |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`.
-
-### `MSP2_INAV_GVAR_STATUS` (0x2027 / 8231)
-
-* **Direction:** Out
-* **Description:** Retrieves the current values of all Global Variables (GVARS).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `gvarValues` | `uint32_t[MAX_GLOBAL_VARIABLES]` | `MAX_GLOBAL_VARIABLES * 4` | Array of current values for each global variable (`gvGet(i)`) |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`.
-
-### `MSP2_INAV_PROGRAMMING_PID` (0x2028 / 8232)
-
-* **Direction:** Out
-* **Description:** Retrieves the configuration of all Programming PIDs.
-* **Payload:** Repeated `MAX_PROGRAMMING_PID_COUNT` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `enabled` | `uint8_t` | 1 | Boolean: 1 if the PID is enabled |
- | `setpointType` | `uint8_t` | 1 | Enum (`logicOperandType_e`) Type of the setpoint source |
- | `setpointValue` | `uint32_t` | 4 | Value/ID of the setpoint source |
- | `measurementType` | `uint8_t` | 1 | Enum (`logicOperandType_e`) Type of the measurement source |
- | `measurementValue` | `uint32_t` | 4 | Value/ID of the measurement source |
- | `gainP` | `uint16_t` | 2 | Proportional gain |
- | `gainI` | `uint16_t` | 2 | Integral gain |
- | `gainD` | `uint16_t` | 2 | Derivative gain |
- | `gainFF` | `uint16_t` | 2 | Feed-forward gain |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. See `programmingPid_t` structure.
-
-### `MSP2_INAV_SET_PROGRAMMING_PID` (0x2029 / 8233)
-
-* **Direction:** In
-* **Description:** Sets the configuration for a single Programming PID by its index.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `pidIndex` | `uint8_t` | 1 | Index of the Programming PID to set (0 to `MAX_PROGRAMMING_PID_COUNT - 1`) |
- | `enabled` | `uint8_t` | 1 | Boolean: 1 to enable the PID |
- | `setpointType` | `uint8_t` | 1 | Enum (`logicOperandType_e`) Type of the setpoint source |
- | `setpointValue` | `uint32_t` | 4 | Value/ID of the setpoint source |
- | `measurementType` | `uint8_t` | 1 | Enum (`logicOperandType_e`) Type of the measurement source |
- | `measurementValue` | `uint32_t` | 4 | Value/ID of the measurement source |
- | `gainP` | `uint16_t` | 2 | Proportional gain |
- | `gainI` | `uint16_t` | 2 | Integral gain |
- | `gainD` | `uint16_t` | 2 | Derivative gain |
- | `gainFF` | `uint16_t` | 2 | Feed-forward gain |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 20 bytes. Returns error if index is invalid.
-
-### `MSP2_INAV_PROGRAMMING_PID_STATUS` (0x202A / 8234)
-
-* **Direction:** Out
-* **Description:** Retrieves the current output value of all Programming PIDs.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `pidOutputs` | `uint32_t[MAX_PROGRAMMING_PID_COUNT]` | `MAX_PROGRAMMING_PID_COUNT * 4` | Array of current output values for each Programming PID (`programmingPidGetOutput(i)`) |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`.
-
-### `MSP2_PID` (0x2030 / 8240)
-
-* **Direction:** Out
-* **Description:** Retrieves the standard PID controller gains (P, I, D, FF) for the current PID profile.
-* **Payload:** Repeated `PID_ITEM_COUNT` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `P` | `uint8_t` | 1 | Proportional gain (`pidBank()->pid[i].P`), constrained 0-255 |
- | `I` | `uint8_t` | 1 | Integral gain (`pidBank()->pid[i].I`), constrained 0-255 |
- | `D` | `uint8_t` | 1 | Derivative gain (`pidBank()->pid[i].D`), constrained 0-255 |
- | `FF` | `uint8_t` | 1 | Feed-forward gain (`pidBank()->pid[i].FF`), constrained 0-255 |
-* **Notes:** `PID_ITEM_COUNT` defines the number of standard PID controllers (Roll, Pitch, Yaw, Alt, Vel, etc.). Updates from EZ-Tune if enabled.
-
-### `MSP2_SET_PID` (0x2031 / 8241)
-
-* **Direction:** In
-* **Description:** Sets the standard PID controller gains (P, I, D, FF) for the current PID profile.
-* **Payload:** Repeated `PID_ITEM_COUNT` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `P` | `uint8_t` | 1 | Sets Proportional gain (`pidBankMutable()->pid[i].P`) |
- | `I` | `uint8_t` | 1 | Sets Integral gain (`pidBankMutable()->pid[i].I`) |
- | `D` | `uint8_t` | 1 | Sets Derivative gain (`pidBankMutable()->pid[i].D`) |
- | `FF` | `uint8_t` | 1 | Sets Feed-forward gain (`pidBankMutable()->pid[i].FF`) |
-* **Notes:** Expects `PID_ITEM_COUNT * 4` bytes. Calls `schedulePidGainsUpdate()` and `navigationUsePIDs()`.
-
-### `MSP2_INAV_OPFLOW_CALIBRATION` (0x2032 / 8242)
-
-* **Direction:** In
-* **Description:** Starts the optical flow sensor calibration procedure.
-* **Payload:** None
-* **Notes:** Requires `USE_OPFLOW`. Will fail if armed. Calls `opflowStartCalibration()`.
-
-### `MSP2_INAV_FWUPDT_PREPARE` (0x2033 / 8243)
-
-* **Direction:** In
-* **Description:** Prepares the flight controller to receive a firmware update via MSP.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `firmwareSize` | `uint32_t` | 4 | Total size of the incoming firmware file in bytes |
-* **Notes:** Requires `MSP_FIRMWARE_UPDATE`. Expects 4 bytes. Returns error if preparation fails (e.g., no storage, invalid size). Calls `firmwareUpdatePrepare()`.
-
-### `MSP2_INAV_FWUPDT_STORE` (0x2034 / 8244)
-
-* **Direction:** In
-* **Description:** Stores a chunk of firmware data received via MSP.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `firmwareChunk` | `uint8_t[]` | Variable | Chunk of firmware data |
-* **Notes:** Requires `MSP_FIRMWARE_UPDATE`. Returns error if storage fails (e.g., out of space, checksum error). Called repeatedly until the entire firmware is transferred. Calls `firmwareUpdateStore()`.
-
-### `MSP2_INAV_FWUPDT_EXEC` (0x2035 / 8245)
-
-* **Direction:** In
-* **Description:** Executes the firmware update process (flashes the stored firmware and reboots).
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `updateType` | `uint8_t` | 1 | Type of update (e.g., full flash, specific section - currently ignored/unused) |
-* **Notes:** Requires `MSP_FIRMWARE_UPDATE`. Expects 1 byte. Returns error if update cannot start (e.g., not fully received). Calls `firmwareUpdateExec()`. If successful, the device will reboot into the new firmware.
-
-### `MSP2_INAV_FWUPDT_ROLLBACK_PREPARE` (0x2036 / 8246)
-
-* **Direction:** In
-* **Description:** Prepares the flight controller to perform a firmware rollback to the previously stored version.
-* **Payload:** None
-* **Notes:** Requires `MSP_FIRMWARE_UPDATE`. Returns error if rollback preparation fails (e.g., no rollback image available). Calls `firmwareUpdateRollbackPrepare()`.
-
-### `MSP2_INAV_FWUPDT_ROLLBACK_EXEC` (0x2037 / 8247)
-
-* **Direction:** In
-* **Description:** Executes the firmware rollback process (flashes the stored backup firmware and reboots).
-* **Payload:** None
-* **Notes:** Requires `MSP_FIRMWARE_UPDATE`. Returns error if rollback cannot start. Calls `firmwareUpdateRollbackExec()`. If successful, the device will reboot into the backup firmware.
-
-### `MSP2_INAV_SAFEHOME` (0x2038 / 8248)
-
-* **Direction:** In/Out
-* **Description:** Get or Set configuration for a specific Safe Home location.
-* **Request Payload (Get):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `safehomeIndex` | `uint8_t` | 1 | Index of the safe home location (0 to `MAX_SAFE_HOMES - 1`) |
-* **Reply Payload (Get):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `safehomeIndex` | `uint8_t` | 1 | Index requested |
- | `enabled` | `uint8_t` | 1 | Boolean: 1 if this safe home is enabled |
- | `latitude` | `int32_t` | 4 | Latitude (1e7 deg) |
- | `longitude` | `int32_t` | 4 | Longitude (1e7 deg) |
-* **Notes:** Requires `USE_SAFE_HOME`. Used by `mspFcSafeHomeOutCommand`. See `MSP2_INAV_SET_SAFEHOME` for setting.
-
-### `MSP2_INAV_SET_SAFEHOME` (0x2039 / 8249)
-
-* **Direction:** In
-* **Description:** Sets the configuration for a specific Safe Home location.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `safehomeIndex` | `uint8_t` | 1 | Index of the safe home location (0 to `MAX_SAFE_HOMES - 1`) |
- | `enabled` | `uint8_t` | 1 | Boolean: 1 to enable this safe home |
- | `latitude` | `int32_t` | 4 | Latitude (1e7 deg) |
- | `longitude` | `int32_t` | 4 | Longitude (1e7 deg) |
-* **Notes:** Requires `USE_SAFE_HOME`. Expects 10 bytes. Returns error if index invalid. Resets corresponding FW autoland approach if `USE_FW_AUTOLAND` is enabled.
-
-### `MSP2_INAV_MISC2` (0x203A / 8250)
-
-* **Direction:** Out
-* **Description:** Retrieves miscellaneous runtime information including timers and throttle status.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `uptimeSeconds` | `uint32_t` | 4 | Seconds | Time since boot (`micros() / 1000000`) |
- | `flightTimeSeconds` | `uint32_t` | 4 | Seconds | Accumulated flight time (`getFlightTime()`) |
- | `throttlePercent` | `uint8_t` | 1 | % | Current throttle output percentage (`getThrottlePercent(true)`) |
- | `autoThrottleFlag` | `uint8_t` | 1 | Boolean | 1 if navigation is controlling throttle, 0 otherwise (`navigationIsControllingThrottle()`) |
-
-### `MSP2_INAV_LOGIC_CONDITIONS_SINGLE` (0x203B / 8251)
-
-* **Direction:** In/Out
-* **Description:** Gets the configuration for a single Logic Condition by its index.
-* **Request Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `conditionIndex` | `uint8_t` | 1 | Index of the condition to retrieve (0 to `MAX_LOGIC_CONDITIONS - 1`) |
-* **Reply Payload:** (Matches structure of one entry in `MSP2_INAV_LOGIC_CONDITIONS`)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `enabled` | `uint8_t` | 1 | Boolean: 1 if enabled |
- | `activatorId` | `uint8_t` | 1 | Activator ID |
- | `operation` | `uint8_t` | 1 | Enum `logicConditionOp_e` Logical operation |
- | `operandAType` | `uint8_t` | 1 | Enum `logicOperandType_e` Type of operand A |
- | `operandAValue` | `uint32_t` | 4 | Value/ID of operand A |
- | `operandBType` | `uint8_t` | 1 | Enum `logicOperandType_e` Type of operand B |
- | `operandBValue` | `uint32_t` | 4 | Value/ID of operand B |
- | `flags` | `uint8_t` | 1 | Bitmask: Condition flags |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. Used by `mspFcLogicConditionCommand`.
-
-### `MSP2_INAV_ESC_RPM` (0x2040 / 8256)
-
-* **Direction:** Out
-* **Description:** Retrieves the RPM reported by each ESC via telemetry.
-* **Payload:** Repeated `getMotorCount()` times:
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `escRpm` | `uint32_t` | 4 | RPM | RPM reported by the ESC |
-* **Notes:** Requires `USE_ESC_SENSOR`. Payload size depends on the number of detected motors with telemetry.
-
-### `MSP2_INAV_ESC_TELEM` (0x2041 / 8257)
-
-* **Direction:** Out
-* **Description:** Retrieves the full telemetry data structure reported by each ESC.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `motorCount` | `uint8_t` | 1 | Number of motors reporting telemetry (`getMotorCount()`) |
- | `escData` | `escSensorData_t[]` | `motorCount * sizeof(escSensorData_t)` | Array of `escSensorData_t` structures containing voltage, current, temp, RPM, errors etc. for each ESC |
-* **Notes:** Requires `USE_ESC_SENSOR`. See `escSensorData_t` in `sensors/esc_sensor.h` for the exact structure fields.
-
-### `MSP2_INAV_LED_STRIP_CONFIG_EX` (0x2048 / 8264)
-
-* **Direction:** Out
-* **Description:** Retrieves the full configuration for each LED on the strip using the `ledConfig_t` structure. Supersedes `MSP_LED_STRIP_CONFIG`.
-* **Payload:** Repeated `LED_MAX_STRIP_LENGTH` times:
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `ledConfig` | `uint16_t` | 6 | Full configuration structure for the LED, size sizeof(ledConfig_t) |
-* **Notes:** Requires `USE_LED_STRIP`. See `ledConfig_t` in `io/ledstrip.h` for structure fields (position, function, overlay, color, direction, params).
-
-### `MSP2_INAV_SET_LED_STRIP_CONFIG_EX` (0x2049 / 8265)
-
-* **Direction:** In
-* **Description:** Sets the configuration for a single LED on the strip using the `ledConfig_t` structure. Supersedes `MSP_SET_LED_STRIP_CONFIG`.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `ledIndex` | `uint8_t` | 1 | Index of the LED to configure (0 to `LED_MAX_STRIP_LENGTH - 1`) |
- | `ledConfig` |`uint16_t` | 6 Full configuration structure for the LED , size sizeof(ledConfig_t) |
-* **Notes:** Requires `USE_LED_STRIP`. Expects `1 + sizeof(ledConfig_t)` bytes. Returns error if index invalid. Calls `reevaluateLedConfig()`.
-
-### `MSP2_INAV_FW_APPROACH` (0x204A / 8266)
-
-* **Direction:** In/Out
-* **Description:** Get or Set configuration for a specific Fixed Wing Autoland approach.
-* **Request Payload (Get):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `approachIndex` | `uint8_t` | 1 | Index of the approach setting (0 to `MAX_FW_LAND_APPOACH_SETTINGS - 1`) |
-* **Reply Payload (Get):**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `approachIndex` | `uint8_t` | 1 | Index | Index requested |
- | `approachAlt` | `uint32_t` | 4 | cm | Altitude for the approach phase |
- | `landAlt` | `uint32_t` | 4 | cm | Altitude for the final landing phase |
- | `approachDirection` | `uint8_t` | 1 | Enum | Enum `fwAutolandApproachDirection_e`: Direction of approach (From WP, Specific Heading) |
- | `landHeading1` | `int16_t` | 2 | degrees | Primary landing heading (if approachDirection requires it) |
- | `landHeading2` | `int16_t` | 2 | degrees | Secondary landing heading (if approachDirection requires it) |
- | `isSeaLevelRef` | `uint8_t` | 1 | Boolean | 1 if altitudes are relative to sea level, 0 if relative to home |
-* **Notes:** Requires `USE_FW_AUTOLAND`. Used by `mspFwApproachOutCommand`. See `MSP2_INAV_SET_FW_APPROACH` for setting.
-
-### `MSP2_INAV_SET_FW_APPROACH` (0x204B / 8267)
-
-* **Direction:** In
-* **Description:** Sets the configuration for a specific Fixed Wing Autoland approach.
-* **Payload:** (Matches `MSP2_INAV_FW_APPROACH` reply structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `approachIndex` | `uint8_t` | 1 | Index | Index of the approach setting (0 to `MAX_FW_LAND_APPOACH_SETTINGS - 1`) |
- | `approachAlt` | `uint32_t` | 4 | cm | Sets approach altitude |
- | `landAlt` | `uint32_t` | 4 | cm | Sets landing altitude |
- | `approachDirection` | `uint8_t` | 1 | Enum | Enum `fwAutolandApproachDirection_e` Sets approach direction |
- | `landHeading1` | `int16_t` | 2 | degrees | Sets primary landing heading |
- | `landHeading2` | `int16_t` | 2 | degrees | Sets secondary landing heading |
- | `isSeaLevelRef` | `uint8_t` | 1 | Boolean | Sets altitude reference |
-* **Notes:** Requires `USE_FW_AUTOLAND`. Expects 15 bytes. Returns error if index invalid.
-
-### `MSP2_INAV_GPS_UBLOX_COMMAND` (0x2050 / 8272)
-
-* **Direction:** In
-* **Description:** Sends a raw command directly to a U-Blox GPS module connected to the FC.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `ubxCommand` | `uint8_t[]` | Variable (>= 8) | Raw U-Blox UBX protocol command frame (including header, class, ID, length, payload, checksum) |
-* **Notes:** Requires GPS feature enabled (`FEATURE_GPS`) and the GPS driver to be U-Blox (`isGpsUblox()`). Payload must be at least 8 bytes (minimum UBX frame size). Use with extreme caution, incorrect commands can misconfigure the GPS module. Calls `gpsUbloxSendCommand()`.
-
-### `MSP2_INAV_RATE_DYNAMICS` (0x2060 / 8288)
-
-* **Direction:** Out
-* **Description:** Retrieves Rate Dynamics configuration parameters for the current control rate profile.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `sensitivityCenter` | `uint8_t` | 1 | % | Sensitivity at stick center (`currentControlRateProfile->rateDynamics.sensitivityCenter`) |
- | `sensitivityEnd` | `uint8_t` | 1 | % | Sensitivity at stick ends (`currentControlRateProfile->rateDynamics.sensitivityEnd`) |
- | `correctionCenter` | `uint8_t` | 1 | % | Correction strength at stick center (`currentControlRateProfile->rateDynamics.correctionCenter`) |
- | `correctionEnd` | `uint8_t` | 1 | % | Correction strength at stick ends (`currentControlRateProfile->rateDynamics.correctionEnd`) |
- | `weightCenter` | `uint8_t` | 1 | % | Transition weight at stick center (`currentControlRateProfile->rateDynamics.weightCenter`) |
- | `weightEnd` | `uint8_t` | 1 | % | Transition weight at stick ends (`currentControlRateProfile->rateDynamics.weightEnd`) |
-* **Notes:** Requires `USE_RATE_DYNAMICS`.
-
-### `MSP2_INAV_SET_RATE_DYNAMICS` (0x2061 / 8289)
-
-* **Direction:** In
-* **Description:** Sets Rate Dynamics configuration parameters for the current control rate profile.
-* **Payload:** (Matches `MSP2_INAV_RATE_DYNAMICS` structure)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `sensitivityCenter` | `uint8_t` | 1 | % | Sets sensitivity at center |
- | `sensitivityEnd` | `uint8_t` | 1 | % | Sets sensitivity at ends |
- | `correctionCenter` | `uint8_t` | 1 | % | Sets correction at center |
- | `correctionEnd` | `uint8_t` | 1 | % | Sets correction at ends |
- | `weightCenter` | `uint8_t` | 1 | % | Sets weight at center |
- | `weightEnd` | `uint8_t` | 1 | % | Sets weight at ends |
-* **Notes:** Requires `USE_RATE_DYNAMICS`. Expects 6 bytes.
-
-### `MSP2_INAV_EZ_TUNE` (0x2070 / 8304)
-
-* **Direction:** Out
-* **Description:** Retrieves the current EZ-Tune parameters.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `enabled` | `uint8_t` | 1 | Boolean: 1 if EZ-Tune is enabled (`ezTune()->enabled`) |
- | `filterHz` | `uint16_t` | 2 | Filter frequency used during tuning (`ezTune()->filterHz`) |
- | `axisRatio` | `uint8_t` | 1 | Roll vs Pitch axis tuning ratio (`ezTune()->axisRatio`) |
- | `response` | `uint8_t` | 1 | Desired response characteristic (`ezTune()->response`) |
- | `damping` | `uint8_t` | 1 | Desired damping characteristic (`ezTune()->damping`) |
- | `stability` | `uint8_t` | 1 | Stability preference (`ezTune()->stability`) |
- | `aggressiveness` | `uint8_t` | 1 | Aggressiveness preference (`ezTune()->aggressiveness`) |
- | `rate` | `uint8_t` | 1 | Resulting rate setting (`ezTune()->rate`) |
- | `expo` | `uint8_t` | 1 | Resulting expo setting (`ezTune()->expo`) |
- | `snappiness` | `uint8_t` | 1 | Snappiness preference (`ezTune()->snappiness`) |
-* **Notes:** Requires `USE_EZ_TUNE`. Calls `ezTuneUpdate()` before sending.
-
-### `MSP2_INAV_EZ_TUNE_SET` (0x2071 / 8305)
-
-* **Direction:** In
-* **Description:** Sets the EZ-Tune parameters and triggers an update.
-* **Payload:** (Matches `MSP2_INAV_EZ_TUNE` structure, potentially omitting `snappiness`)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `enabled` | `uint8_t` | 1 | Sets enabled state |
- | `filterHz` | `uint16_t` | 2 | Sets filter frequency |
- | `axisRatio` | `uint8_t` | 1 | Sets axis ratio |
- | `response` | `uint8_t` | 1 | Sets response characteristic |
- | `damping` | `uint8_t` | 1 | Sets damping characteristic |
- | `stability` | `uint8_t` | 1 | Sets stability preference |
- | `aggressiveness` | `uint8_t` | 1 | Sets aggressiveness preference |
- | `rate` | `uint8_t` | 1 | Sets rate setting |
- | `expo` | `uint8_t` | 1 | Sets expo setting |
- | `snappiness` | `uint8_t` | 1 | (Optional) Sets snappiness preference |
-* **Notes:** Requires `USE_EZ_TUNE`. Expects 10 or 11 bytes. Calls `ezTuneUpdate()` after setting parameters.
-
-### `MSP2_INAV_SELECT_MIXER_PROFILE` (0x2080 / 8320)
-
-* **Direction:** In
-* **Description:** Selects the active mixer profile and saves configuration.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `mixerProfileIndex` | `uint8_t` | 1 | Index of the mixer profile to activate (0-based) |
-* **Notes:** Expects 1 byte. Will fail if armed. Calls `setConfigMixerProfileAndWriteEEPROM()`. Only applicable if `MAX_MIXER_PROFILE_COUNT` > 1.
-
-### `MSP2_ADSB_VEHICLE_LIST` (0x2090 / 8336)
-
-* **Direction:** Out
-* **Description:** Retrieves the list of currently tracked ADSB (Automatic Dependent Surveillance–Broadcast) vehicles.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `maxVehicles` | `uint8_t` | 1 | Maximum number of vehicles tracked (`MAX_ADSB_VEHICLES`). 0 if `USE_ADSB` disabled |
- | `callsignLength` | `uint8_t` | 1 | Maximum length of callsign string (`ADSB_CALL_SIGN_MAX_LENGTH`). 0 if `USE_ADSB` disabled |
- | `totalVehicleMsgs` | `uint32_t` | 4 | Total vehicle messages received (`getAdsbStatus()->vehiclesMessagesTotal`). 0 if `USE_ADSB` disabled |
- | `totalHeartbeatMsgs` | `uint32_t` | 4 | Total heartbeat messages received (`getAdsbStatus()->heartbeatMessagesTotal`). 0 if `USE_ADSB` disabled |
- | **Vehicle Data (Repeated `maxVehicles` times):** | | | |
- | `callsign` | `char[ADSB_CALL_SIGN_MAX_LENGTH]` | `ADSB_CALL_SIGN_MAX_LENGTH` | Vehicle callsign (padded with nulls) |
- | `icao` | `uint32_t` | 4 | ICAO 24-bit address |
- | `latitude` | `int32_t` | 4 | Latitude (1e7 deg) |
- | `longitude` | `int32_t` | 4 | Longitude (1e7 deg) |
- | `altitude` | `int32_t` | 4 | Altitude (cm) |
- | `heading` | `int16_t` | 2 | Heading (degrees) |
- | `tslc` | `uint8_t` | 1 | Time Since Last Communication (seconds) |
- | `emitterType` | `uint8_t` | 1 | Enum: Type of ADSB emitter |
- | `ttl` | `uint8_t` | 1 | Time-to-live counter for this entry |
-* **Notes:** Requires `USE_ADSB`.
-
-### `MSP2_INAV_CUSTOM_OSD_ELEMENTS` (0x2100 / 8448)
-
-* **Direction:** Out
-* **Description:** Retrieves counts related to custom OSD elements defined by the programming framework.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `maxElements` | `uint8_t` | 1 | Maximum number of custom elements (`MAX_CUSTOM_ELEMENTS`) |
- | `maxTextLength` | `uint8_t` | 1 | Maximum length of the text part (`OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1`) |
- | `maxParts` | `uint8_t` | 1 | Maximum number of parts per element (`CUSTOM_ELEMENTS_PARTS`) |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`.
-
-### `MSP2_INAV_CUSTOM_OSD_ELEMENT` (0x2101 / 8449)
-
-* **Direction:** In/Out
-* **Description:** Gets the configuration of a single custom OSD element defined by the programming framework.
-* **Request Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `elementIndex` | `uint8_t` | 1 | Index of the custom element (0 to `MAX_CUSTOM_ELEMENTS - 1`) |
-* **Reply Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | **Parts Data (Repeated `CUSTOM_ELEMENTS_PARTS` times):** | | | |
- | `partType` | `uint8_t` | 1 | Enum (`customElementType_e`): Type of this part (Text, Variable, Symbol) |
- | `partValue` | `uint16_t` | 2 | Value/ID associated with this part (GVAR index, Symbol ID, etc.) |
- | **Visibility Data:** | | | |
- | `visibilityType` | `uint8_t` | 1 | Enum (`logicOperandType_e`): Type of visibility condition source |
- | `visibilityValue` | `uint16_t` | 2 | Value/ID of the visibility condition source (e.g., Logic Condition ID) |
- | **Text Data:** | | | |
- | `elementText` | `char[OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1]` | `OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1` | Static text part of the element (null padding likely) |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. See `osdCustomElement_t`.
-
-### `MSP2_INAV_SET_CUSTOM_OSD_ELEMENTS` (0x2102 / 8450)
-
-* **Direction:** In
-* **Description:** Sets the configuration of a single custom OSD element defined by the programming framework.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `elementIndex` | `uint8_t` | 1 | Index of the custom element (0 to `MAX_CUSTOM_ELEMENTS - 1`) |
- | **Parts Data (Repeated `CUSTOM_ELEMENTS_PARTS` times):** | | | |
- | `partType` | `uint8_t` | 1 | Enum (`customElementType_e`): Type of this part |
- | `partValue` | `uint16_t` | 2 | Value/ID associated with this part |
- | **Visibility Data:** | | | |
- | `visibilityType` | `uint8_t` | 1 | Enum (`logicOperandType_e`): Type of visibility condition source |
- | `visibilityValue` | `uint16_t` | 2 | Value/ID of the visibility condition source |
- | **Text Data:** | | | |
- | `elementText` | `char[OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1]` | `OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1` | Static text part of the element |
-* **Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. Expects `1 + (CUSTOM_ELEMENTS_PARTS * 3) + 3 + (OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1)` bytes. Returns error if index or part type is invalid. Null-terminates the text internally.
-
-### `MSP2_INAV_SERVO_CONFIG` (0x2200 / 8704)
-
-* **Direction:** Out
-* **Description:** Retrieves the configuration parameters for all supported servos (min, max, middle, rate). Supersedes `MSP_SERVO_CONFIGURATIONS`.
-* **Payload:** Repeated `MAX_SUPPORTED_SERVOS` times:
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `min` | `uint16_t` | 2 | PWM | Minimum servo endpoint (`servoParams(i)->min`) |
- | `max` | `uint16_t` | 2 | PWM | Maximum servo endpoint (`servoParams(i)->max`) |
- | `middle` | `uint16_t` | 2 | PWM | Middle/Neutral servo position (`servoParams(i)->middle`) |
- | `rate` | `uint8_t` | 1 | % (-100 to 100) | Servo rate/scaling (`servoParams(i)->rate`) |
-
-### `MSP2_INAV_SET_SERVO_CONFIG` (0x2201 / 8705)
-
-* **Direction:** In
-* **Description:** Sets the configuration parameters for a single servo. Supersedes `MSP_SET_SERVO_CONFIGURATION`.
-* **Payload:**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `servoIndex` | `uint8_t` | 1 | Index | Index of the servo to configure (0 to `MAX_SUPPORTED_SERVOS - 1`) |
- | `min` | `uint16_t` | 2 | PWM | Sets minimum servo endpoint |
- | `max` | `uint16_t` | 2 | PWM | Sets maximum servo endpoint |
- | `middle` | `uint16_t` | 2 | PWM | Sets middle/neutral servo position |
- | `rate` | `uint8_t` | 1 | % | Sets servo rate/scaling |
-* **Notes:** Expects 8 bytes. Returns error if index invalid. Calls `servoComputeScalingFactors()`.
-
-### `MSP2_INAV_GEOZONE` (0x2210 / 8720)
-
-* **Direction:** In/Out
-* **Description:** Get configuration for a specific Geozone.
-* **Request Payload (Get):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `geozoneIndex` | `uint8_t` | 1 | Index of the geozone (0 to `MAX_GEOZONES_IN_CONFIG - 1`) |
-* **Reply Payload (Get):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `geozoneIndex` | `uint8_t` | 1 | Index requested |
- | `type` | `uint8_t` | 1 | Define (`GEOZONE_TYPE_EXCLUSIVE/INCLUSIVE`): Zone type (Inclusion/Exclusion) |
- | `shape` | `uint8_t` | 1 | Define (`GEOZONE_SHAPE_CIRCULAR/POLYGHON`): Zone shape (Polygon/Circular) |
- | `minAltitude` | `uint32_t` | 4 | Minimum allowed altitude within the zone (cm) |
- | `maxAltitude` | `uint32_t` | 4 | Maximum allowed altitude within the zone (cm) |
- | `isSeaLevelRef` | `uint8_t` | 1 | Boolean: 1 if altitudes are relative to sea level, 0 if relative to home |
- | `fenceAction` | `uint8_t` | 1 | Enum (`geozoneActionState_e`): Action to take upon boundary violation |
- | `vertexCount` | `uint8_t` | 1 | Number of vertices defined for this zone |
-* **Notes:** Requires `USE_GEOZONE`. Used by `mspFcGeozoneOutCommand`.
-
-### `MSP2_INAV_SET_GEOZONE` (0x2211 / 8721)
-
-* **Direction:** In
-* **Description:** Sets the main configuration for a specific Geozone (type, shape, altitude, action). **This command resets (clears) all vertices associated with the zone.**
-* **Payload:**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `geozoneIndex` | `uint8_t` | 1 | Index of the geozone (0 to `MAX_GEOZONES_IN_CONFIG - 1`) |
- | `type` | `uint8_t` | 1 | Define (`GEOZONE_TYPE_EXCLUSIVE/INCLUSIVE`): Zone type (Inclusion/Exclusion) |
- | `shape` | `uint8_t` | 1 | Define (`GEOZONE_SHAPE_CIRCULAR/POLYGHON`): Zone shape (Polygon/Circular) |
- | `minAltitude` | `uint32_t` | 4 | Minimum allowed altitude (cm) |
- | `maxAltitude` | `uint32_t` | 4 | Maximum allowed altitude (cm) |
- | `isSeaLevelRef` | `uint8_t` | 1 | Boolean: Altitude reference |
- | `fenceAction` | `uint8_t` | 1 | Enum (`geozoneActionState_e`): Action to take upon boundary violation |
- | `vertexCount` | `uint8_t` | 1 | Number of vertices to be defined (used for validation later) |
-* **Notes:** Requires `USE_GEOZONE`. Expects 14 bytes. Returns error if index invalid. Calls `geozoneResetVertices()`. Vertices must be set subsequently using `MSP2_INAV_SET_GEOZONE_VERTEX`.
-
-### `MSP2_INAV_GEOZONE_VERTEX` (0x2212 / 8722)
-
-* **Direction:** In/Out
-* **Description:** Get a specific vertex (or center+radius for circular zones) of a Geozone.
-* **Request Payload (Get):**
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `geozoneIndex` | `uint8_t` | 1 | Index of the geozone |
- | `vertexId` | `uint8_t` | 1 | Index of the vertex within the zone (0-based). For circles, 0 = center |
-* **Reply Payload (Get - Polygon):**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `geozoneIndex` | `uint8_t` | 1 | Index | Geozone index requested |
- | `vertexId` | `uint8_t` | 1 | Index | Vertex index requested |
- | `latitude` | `int32_t` | 4 | deg * 1e7 | Vertex latitude |
- | `longitude` | `int32_t` | 4 | deg * 1e7 | Vertex longitude |
-* **Reply Payload (Get - Circular):**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `geozoneIndex` | `uint8_t` | 1 | Index | Geozone index requested |
- | `vertexId` | `uint8_t` | 1 | Index | Vertex index requested (always 0 for center) |
- | `centerLatitude` | `int32_t` | 4 | deg * 1e7 | Center latitude |
- | `centerLongitude` | `int32_t` | 4 | deg * 1e7 | Center longitude |
- | `radius` | `uint32_t` | 4 | cm | Radius of the circular zone |
-* **Notes:** Requires `USE_GEOZONE`. Returns error if indexes are invalid or vertex doesn't exist. For circular zones, the radius is stored internally as the 'latitude' of the vertex with index 1.
-
-### `MSP2_INAV_SET_GEOZONE_VERTEX` (0x2213 / 8723)
-
-* **Direction:** In
-* **Description:** Sets a specific vertex (or center+radius for circular zones) for a Geozone.
-* **Payload (Polygon):**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `geozoneIndex` | `uint8_t` | 1 | Index | Geozone index |
- | `vertexId` | `uint8_t` | 1 | Index | Vertex index (0-based) |
- | `latitude` | `int32_t` | 4 | deg * 1e7 | Vertex latitude |
- | `longitude` | `int32_t` | 4 | deg * 1e7 | Vertex longitude |
-* **Payload (Circular):**
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `geozoneIndex` | `uint8_t` | 1 | Index | Geozone index |
- | `vertexId` | `uint8_t` | 1 | Index | Vertex index (must be 0 for center) |
- | `centerLatitude` | `int32_t` | 4 | deg * 1e7 | Center latitude |
- | `centerLongitude` | `int32_t` | 4 | deg * 1e7 | Center longitude |
- | `radius` | `uint32_t` | 4 | cm | Radius of the circular zone |
-* **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).
-
----
-
-## MSPv2 Betaflight Commands (0x3000 Range)
-
-### `MSP2_BETAFLIGHT_BIND` (0x3000 / 12288)
-
-* **Direction:** In
-* **Description:** Initiates the receiver binding procedure for supported serial protocols (CRSF, SRXL2).
-* **Payload:** None
-* **Notes:** Requires `rxConfig()->receiverType == RX_TYPE_SERIAL`. Requires `USE_SERIALRX_CRSF` or `USE_SERIALRX_SRXL2`. Calls `crsfBind()` or `srxl2Bind()` respectively. Returns error if receiver type or provider is not supported for binding.
-
----
-
-## MSPv2 Sensor Input Commands (0x1F00 Range)
-
-These commands are typically sent *to* the FC from external sensor modules connected via a serial port configured for MSP sensor input. They usually expect **no reply** (`MSP_RESULT_NO_REPLY`).
-
-### `MSP2_SENSOR_RANGEFINDER` (0x1F01 / 7937)
-
-* **Direction:** In
-* **Description:** Provides rangefinder data (distance, quality) from an external MSP-based sensor.
-* **Payload:** (`mspSensorRangefinderDataMessage_t`)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `quality` | `uint8_t` | 1 | 0-255 | Quality of the measurement |
- | `distanceMm` | `int32_t` | 4 | mm | Measured distance. Negative value indicates out of range |
-* **Notes:** Requires `USE_RANGEFINDER_MSP`. Calls `mspRangefinderReceiveNewData()`.
-
-### `MSP2_SENSOR_OPTIC_FLOW` (0x1F02 / 7938)
-
-* **Direction:** In
-* **Description:** Provides optical flow data (motion, quality) from an external MSP-based sensor.
-* **Payload:** (`mspSensorOpflowDataMessage_t`)
- | Field | C Type | Size (Bytes) | Description |
- |---|---|---|---|
- | `quality` | `uint8_t` | 1 | Quality of the measurement (0-255) |
- | `motionX` | `int32_t` | 4 | Raw integrated flow value X |
- | `motionY` | `int32_t` | 4 | Raw integrated flow value Y |
-* **Notes:** Requires `USE_OPFLOW_MSP`. Calls `mspOpflowReceiveNewData()`.
-
-### `MSP2_SENSOR_GPS` (0x1F03 / 7939)
-
-* **Direction:** In
-* **Description:** Provides detailed GPS data from an external MSP-based GPS module.
-* **Payload:** (`mspSensorGpsDataMessage_t`)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `instance` | `uint8_t` | 1 | - | Sensor instance number (for multi-GPS) |
- | `gpsWeek` | `uint16_t` | 2 | - | GPS week number (0xFFFF if unavailable) |
- | `msTOW` | `uint32_t` | 4 | ms | Milliseconds Time of Week |
- | `fixType` | `uint8_t` | 1 | Enum | Enum `gpsFixType_e` Type of GPS fix |
- | `satellitesInView`| `uint8_t` | 1 | Count | Number of satellites used in solution |
- | `hPosAccuracy` | `uint16_t` | 2 | cm | Horizontal position accuracy estimate |
- | `vPosAccuracy` | `uint16_t` | 2 | cm | Vertical position accuracy estimate |
- | `hVelAccuracy` | `uint16_t` | 2 | cm/s | Horizontal velocity accuracy estimate |
- | `hdop` | `uint16_t` | 2 | HDOP * 100 | Horizontal Dilution of Precision |
- | `longitude` | `int32_t` | 4 | deg * 1e7 | Longitude |
- | `latitude` | `int32_t` | 4 | deg * 1e7 | Latitude |
- | `mslAltitude` | `int32_t` | 4 | cm | Altitude above Mean Sea Level |
- | `nedVelNorth` | `int32_t` | 4 | cm/s | North velocity (NED frame) |
- | `nedVelEast` | `int32_t` | 4 | cm/s | East velocity (NED frame) |
- | `nedVelDown` | `int32_t` | 4 | cm/s | Down velocity (NED frame) |
- | `groundCourse` | `uint16_t` | 2 | deg * 100 | Ground course (0-36000) |
- | `trueYaw` | `uint16_t` | 2 | deg * 100 | True heading/yaw (0-36000, 65535 if unavailable) |
- | `year` | `uint16_t` | 2 | - | Year (e.g., 2023) |
- | `month` | `uint8_t` | 1 | - | Month (1-12) |
- | `day` | `uint8_t` | 1 | - | Day of month (1-31) |
- | `hour` | `uint8_t` | 1 | - | Hour (0-23) |
- | `min` | `uint8_t` | 1 | - | Minute (0-59) |
- | `sec` | `uint8_t` | 1 | - | Second (0-59) |
-* **Notes:** Requires `USE_GPS_PROTO_MSP`. Calls `mspGPSReceiveNewData()`.
-
-### `MSP2_SENSOR_COMPASS` (0x1F04 / 7940)
-
-* **Direction:** In
-* **Description:** Provides magnetometer data from an external MSP-based compass module.
-* **Payload:** (`mspSensorCompassDataMessage_t`)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `instance` | `uint8_t` | 1 | - | Sensor instance number |
- | `timeMs` | `uint32_t` | 4 | ms | Timestamp from the sensor |
- | `magX` | `int16_t` | 2 | mGauss | Front component reading |
- | `magY` | `int16_t` | 2 | mGauss | Right component reading |
- | `magZ` | `int16_t` | 2 | mGauss | Down component reading |
-* **Notes:** Requires `USE_MAG_MSP`. Calls `mspMagReceiveNewData()`.
-
-### `MSP2_SENSOR_BAROMETER` (0x1F05 / 7941)
-
-* **Direction:** In
-* **Description:** Provides barometer data from an external MSP-based barometer module.
-* **Payload:** (`mspSensorBaroDataMessage_t`)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `instance` | `uint8_t` | 1 | - | Sensor instance number |
- | `timeMs` | `uint32_t` | 4 | ms | Timestamp from the sensor |
- | `pressurePa` | `float` | 4 | Pa | Absolute pressure |
- | `temp` | `int16_t` | 2 | 0.01 deg C | Temperature |
-* **Notes:** Requires `USE_BARO_MSP`. Calls `mspBaroReceiveNewData()`.
-
-### `MSP2_SENSOR_AIRSPEED` (0x1F06 / 7942)
-
-* **Direction:** In
-* **Description:** Provides airspeed data from an external MSP-based pitot sensor module.
-* **Payload:** (`mspSensorAirspeedDataMessage_t`)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `instance` | `uint8_t` | 1 | - | Sensor instance number |
- | `timeMs` | `uint32_t` | 4 | ms | Timestamp from the sensor |
- | `diffPressurePa`| `float` | 4 | Pa | Differential pressure |
- | `temp` | `int16_t` | 2 | 0.01 deg C | Temperature |
-* **Notes:** Requires `USE_PITOT_MSP`. Calls `mspPitotmeterReceiveNewData()`.
-
-### `MSP2_SENSOR_HEADTRACKER` (0x1F07 / 7943)
-
-* **Direction:** In
-* **Description:** Provides head tracker orientation data.
-* **Payload:** (Structure not defined in provided headers, but likely Roll, Pitch, Yaw angles)
- | Field | C Type | Size (Bytes) | Units | Description |
- |---|---|---|---|---|
- | `...` | Varies | Variable | Head tracker angles (e.g., int16 Roll, Pitch, Yaw in deci-degrees) |
-* **Notes:** Requires `USE_HEADTRACKER` and `USE_HEADTRACKER_MSP`. Calls `mspHeadTrackerReceiverNewData()`. Payload structure needs verification from `mspHeadTrackerReceiverNewData` implementation.
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