From d691333e82ff74358450dc333e3cb577bf8e2461 Mon Sep 17 00:00:00 2001 From: shota Date: Fri, 26 Sep 2025 14:04:45 +0900 Subject: [PATCH 01/67] Add airspeed TPA support --- docs/Settings.md | 10 +++++ src/main/fc/controlrate_profile.c | 3 +- .../fc/controlrate_profile_config_struct.h | 1 + src/main/fc/settings.yaml | 5 +++ src/main/flight/pid.c | 37 ++++++++++--------- src/main/sensors/pitotmeter.c | 9 +++++ src/main/sensors/pitotmeter.h | 1 + 7 files changed, 48 insertions(+), 18 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 256dd05a005..afab765a87d 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -302,6 +302,16 @@ ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't hav --- +### airspeed_tpa + +Use airspeed instead of throttle position for TPA if airspeed is available. use throttle as {tpa_breakpoint + (airspeed - fw_reference_airspeed)/fw_reference_airspeed * (tpa_breakpoint - ThrottleIdleValue(default:1150))} for TPA calculation + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### align_board_pitch Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc diff --git a/src/main/fc/controlrate_profile.c b/src/main/fc/controlrate_profile.c index c8b144e136c..42fd3129ce1 100644 --- a/src/main/fc/controlrate_profile.c +++ b/src/main/fc/controlrate_profile.c @@ -46,7 +46,8 @@ void pgResetFn_controlRateProfiles(controlRateConfig_t *instance) .dynPID = SETTING_TPA_RATE_DEFAULT, .dynPID_on_YAW = SETTING_TPA_ON_YAW_DEFAULT, .pa_breakpoint = SETTING_TPA_BREAKPOINT_DEFAULT, - .fixedWingTauMs = SETTING_FW_TPA_TIME_CONSTANT_DEFAULT + .fixedWingTauMs = SETTING_FW_TPA_TIME_CONSTANT_DEFAULT, + .airspeed_tpa = SETTING_AIRSPEED_TPA_DEFAULT, }, .stabilized = { diff --git a/src/main/fc/controlrate_profile_config_struct.h b/src/main/fc/controlrate_profile_config_struct.h index e4038537603..acd4e40926f 100644 --- a/src/main/fc/controlrate_profile_config_struct.h +++ b/src/main/fc/controlrate_profile_config_struct.h @@ -32,6 +32,7 @@ typedef struct controlRateConfig_s { bool dynPID_on_YAW; uint16_t pa_breakpoint; // Breakpoint where TPA is activated uint16_t fixedWingTauMs; // Time constant of airplane TPA PT1-filter + bool airspeed_tpa; // Use airspeed instead of throttle position for TPA calculation } throttle; struct { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5fe29261630..a5593efaf03 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1343,6 +1343,11 @@ groups: field: throttle.dynPID min: 0 max: 100 + - name: airspeed_tpa + description: "Use airspeed instead of throttle position for TPA if airspeed is available. use throttle as {tpa_breakpoint + (airspeed - fw_reference_airspeed)/fw_reference_airspeed * (tpa_breakpoint - ThrottleIdleValue(default:1150))} for TPA calculation" + type: bool + field: throttle.airspeed_tpa + default_value: OFF - name: tpa_breakpoint description: "See tpa_rate." default_value: 1500 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index ae8eb57fb30..f957073ccbd 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -469,15 +469,15 @@ static float calculateFixedWingTPAFactor(uint16_t throttle) return tpaFactor; } -static float calculateMultirotorTPAFactor(void) +static float calculateMultirotorTPAFactor(uint16_t throttle) { float tpaFactor; // TPA should be updated only when TPA is actually set - if (currentControlRateProfile->throttle.dynPID == 0 || rcCommand[THROTTLE] < currentControlRateProfile->throttle.pa_breakpoint) { + if (currentControlRateProfile->throttle.dynPID == 0 || throttle < currentControlRateProfile->throttle.pa_breakpoint) { tpaFactor = 1.0f; - } else if (rcCommand[THROTTLE] < getMaxThrottle()) { - tpaFactor = (100 - (uint16_t)currentControlRateProfile->throttle.dynPID * (rcCommand[THROTTLE] - currentControlRateProfile->throttle.pa_breakpoint) / (float)(getMaxThrottle() - currentControlRateProfile->throttle.pa_breakpoint)) / 100.0f; + } else if (throttle < getMaxThrottle()) { + tpaFactor = (100 - (uint16_t)currentControlRateProfile->throttle.dynPID * (throttle - currentControlRateProfile->throttle.pa_breakpoint) / (float)(getMaxThrottle() - currentControlRateProfile->throttle.pa_breakpoint)) / 100.0f; } else { tpaFactor = (100 - currentControlRateProfile->throttle.dynPID) / 100.0f; } @@ -493,20 +493,24 @@ void schedulePidGainsUpdate(void) void updatePIDCoefficients(void) { STATIC_FASTRAM uint16_t prevThrottle = 0; + STATIC_FASTRAM uint16_t tpaThrottle = 0; - // Check if throttle changed. Different logic for fixed wing vs multirotor - if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { - uint16_t filteredThrottle = pt1FilterApply(&fixedWingTpaFilter, rcCommand[THROTTLE]); - if (filteredThrottle != prevThrottle) { - prevThrottle = filteredThrottle; - pidGainsUpdateRequired = true; - } + if (usedPidControllerType == PID_TYPE_PIFF && pitotValidForAirspeed() && currentControlRateProfile->throttle.airspeed_tpa) { + // Use airspeed instead of throttle for TPA calculation + const float airspeed = getAirspeedEstimate(); // in cm/s + const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s + tpaThrottle = currentControlRateProfile->throttle.pa_breakpoint + (uint16_t)((airspeed - referenceAirspeed) / referenceAirspeed * (currentControlRateProfile->throttle.pa_breakpoint - getThrottleIdleValue())); + //upper and lower limits will be applied in calculateFixedWingTPAFactor() + } + else if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { + tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, rcCommand[THROTTLE]); } else { - if (rcCommand[THROTTLE] != prevThrottle) { - prevThrottle = rcCommand[THROTTLE]; - pidGainsUpdateRequired = true; - } + tpaThrottle = rcCommand[THROTTLE]; + } + if (tpaThrottle != prevThrottle) { + prevThrottle = tpaThrottle; + pidGainsUpdateRequired = true; } #ifdef USE_ANTIGRAVITY @@ -528,8 +532,7 @@ void updatePIDCoefficients(void) return; } - const float tpaFactor = usedPidControllerType == PID_TYPE_PIFF ? calculateFixedWingTPAFactor(prevThrottle) : calculateMultirotorTPAFactor(); - + const float tpaFactor = usedPidControllerType == PID_TYPE_PIFF ? calculateFixedWingTPAFactor(prevThrottle) : calculateMultirotorTPAFactor(prevThrottle); // PID coefficients can be update only with THROTTLE and TPA or inflight PID adjustments //TODO: Next step would be to update those only at THROTTLE or inflight adjustments change for (int axis = 0; axis < 3; axis++) { diff --git a/src/main/sensors/pitotmeter.c b/src/main/sensors/pitotmeter.c index baf7bed0a61..cb5b9f76f9a 100755 --- a/src/main/sensors/pitotmeter.c +++ b/src/main/sensors/pitotmeter.c @@ -305,4 +305,13 @@ bool pitotIsHealthy(void) return (millis() - pitot.lastSeenHealthyMs) < PITOT_HARDWARE_TIMEOUT_MS; } +bool pitotValidForAirspeed(void) +{ + bool ret = false; + ret = pitotIsHealthy() && pitotIsCalibrationComplete(); + if (detectedSensors[SENSOR_INDEX_PITOT] == PITOT_VIRTUAL) { + ret = ret && STATE(GPS_FIX); + } + return ret; +} #endif /* PITOT */ diff --git a/src/main/sensors/pitotmeter.h b/src/main/sensors/pitotmeter.h index aed924f8e4c..68f5a9c1a02 100755 --- a/src/main/sensors/pitotmeter.h +++ b/src/main/sensors/pitotmeter.h @@ -69,5 +69,6 @@ void pitotStartCalibration(void); void pitotUpdate(void); float getAirspeedEstimate(void); bool pitotIsHealthy(void); +bool pitotValidForAirspeed(void); #endif From 6bc321b773c41ee928f62d5994b8e2e1345f4e20 Mon Sep 17 00:00:00 2001 From: shota Date: Sat, 27 Sep 2025 19:10:17 +0900 Subject: [PATCH 02/67] minor fix --- src/main/flight/pid.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index f957073ccbd..a85d9bf6bab 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -500,7 +500,7 @@ void updatePIDCoefficients(void) const float airspeed = getAirspeedEstimate(); // in cm/s const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s tpaThrottle = currentControlRateProfile->throttle.pa_breakpoint + (uint16_t)((airspeed - referenceAirspeed) / referenceAirspeed * (currentControlRateProfile->throttle.pa_breakpoint - getThrottleIdleValue())); - //upper and lower limits will be applied in calculateFixedWingTPAFactor() + tpaThrottle = constrain(tpaThrottle, getThrottleIdleValue(), tpaThrottle); } else if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, rcCommand[THROTTLE]); From e14ba5d668a7cb651a068d283805753e7f2b7c2f Mon Sep 17 00:00:00 2001 From: functionpointer Date: Sat, 25 Oct 2025 18:35:49 +0200 Subject: [PATCH 03/67] VANTAC_RF007: Add new target FrSky/Rotorflight Vantac RF007 Quite similar to NEXUSX, but with FrSky built-in receiver --- src/main/target/VANTAC_RF007/CMakeLists.txt | 3 + src/main/target/VANTAC_RF007/README.md | 69 +++++++++ src/main/target/VANTAC_RF007/config.c | 28 ++++ src/main/target/VANTAC_RF007/target.c | 45 ++++++ src/main/target/VANTAC_RF007/target.h | 160 ++++++++++++++++++++ 5 files changed, 305 insertions(+) create mode 100644 src/main/target/VANTAC_RF007/CMakeLists.txt create mode 100644 src/main/target/VANTAC_RF007/README.md create mode 100644 src/main/target/VANTAC_RF007/config.c create mode 100644 src/main/target/VANTAC_RF007/target.c create mode 100644 src/main/target/VANTAC_RF007/target.h diff --git a/src/main/target/VANTAC_RF007/CMakeLists.txt b/src/main/target/VANTAC_RF007/CMakeLists.txt new file mode 100644 index 00000000000..49f5a9edd76 --- /dev/null +++ b/src/main/target/VANTAC_RF007/CMakeLists.txt @@ -0,0 +1,3 @@ +target_stm32f722xe(VANTAC_RF007) +target_stm32f722xe(VANTAC_RF007_9SERVOS) +target_stm32f722xe(VANTAC_RF007_NOI2C) diff --git a/src/main/target/VANTAC_RF007/README.md b/src/main/target/VANTAC_RF007/README.md new file mode 100644 index 00000000000..9cf0f4a820d --- /dev/null +++ b/src/main/target/VANTAC_RF007/README.md @@ -0,0 +1,69 @@ +FrSky/Rotorflight VANTAC RF007 +============================== + +Family of flight controllers originally designed for Helicopters using Rotorflight. +There are three versions available, the only difference is the type of integrated FrSky receiver. +All versions share the same targets in INAV. + +Rotorflight's site: https://www.rotorflight.org/docs/controllers/frsky-007 + +FrSky's manual: https://www.frsky-rc.com/wp-content/uploads/Downloads/Amanual/VANTAC%20RF007%20Manual.pdf + +Built-in receiver +------------------- + +The built-in receiver is connected to UART5 and uses FrSky FBUS. +Only the RxUG update port is connected to the receiver directly. +All other pins are connected to the STM32F7 running INAV. + +The receiver has a bind button labelled "Rx". +To bind the Archer+ version, the button needs to be held while power gets connected. +The Archer+ version will bind to Multiprotocol Module FrSky X2 D16 mode, among other options. +For more information, see the manufacturer's manual. + +Pin configuration +----------------- + +All pin orders are from left to right, when looking at the connector on the flight controller. + +**Port "C" has the data pins swapped, the manufacturers documentation is incorrect.** +Port "A" is wired correctly. + +| Marking on the case | VANTAC_RF007 | VANTAC_RF007_9SERVOS | VANTAC_RF007_NOI2C | +|---------------------|-------------------------------------------------------|-------------------------------------------------------|-------------------------------------------------------| +| S1 | Output S1 | Output S1 | Output S1 | +| S2 | Output S2 | Output S2 | Output S2 | +| S3 | Output S3 | Output S3 | Output S3 | +| TAIL | Output S4 | Output S4 | Output S4 | +| ESC | Output S5 | Output S5 | Output S5 | +| RPM | Output S6 | Output S6 | Output S6 | +| TLM | Output S7 | Output S7 | Output S7 | +| AUX | UART1 TX | Output S8 | Output S8 | +| SBUS | UART1 RX | Output S9 | Output S9 | +| A | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | +| C | I2C
pin order:
**SDA, SCL, 5V, GND** | I2C
pin order:
**SDA, SCL, 5V, GND** | UART3
pin order:
**RX, TX, 5V, GND** | +| EXT-V | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | +| built-in receiver | UART5 | UART5 | UART5 | + +Hardware layout +--------------- + + +| Marking on the case | STM32 pin | Servo | UART | I2C | +|---------------------|-----------|------------------------------:|---------------:|---------:| +| S1 | PB4 | TIM3CH1 | n/a | n/a | +| S2 | PB5 | TIM3CH2 | n/a | n/a | +| S3 | PB0 | TIM3CH3 | n/a | n/a | +| TAIL | PA15 | TIM2CH1 | n/a | n/a | +| ESC | PA9 | TIM1CH2 | UART1 TX | n/a | +| RPM | PA2 | TIM2CH3
TIM5CH3
TIM9CH1 | UART2 TX | n/a | +| TLM | PA3 | TIM2CH4
TIM5CH4
TIM9CH2 | UART2 RX | n/a | +| AUX | PB6 | TIM4CH1 | UART1 TX | I2C1 SCL | +| SBUS | PB7 | TIM4CH2 | UART1 RX | I2C1 SDA | +| A | PA0/PA1 | TIM1
TIM5 | UART2
UART4 | n/a | +| C | PB10/PB11 | TIM2 | UART3 | I2C2 | +| EXT-V | PC0 | n/a | n/a | n/a | +| built-in receiver | PC12/PD2 | n/a | UART5 | n/a | + +The pinout is extremely similar to the F7B5 reference design from Rotorflight. +https://github.com/rotorflight/rotorflight-ref-design/blob/master/Reference-Design-F7B.md \ No newline at end of file diff --git a/src/main/target/VANTAC_RF007/config.c b/src/main/target/VANTAC_RF007/config.c new file mode 100644 index 00000000000..c3c3f3d6295 --- /dev/null +++ b/src/main/target/VANTAC_RF007/config.c @@ -0,0 +1,28 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +void targetConfiguration(void) +{ + +} diff --git a/src/main/target/VANTAC_RF007/target.c b/src/main/target/VANTAC_RF007/target.c new file mode 100644 index 00000000000..b9a1822809a --- /dev/null +++ b/src/main/target/VANTAC_RF007/target.c @@ -0,0 +1,45 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "target.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "S1" + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "S2" + DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "S3" + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "TAIL" + + DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "ESC" + + DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "RPM", clashes with UART2 TX + DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "TLM", clashes with UART2 RX + +#if defined(VANTAC_RF007_9SERVOS) || defined(VANTAC_RF007_NOI2C) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "AUX", clashes with UART1 TX and I2C1 SCL + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "SBUS", clashes with UART1 RX and I2C1 SDA +#endif +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/VANTAC_RF007/target.h b/src/main/target/VANTAC_RF007/target.h new file mode 100644 index 00000000000..09405810d87 --- /dev/null +++ b/src/main/target/VANTAC_RF007/target.h @@ -0,0 +1,160 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "F7B5" + +#define USBD_PRODUCT_STRING "VANTAC_RF007" + +#define LED0 PC14 +#define LED1 PC15 + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_ICM42605 // is actually ICM42688P +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_CS_PIN PA4 +#define ICM42605_EXTI_PIN PB2 +#define ICM42605_SPI_BUS BUS_SPI1 + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +//#define USE_I2C_DEVICE_1 // clashes with UART1 +//#define I2C1_SCL PB6 +//#define I2C1_SDA PB7 + +#if defined(VANTAC_RF007) || defined(VANTAC_RF007_9SERVOS) +#define USE_I2C_DEVICE_2 // clashes with UART3 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 +#define DEFAULT_I2C BUS_I2C2 +#else +#define DEFAULT_I2C BUS_I2C1 +#endif + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_SPL06 +#define SPL06_I2C_ADDR 119 + +#define TEMPERATURE_I2C_BUS DEFAULT_I2C + +#define PITOT_I2C_BUS DEFAULT_I2C + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS DEFAULT_I2C + +// *************** SPI2 Blackbox ******************* +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_FLASHFS +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI2 +#define W25N01G_CS_PIN PB12 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** UART ***************************** +#define USE_VCP + +#ifdef VANTAC_RF007 +#define USE_UART1 // clashes with I2C1 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 // pin labelled "SBUS" +#endif + +//#define USE_UART2 // clashes with 2 servo outputs +//#define UART2_TX_PIN PA2 // pin labelled as "RPM" +//#define UART2_RX_PIN PA3 // pin labelled as "TLM" + +#ifdef VANTAC_RF007_NOI2C +#define USE_UART3 +// port labelled "C" +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#endif + +#define USE_UART4 +// port labelled "A" +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +// port internal receiver +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#if defined(VANTAC_RF007) +#define SERIAL_PORT_COUNT 4 +#elif defined(VANTAC_RF007_9SERVOS) +#define SERIAL_PORT_COUNT 3 +#elif defined(VANTAC_RF007_NOI2C) +#define SERIAL_PORT_COUNT 4 +#endif + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_FBUS +#define SERIALRX_UART SERIAL_PORT_USART5 + +#define SENSORS_SET (SENSOR_ACC|SENSOR_BARO) + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC0 + +#define VBAT_ADC_CHANNEL ADC_CHN_3 // port labelled "EXT-V" +//BEC ADC is ADC_CHN_2 +//BUS ADC is ADC_CHN_1 + +#define VBAT_SCALE_DEFAULT 2464 + +#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_TX_PROF_SEL) + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#if defined(VANTAC_RF007) +#define MAX_PWM_OUTPUT_PORTS 7 +#elif defined(VANTAC_RF007_9SERVOS) || defined(VANTAC_RF007_NOI2C) +#define MAX_PWM_OUTPUT_PORTS 9 +#endif + +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR +#define USE_SMARTPORT_MASTER // no internal current sensor, enable SMARTPORT_MASTER so external ones can be used From 0c6b4fd1048437b4140791be94c1affa2c934872 Mon Sep 17 00:00:00 2001 From: functionpointer Date: Sat, 1 Nov 2025 16:09:53 +0100 Subject: [PATCH 04/67] VANTAC_RF007: combine targets --- src/main/target/VANTAC_RF007/CMakeLists.txt | 2 - src/main/target/VANTAC_RF007/README.md | 42 +++++++++++---------- src/main/target/VANTAC_RF007/target.c | 2 - src/main/target/VANTAC_RF007/target.h | 41 ++++++-------------- 4 files changed, 35 insertions(+), 52 deletions(-) diff --git a/src/main/target/VANTAC_RF007/CMakeLists.txt b/src/main/target/VANTAC_RF007/CMakeLists.txt index 49f5a9edd76..3ad19278f00 100644 --- a/src/main/target/VANTAC_RF007/CMakeLists.txt +++ b/src/main/target/VANTAC_RF007/CMakeLists.txt @@ -1,3 +1 @@ target_stm32f722xe(VANTAC_RF007) -target_stm32f722xe(VANTAC_RF007_9SERVOS) -target_stm32f722xe(VANTAC_RF007_NOI2C) diff --git a/src/main/target/VANTAC_RF007/README.md b/src/main/target/VANTAC_RF007/README.md index 9cf0f4a820d..e5d3b4a0739 100644 --- a/src/main/target/VANTAC_RF007/README.md +++ b/src/main/target/VANTAC_RF007/README.md @@ -1,9 +1,9 @@ FrSky/Rotorflight VANTAC RF007 ============================== -Family of flight controllers originally designed for Helicopters using Rotorflight. +Family of flight controllers originally designed for helicopters using Rotorflight. There are three versions available, the only difference is the type of integrated FrSky receiver. -All versions share the same targets in INAV. +All versions share the same target in INAV. Rotorflight's site: https://www.rotorflight.org/docs/controllers/frsky-007 @@ -24,27 +24,31 @@ For more information, see the manufacturer's manual. Pin configuration ----------------- +The RPM, TLM, AUX and SBUS pins are Servo/Motor outputs by default. +However, when UART1 or UART2 are assigned a function in the ports tab, the pins will become a UART instead. +See the table below. + +| Marking on the case | Both UART1 and UART2 unused | UART1 in use | UART2 in use | Both UART1 and UART2 in use | +|---------------------|------------------------------------------------------------------------------------------------|------------------------------------------------------------------------------------------------|------------------------------------------------------------------------------------------------|------------------------------------------------------------------------------------------------| +| S1 | Output S1 | Output S1 | Output S1 | Output S1 | +| S2 | Output S2 | Output S2 | Output S2 | Output S2 | +| S3 | Output S3 | Output S3 | Output S3 | Output S3 | +| TAIL | Output S4 | Output S4 | Output S4 | Output S4 | +| ESC | Output S5 | Output S5 | Output S5 | Output S5 | +| RPM | Output S6 | Output S6 | UART2 TX | UART2 TX | +| TLM | Output S7 | Output S7 | UART2 RX | UART2 RX | +| AUX | Output S8 | UART1 TX | Output S6 | UART1 TX | +| SBUS | Output S9 | UART1 RX | Output S7 | UART1 RX | +| A | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | +| C | I2C
pin order:
**SDA, SCL, 5V, GND**
or
UART3
pin order:
**RX, TX, 5V, GND** | I2C
pin order:
**SDA, SCL, 5V, GND**
or
UART3
pin order:
**RX, TX, 5V, GND** | I2C
pin order:
**SDA, SCL, 5V, GND**
or
UART3
pin order:
**RX, TX, 5V, GND** | I2C
pin order:
**SDA, SCL, 5V, GND**
or
UART3
pin order:
**RX, TX, 5V, GND** | +| EXT-V | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | +| built-in receiver | UART5 | UART5 | UART5 | UART5 | + All pin orders are from left to right, when looking at the connector on the flight controller. -**Port "C" has the data pins swapped, the manufacturers documentation is incorrect.** +**Port "C" has the data pins swapped. The manufacturers documentation is incorrect.** Port "A" is wired correctly. -| Marking on the case | VANTAC_RF007 | VANTAC_RF007_9SERVOS | VANTAC_RF007_NOI2C | -|---------------------|-------------------------------------------------------|-------------------------------------------------------|-------------------------------------------------------| -| S1 | Output S1 | Output S1 | Output S1 | -| S2 | Output S2 | Output S2 | Output S2 | -| S3 | Output S3 | Output S3 | Output S3 | -| TAIL | Output S4 | Output S4 | Output S4 | -| ESC | Output S5 | Output S5 | Output S5 | -| RPM | Output S6 | Output S6 | Output S6 | -| TLM | Output S7 | Output S7 | Output S7 | -| AUX | UART1 TX | Output S8 | Output S8 | -| SBUS | UART1 RX | Output S9 | Output S9 | -| A | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | UART4
pin order:
TX, RX, 5V, GND | -| C | I2C
pin order:
**SDA, SCL, 5V, GND** | I2C
pin order:
**SDA, SCL, 5V, GND** | UART3
pin order:
**RX, TX, 5V, GND** | -| EXT-V | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | battery voltage
max 80V
pin order:
Vbat, GND | -| built-in receiver | UART5 | UART5 | UART5 | - Hardware layout --------------- diff --git a/src/main/target/VANTAC_RF007/target.c b/src/main/target/VANTAC_RF007/target.c index b9a1822809a..3589a56c224 100644 --- a/src/main/target/VANTAC_RF007/target.c +++ b/src/main/target/VANTAC_RF007/target.c @@ -36,10 +36,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "RPM", clashes with UART2 TX DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "TLM", clashes with UART2 RX -#if defined(VANTAC_RF007_9SERVOS) || defined(VANTAC_RF007_NOI2C) DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "AUX", clashes with UART1 TX and I2C1 SCL DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "SBUS", clashes with UART1 RX and I2C1 SDA -#endif }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/VANTAC_RF007/target.h b/src/main/target/VANTAC_RF007/target.h index 09405810d87..3f54ef4cf37 100644 --- a/src/main/target/VANTAC_RF007/target.h +++ b/src/main/target/VANTAC_RF007/target.h @@ -42,31 +42,28 @@ #define USE_I2C_DEVICE_1 #define I2C1_SCL PB8 #define I2C1_SDA PB9 - -//#define USE_I2C_DEVICE_1 // clashes with UART1 +// alternate pin assignment +// clashes with UART1 +// also won't allow the built-in barometer to be used //#define I2C1_SCL PB6 //#define I2C1_SDA PB7 -#if defined(VANTAC_RF007) || defined(VANTAC_RF007_9SERVOS) #define USE_I2C_DEVICE_2 // clashes with UART3 #define I2C2_SCL PB10 #define I2C2_SDA PB11 -#define DEFAULT_I2C BUS_I2C2 -#else -#define DEFAULT_I2C BUS_I2C1 -#endif +#define EXTERNAL_I2C BUS_I2C2 #define USE_BARO #define BARO_I2C_BUS BUS_I2C1 #define USE_BARO_SPL06 #define SPL06_I2C_ADDR 119 -#define TEMPERATURE_I2C_BUS DEFAULT_I2C +#define TEMPERATURE_I2C_BUS EXTERNAL_I2C -#define PITOT_I2C_BUS DEFAULT_I2C +#define PITOT_I2C_BUS EXTERNAL_I2C #define USE_RANGEFINDER -#define RANGEFINDER_I2C_BUS DEFAULT_I2C +#define RANGEFINDER_I2C_BUS EXTERNAL_I2C // *************** SPI2 Blackbox ******************* #define USE_SPI_DEVICE_2 @@ -83,22 +80,18 @@ // *************** UART ***************************** #define USE_VCP -#ifdef VANTAC_RF007 #define USE_UART1 // clashes with I2C1 #define UART1_TX_PIN PB6 #define UART1_RX_PIN PB7 // pin labelled "SBUS" -#endif -//#define USE_UART2 // clashes with 2 servo outputs -//#define UART2_TX_PIN PA2 // pin labelled as "RPM" -//#define UART2_RX_PIN PA3 // pin labelled as "TLM" +#define USE_UART2 +#define UART2_TX_PIN PA2 // pin labelled as "RPM" +#define UART2_RX_PIN PA3 // pin labelled as "TLM" -#ifdef VANTAC_RF007_NOI2C -#define USE_UART3 +#define USE_UART3 // clashes with I2C2 // port labelled "C" #define UART3_TX_PIN PB10 #define UART3_RX_PIN PB11 -#endif #define USE_UART4 // port labelled "A" @@ -110,13 +103,7 @@ #define UART5_TX_PIN PC12 #define UART5_RX_PIN PD2 -#if defined(VANTAC_RF007) -#define SERIAL_PORT_COUNT 4 -#elif defined(VANTAC_RF007_9SERVOS) -#define SERIAL_PORT_COUNT 3 -#elif defined(VANTAC_RF007_NOI2C) -#define SERIAL_PORT_COUNT 4 -#endif +#define SERIAL_PORT_COUNT 6 #define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define SERIALRX_PROVIDER SERIALRX_FBUS @@ -148,11 +135,7 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD 0xffff -#if defined(VANTAC_RF007) -#define MAX_PWM_OUTPUT_PORTS 7 -#elif defined(VANTAC_RF007_9SERVOS) || defined(VANTAC_RF007_NOI2C) #define MAX_PWM_OUTPUT_PORTS 9 -#endif #define USE_DSHOT #define USE_SERIALSHOT From c1e211205d107293bbad9632af4721f46d918880 Mon Sep 17 00:00:00 2001 From: shota Date: Thu, 6 Nov 2025 10:44:51 +0900 Subject: [PATCH 05/67] airspeed tpa --- docs/Settings.md | 6 +- src/main/fc/controlrate_profile.c | 2 +- .../fc/controlrate_profile_config_struct.h | 2 +- src/main/fc/settings.yaml | 12 ++-- src/main/flight/pid.c | 60 ++++++++++++------- 5 files changed, 51 insertions(+), 31 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index afab765a87d..aea055fb937 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -302,13 +302,13 @@ ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't hav --- -### airspeed_tpa +### airspeed_tpa_pow -Use airspeed instead of throttle position for TPA if airspeed is available. use throttle as {tpa_breakpoint + (airspeed - fw_reference_airspeed)/fw_reference_airspeed * (tpa_breakpoint - ThrottleIdleValue(default:1150))} for TPA calculation +Use airspeed instead of throttle position for TPA if airspeed is available on fixedwing. pid_multiplier(tpa_factor) = (referenceAirspeed/airspeed)**(airspeed_tpa_pow/100). Set to 0 will disable this feature and use throttle based tpa; | Default | Min | Max | | --- | --- | --- | -| OFF | OFF | ON | +| 120 | 0 | 200 | --- diff --git a/src/main/fc/controlrate_profile.c b/src/main/fc/controlrate_profile.c index 42fd3129ce1..1c2d632d9ce 100644 --- a/src/main/fc/controlrate_profile.c +++ b/src/main/fc/controlrate_profile.c @@ -47,7 +47,7 @@ void pgResetFn_controlRateProfiles(controlRateConfig_t *instance) .dynPID_on_YAW = SETTING_TPA_ON_YAW_DEFAULT, .pa_breakpoint = SETTING_TPA_BREAKPOINT_DEFAULT, .fixedWingTauMs = SETTING_FW_TPA_TIME_CONSTANT_DEFAULT, - .airspeed_tpa = SETTING_AIRSPEED_TPA_DEFAULT, + .airspeed_tpa_pow = SETTING_AIRSPEED_TPA_POW_DEFAULT, }, .stabilized = { diff --git a/src/main/fc/controlrate_profile_config_struct.h b/src/main/fc/controlrate_profile_config_struct.h index acd4e40926f..8c4e57b7f1f 100644 --- a/src/main/fc/controlrate_profile_config_struct.h +++ b/src/main/fc/controlrate_profile_config_struct.h @@ -32,7 +32,7 @@ typedef struct controlRateConfig_s { bool dynPID_on_YAW; uint16_t pa_breakpoint; // Breakpoint where TPA is activated uint16_t fixedWingTauMs; // Time constant of airplane TPA PT1-filter - bool airspeed_tpa; // Use airspeed instead of throttle position for TPA calculation + uint16_t airspeed_tpa_pow; // Use airspeed instead of throttle position for TPA calculation,0 to disable } throttle; struct { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a5593efaf03..1b14b82d580 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1337,17 +1337,19 @@ groups: field: throttle.rcExpo8 min: 0 max: 100 + - name: airspeed_tpa_pow + description: "Use airspeed instead of throttle position for TPA if airspeed is available on fixedwing. pid_multiplier(tpa_factor) = (referenceAirspeed/airspeed)**(airspeed_tpa_pow/100). Set to 0 will disable this feature and use throttle based tpa;" + type: uint16_t + field: throttle.airspeed_tpa_pow + default_value: 120 + min: 0 + max: 200 - name: tpa_rate description: "Throttle PID attenuation reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate." default_value: 0 field: throttle.dynPID min: 0 max: 100 - - name: airspeed_tpa - description: "Use airspeed instead of throttle position for TPA if airspeed is available. use throttle as {tpa_breakpoint + (airspeed - fw_reference_airspeed)/fw_reference_airspeed * (tpa_breakpoint - ThrottleIdleValue(default:1150))} for TPA calculation" - type: bool - field: throttle.airspeed_tpa - default_value: OFF - name: tpa_breakpoint description: "See tpa_rate." default_value: 1500 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index a85d9bf6bab..9b85d413e69 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -441,6 +441,14 @@ float pidRcCommandToRate(int16_t stick, uint8_t rate) return scaleRangef((float) stick, -500.0f, 500.0f, -maxRateDPS, maxRateDPS); } +static float calculateFixedWingAirspeedTPAFactor(void){ + const float airspeed = getAirspeedEstimate(); // in cm/s + const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s + float tpaFactor= powf(referenceAirspeed/(airspeed+0.01f), currentControlRateProfile->throttle.airspeed_tpa_pow/100.0f); + tpaFactor= constrainf(tpaFactor, 0.3f, 2.0f); + return tpaFactor; +} + static float calculateFixedWingTPAFactor(uint16_t throttle) { float tpaFactor; @@ -485,6 +493,19 @@ static float calculateMultirotorTPAFactor(uint16_t throttle) return tpaFactor; } +static float calculateTPAThtrottle(void) +{ + uint16_t tpaThrottle = 0; + + if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { //fixed wing TPA with filtering + tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, rcCommand[THROTTLE]); + } + else { + tpaThrottle = rcCommand[THROTTLE]; //multirotor TPA without filtering + } + return tpaThrottle; +} + void schedulePidGainsUpdate(void) { pidGainsUpdateRequired = true; @@ -492,26 +513,7 @@ void schedulePidGainsUpdate(void) void updatePIDCoefficients(void) { - STATIC_FASTRAM uint16_t prevThrottle = 0; - STATIC_FASTRAM uint16_t tpaThrottle = 0; - - if (usedPidControllerType == PID_TYPE_PIFF && pitotValidForAirspeed() && currentControlRateProfile->throttle.airspeed_tpa) { - // Use airspeed instead of throttle for TPA calculation - const float airspeed = getAirspeedEstimate(); // in cm/s - const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s - tpaThrottle = currentControlRateProfile->throttle.pa_breakpoint + (uint16_t)((airspeed - referenceAirspeed) / referenceAirspeed * (currentControlRateProfile->throttle.pa_breakpoint - getThrottleIdleValue())); - tpaThrottle = constrain(tpaThrottle, getThrottleIdleValue(), tpaThrottle); - } - else if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { - tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, rcCommand[THROTTLE]); - } - else { - tpaThrottle = rcCommand[THROTTLE]; - } - if (tpaThrottle != prevThrottle) { - prevThrottle = tpaThrottle; - pidGainsUpdateRequired = true; - } + STATIC_FASTRAM float tpaFactorprev=1.0f; #ifdef USE_ANTIGRAVITY if (usedPidControllerType == PID_TYPE_PID) { @@ -526,13 +528,29 @@ void updatePIDCoefficients(void) for (int axis = 0; axis < 3; axis++) { pidState[axis].stickPosition = constrain(rxGetChannelValue(axis) - PWM_RANGE_MIDDLE, -500, 500) / 500.0f; } + + float tpaFactor=1.0f; + if(usedPidControllerType == PID_TYPE_PIFF){ // Fixed wing TPA calculation + if(currentControlRateProfile->throttle.airspeed_tpa_pow>0){ + tpaFactor = calculateFixedWingAirspeedTPAFactor(); + }else{ + tpaFactor = calculateFixedWingTPAFactor(calculateTPAThtrottle()); + } + } else { + tpaFactor = calculateMultirotorTPAFactor(calculateTPAThtrottle()); + } + if (tpaFactor != tpaFactorprev) { + pidGainsUpdateRequired = true; + } + tpaFactorprev = tpaFactor; + // If nothing changed - don't waste time recalculating coefficients if (!pidGainsUpdateRequired) { return; } - const float tpaFactor = usedPidControllerType == PID_TYPE_PIFF ? calculateFixedWingTPAFactor(prevThrottle) : calculateMultirotorTPAFactor(prevThrottle); + // PID coefficients can be update only with THROTTLE and TPA or inflight PID adjustments //TODO: Next step would be to update those only at THROTTLE or inflight adjustments change for (int axis = 0; axis < 3; axis++) { From 4c44d5f01227a810e8a9873b9024d06210915c2d Mon Sep 17 00:00:00 2001 From: shota Date: Thu, 6 Nov 2025 12:02:22 +0900 Subject: [PATCH 06/67] Initialize pidGainsUpdateRequired to true for proper PID gain updates --- src/main/flight/pid.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 9b85d413e69..a35b5add72a 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -126,7 +126,7 @@ static EXTENDED_FASTRAM pt1Filter_t headingHoldRateFilter; static EXTENDED_FASTRAM pt1Filter_t fixedWingTpaFilter; // Thrust PID Attenuation factor. 0.0f means fully attenuated, 1.0f no attenuation is applied -STATIC_FASTRAM bool pidGainsUpdateRequired; +STATIC_FASTRAM bool pidGainsUpdateRequired= true; FASTRAM int16_t axisPID[FLIGHT_DYNAMICS_INDEX_COUNT]; #ifdef USE_BLACKBOX @@ -513,7 +513,7 @@ void schedulePidGainsUpdate(void) void updatePIDCoefficients(void) { - STATIC_FASTRAM float tpaFactorprev=1.0f; + STATIC_FASTRAM float tpaFactorprev=-1.0f; #ifdef USE_ANTIGRAVITY if (usedPidControllerType == PID_TYPE_PID) { From 960336143959958364cbf44586d0f17f5509a1cd Mon Sep 17 00:00:00 2001 From: shota Date: Thu, 6 Nov 2025 12:13:59 +0900 Subject: [PATCH 07/67] raise pitot_lpf_milli_hz --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- src/main/flight/pid.c | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index aea055fb937..193cc38485a 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -5578,7 +5578,7 @@ Pitot tube lowpass filter cutoff frequency. Lower cutoff frequencies result in s | Default | Min | Max | | --- | --- | --- | -| 350 | 0 | 10000 | +| 1000 | 0 | 10000 | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 1b14b82d580..d5a80e745d3 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -656,7 +656,7 @@ groups: description: "Pitot tube lowpass filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay" min: 0 max: 10000 - default_value: 350 + default_value: 1000 - name: pitot_scale description: "Pitot tube scale factor" min: 0 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index a35b5add72a..14a78ea7842 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -531,7 +531,7 @@ void updatePIDCoefficients(void) float tpaFactor=1.0f; if(usedPidControllerType == PID_TYPE_PIFF){ // Fixed wing TPA calculation - if(currentControlRateProfile->throttle.airspeed_tpa_pow>0){ + if(currentControlRateProfile->throttle.airspeed_tpa_pow>0 && pitotValidForAirspeed()){ tpaFactor = calculateFixedWingAirspeedTPAFactor(); }else{ tpaFactor = calculateFixedWingTPAFactor(calculateTPAThtrottle()); From 00c9db0f46d4c0bc28a750007d9a2b060e0bcf02 Mon Sep 17 00:00:00 2001 From: shota hayashi Date: Mon, 17 Nov 2025 02:15:19 +0900 Subject: [PATCH 08/67] enhance tpa with pitch angle aware --- docs/Settings.md | 22 +++++++++---------- src/main/fc/controlrate_profile.c | 2 +- .../fc/controlrate_profile_config_struct.h | 2 +- src/main/fc/settings.yaml | 8 +++---- src/main/flight/pid.c | 11 +++++++--- 5 files changed, 25 insertions(+), 20 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 193cc38485a..7cc99c94e7a 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -302,16 +302,6 @@ ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't hav --- -### airspeed_tpa_pow - -Use airspeed instead of throttle position for TPA if airspeed is available on fixedwing. pid_multiplier(tpa_factor) = (referenceAirspeed/airspeed)**(airspeed_tpa_pow/100). Set to 0 will disable this feature and use throttle based tpa; - -| Default | Min | Max | -| --- | --- | --- | -| 120 | 0 | 200 | - ---- - ### align_board_pitch Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc @@ -432,6 +422,16 @@ Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allo --- +### apa_pow + +Use airspeed instead of throttle position for PID attenuation if airspeed is available on fixedwing. pid_multiplier = (referenceAirspeed/airspeed)**(apa_pow/100). Set to 0 will disable this feature and use throttle based PID attenuation; + +| Default | Min | Max | +| --- | --- | --- | +| 120 | 0 | 200 | + +--- + ### applied_defaults Internal (configurator) hint. Should not be changed manually @@ -6394,7 +6394,7 @@ Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should b ### tpa_rate -Throttle PID attenuation reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. +Throttle based PID attenuation(TPA) reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/controlrate_profile.c b/src/main/fc/controlrate_profile.c index 1c2d632d9ce..a7794e47eed 100644 --- a/src/main/fc/controlrate_profile.c +++ b/src/main/fc/controlrate_profile.c @@ -47,7 +47,7 @@ void pgResetFn_controlRateProfiles(controlRateConfig_t *instance) .dynPID_on_YAW = SETTING_TPA_ON_YAW_DEFAULT, .pa_breakpoint = SETTING_TPA_BREAKPOINT_DEFAULT, .fixedWingTauMs = SETTING_FW_TPA_TIME_CONSTANT_DEFAULT, - .airspeed_tpa_pow = SETTING_AIRSPEED_TPA_POW_DEFAULT, + .apa_pow = SETTING_APA_POW_DEFAULT, }, .stabilized = { diff --git a/src/main/fc/controlrate_profile_config_struct.h b/src/main/fc/controlrate_profile_config_struct.h index 8c4e57b7f1f..2ac4aa421ee 100644 --- a/src/main/fc/controlrate_profile_config_struct.h +++ b/src/main/fc/controlrate_profile_config_struct.h @@ -32,7 +32,7 @@ typedef struct controlRateConfig_s { bool dynPID_on_YAW; uint16_t pa_breakpoint; // Breakpoint where TPA is activated uint16_t fixedWingTauMs; // Time constant of airplane TPA PT1-filter - uint16_t airspeed_tpa_pow; // Use airspeed instead of throttle position for TPA calculation,0 to disable + uint16_t apa_pow; // Use airspeed instead of throttle position for TPA calculation,0 to disable } throttle; struct { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index d5a80e745d3..7ff9c3b7a6e 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1337,15 +1337,15 @@ groups: field: throttle.rcExpo8 min: 0 max: 100 - - name: airspeed_tpa_pow - description: "Use airspeed instead of throttle position for TPA if airspeed is available on fixedwing. pid_multiplier(tpa_factor) = (referenceAirspeed/airspeed)**(airspeed_tpa_pow/100). Set to 0 will disable this feature and use throttle based tpa;" + - name: apa_pow + description: "Use airspeed instead of throttle position for PID attenuation if airspeed is available on fixedwing. pid_multiplier = (referenceAirspeed/airspeed)**(apa_pow/100). Set to 0 will disable this feature and use throttle based PID attenuation;" type: uint16_t - field: throttle.airspeed_tpa_pow + field: throttle.apa_pow default_value: 120 min: 0 max: 200 - name: tpa_rate - description: "Throttle PID attenuation reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate." + description: "Throttle based PID attenuation(TPA) reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate." default_value: 0 field: throttle.dynPID min: 0 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 14a78ea7842..061646840b4 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -444,7 +444,7 @@ float pidRcCommandToRate(int16_t stick, uint8_t rate) static float calculateFixedWingAirspeedTPAFactor(void){ const float airspeed = getAirspeedEstimate(); // in cm/s const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s - float tpaFactor= powf(referenceAirspeed/(airspeed+0.01f), currentControlRateProfile->throttle.airspeed_tpa_pow/100.0f); + float tpaFactor= powf(referenceAirspeed/(airspeed+0.01f), currentControlRateProfile->throttle.apa_pow/100.0f); tpaFactor= constrainf(tpaFactor, 0.3f, 2.0f); return tpaFactor; } @@ -496,9 +496,14 @@ static float calculateMultirotorTPAFactor(uint16_t throttle) static float calculateTPAThtrottle(void) { uint16_t tpaThrottle = 0; + static const fpVector3_t vDown = { .v = { 0.0f, 0.0f, 1.0f } }; if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { //fixed wing TPA with filtering - tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, rcCommand[THROTTLE]); + fpVector3_t vForward = { .v = { HeadVecEFFiltered.x, -HeadVecEFFiltered.y, -HeadVecEFFiltered.z } }; + float groundCos = vectorDotProduct(&vForward, &vDown); + int16_t throttleAdjustment = currentBatteryProfile->nav.fw.pitch_to_throttle * groundCos * 90.0f; // 90 degrees is to scale from cos to throttle adjustment + uint16_t throttleAdjusted = rcCommand[THROTTLE] + constrain(throttleAdjustment, -1000, 1000); + tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, constrain(throttleAdjusted, 1000, 2000)); } else { tpaThrottle = rcCommand[THROTTLE]; //multirotor TPA without filtering @@ -531,7 +536,7 @@ void updatePIDCoefficients(void) float tpaFactor=1.0f; if(usedPidControllerType == PID_TYPE_PIFF){ // Fixed wing TPA calculation - if(currentControlRateProfile->throttle.airspeed_tpa_pow>0 && pitotValidForAirspeed()){ + if(currentControlRateProfile->throttle.apa_pow>0 && pitotValidForAirspeed()){ tpaFactor = calculateFixedWingAirspeedTPAFactor(); }else{ tpaFactor = calculateFixedWingTPAFactor(calculateTPAThtrottle()); From 95a979574e39a53843c91180b5c0c3f91f4b789a Mon Sep 17 00:00:00 2001 From: functionpointer Date: Sun, 23 Nov 2025 00:38:26 +0100 Subject: [PATCH 09/67] VANTAC_RF007: Fix UART3/I2C2 resource conflict on port C --- src/main/target/VANTAC_RF007/target.h | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/target/VANTAC_RF007/target.h b/src/main/target/VANTAC_RF007/target.h index 3f54ef4cf37..0fc8bd0e495 100644 --- a/src/main/target/VANTAC_RF007/target.h +++ b/src/main/target/VANTAC_RF007/target.h @@ -52,6 +52,7 @@ #define I2C2_SCL PB10 #define I2C2_SDA PB11 #define EXTERNAL_I2C BUS_I2C2 +#define I2C_DEVICE_2_SHARES_UART3 #define USE_BARO #define BARO_I2C_BUS BUS_I2C1 From 0c52ff00675a7309349764d8ca27a1dd103e32a5 Mon Sep 17 00:00:00 2001 From: functionpointer Date: Sun, 23 Nov 2025 14:40:29 +0100 Subject: [PATCH 10/67] VANTAC_RF007: USE_DSHOT_DMAR, modify defaults Apparently DSHOT_DMAR can only work with max 4 timers. With the previous timer setup this caused a limit of 7 motors. The new setup increases it 9. However, it costs some flexibility. The new default config sets up TIM1 as MOTOR by default, creating sane defaults for platforms with 1 or 4 motors. --- src/main/target/VANTAC_RF007/config.c | 6 +++++- src/main/target/VANTAC_RF007/target.c | 4 ++-- src/main/target/VANTAC_RF007/target.h | 3 +++ 3 files changed, 10 insertions(+), 3 deletions(-) diff --git a/src/main/target/VANTAC_RF007/config.c b/src/main/target/VANTAC_RF007/config.c index c3c3f3d6295..44c85b8074a 100644 --- a/src/main/target/VANTAC_RF007/config.c +++ b/src/main/target/VANTAC_RF007/config.c @@ -22,7 +22,11 @@ * along with this program. If not, see http://www.gnu.org/licenses/. */ +#include +#include "drivers/pwm_mapping.h" + void targetConfiguration(void) { - + // default "ESC" pin to be a motor + timerOverridesMutable(timer2id(TIM1))->outputMode = OUTPUT_MODE_MOTORS; } diff --git a/src/main/target/VANTAC_RF007/target.c b/src/main/target/VANTAC_RF007/target.c index 3589a56c224..799dc762322 100644 --- a/src/main/target/VANTAC_RF007/target.c +++ b/src/main/target/VANTAC_RF007/target.c @@ -33,8 +33,8 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH2, PA9, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "ESC" - DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "RPM", clashes with UART2 TX - DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "TLM", clashes with UART2 RX + DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "RPM", clashes with UART2 TX + DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "TLM", clashes with UART2 RX DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "AUX", clashes with UART1 TX and I2C1 SCL DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // labelled "SBUS", clashes with UART1 RX and I2C1 SDA diff --git a/src/main/target/VANTAC_RF007/target.h b/src/main/target/VANTAC_RF007/target.h index 0fc8bd0e495..59188a44142 100644 --- a/src/main/target/VANTAC_RF007/target.h +++ b/src/main/target/VANTAC_RF007/target.h @@ -142,3 +142,6 @@ #define USE_SERIALSHOT #define USE_ESC_SENSOR #define USE_SMARTPORT_MASTER // no internal current sensor, enable SMARTPORT_MASTER so external ones can be used + +#define USE_DSHOT_DMAR + From 7390501c15e1154ad6235ba1bf583dd7d8f4243e Mon Sep 17 00:00:00 2001 From: frogmane <7685285+xznhj8129@users.noreply.github.com> Date: Sat, 29 Nov 2025 11:14:03 -0500 Subject: [PATCH 11/67] added msp set gvar --- docs/development/msp/inav_enums_ref.md | 7 ++++--- docs/development/msp/msp_messages.checksum | 2 +- docs/development/msp/msp_messages.json | 23 ++++++++++++++++++++++ docs/development/msp/msp_ref.md | 17 +++++++++++++++- docs/development/msp/rev | 2 +- src/main/fc/fc_msp.c | 17 ++++++++++++++++ src/main/msp/msp_protocol_v2_inav.h | 3 ++- 7 files changed, 64 insertions(+), 7 deletions(-) diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md index 9a4c64e6e39..2d60f270183 100644 --- a/docs/development/msp/inav_enums_ref.md +++ b/docs/development/msp/inav_enums_ref.md @@ -1385,7 +1385,7 @@ | `DEVHW_MS4525` | 49 | | | `DEVHW_DLVR` | 50 | | | `DEVHW_M25P16` | 51 | | -| `DEVHW_W25N01G` | 52 | | +| `DEVHW_W25N` | 52 | | | `DEVHW_UG2864` | 53 | | | `DEVHW_SDCARD` | 54 | | | `DEVHW_IRLOCK` | 55 | | @@ -2843,6 +2843,7 @@ | `LOGIC_CONDITION_OPERAND_FLIGHT_MIN_GROUND_SPEED` | 46 | | | `LOGIC_CONDITION_OPERAND_FLIGHT_HORIZONTAL_WIND_SPEED` | 47 | | | `LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION` | 48 | | +| `LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET` | 49 | | --- ## `logicOperation_e` @@ -4740,7 +4741,7 @@ --- ## `sdcardReceiveBlockStatus_e` -> Source: ../../../src/main/drivers/sdcard/sdcard_spi.c +> Source: ../../../src/main/drivers/sdcard/sdcard_sdio.c | Enumerator | Value | Condition | |---|---:|---| @@ -4751,7 +4752,7 @@ --- ## `sdcardReceiveBlockStatus_e` -> Source: ../../../src/main/drivers/sdcard/sdcard_sdio.c +> Source: ../../../src/main/drivers/sdcard/sdcard_spi.c | Enumerator | Value | Condition | |---|---:|---| diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum index 3c235d8aaf9..98dc134e990 100644 --- a/docs/development/msp/msp_messages.checksum +++ b/docs/development/msp/msp_messages.checksum @@ -1 +1 @@ -ca27e198f4405b721ad8a15719e15e5d +7db80f38dda2265704e7852630a02a83 diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json index dde6d3ecef5..db8dbe22833 100644 --- a/docs/development/msp/msp_messages.json +++ b/docs/development/msp/msp_messages.json @@ -10829,6 +10829,29 @@ "notes": "Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).", "description": "Sets a specific vertex (or center+radius for circular zones) for a Geozone." }, + "MSP2_INAV_SET_GVAR": { + "code": 8724, + "mspv": 2, + "request": { + "payload": [ + { + "name": "gvarIndex", + "ctype": "uint8_t", + "desc": "Index of the Global Variable to set", + "units": "Index" + }, + { + "name": "value", + "ctype": "int32_t", + "desc": "New value to store (clamped to configured min/max by `gvSet()`)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 5 bytes. Returns error if index is outside `MAX_GLOBAL_VARIABLES`.", + "description": "Sets the specified Global Variable (GVAR) to the provided value." + }, "MSP2_INAV_FULL_LOCAL_POSE": { "code": 8736, "mspv": 2, diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md index 97851bcec1f..5a413a1506c 100644 --- a/docs/development/msp/msp_ref.md +++ b/docs/development/msp/msp_ref.md @@ -10,7 +10,8 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i For current generation code, see [documentation project](https://github.com/xznhj8129/msp_documentation) (temporary until official implementation) -**JSON file rev: 2** +**JSON file rev: 3 +** **Warning: Verification needed, exercise caution until completely verified for accuracy and cleared, especially for integer signs. Source-based generation/validation is forthcoming. Refer to source for absolute certainty** @@ -411,6 +412,7 @@ For current generation code, see [documentation project](https://github.com/xznh [8721 - MSP2_INAV_SET_GEOZONE](#msp2_inav_set_geozone) [8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex) [8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex) +[8724 - MSP2_INAV_SET_GVAR](#msp2_inav_set_gvar) [8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose) [12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind) @@ -4492,6 +4494,19 @@ For current generation code, see [documentation project](https://github.com/xznh **Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude). +## `MSP2_INAV_SET_GVAR (8724 / 0x2214)` +**Description:** Sets the specified Global Variable (GVAR) to the provided value. + +**Request Payload:** +|Field|C Type|Size (Bytes)|Units|Description| +|---|---|---|---|---| +| `gvarIndex` | `uint8_t` | 1 | Index | Index of the Global Variable to set | +| `value` | `int32_t` | 4 | - | New value to store (clamped to configured min/max by `gvSet()`) | + +**Reply Payload:** **None** + +**Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 5 bytes. Returns error if index is outside `MAX_GLOBAL_VARIABLES`. + ## `MSP2_INAV_FULL_LOCAL_POSE (8736 / 0x2220)` **Description:** Provides estimates of current attitude, local NEU position, and velocity. diff --git a/docs/development/msp/rev b/docs/development/msp/rev index d8263ee9860..00750edc07d 100644 --- a/docs/development/msp/rev +++ b/docs/development/msp/rev @@ -1 +1 @@ -2 \ No newline at end of file +3 diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 54c225c78bc..936c708030d 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -2340,6 +2340,23 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } else return MSP_RESULT_ERROR; break; + + case MSP2_INAV_SET_GVAR: + if (dataSize != 5) { + return MSP_RESULT_ERROR; + } + { + uint8_t gvarIndex; + if (!sbufReadU8Safe(&gvarIndex, src)) { + return MSP_RESULT_ERROR; + } + const int32_t gvarValue = (int32_t)sbufReadU32(src); + if (gvarIndex >= MAX_GLOBAL_VARIABLES) { + return MSP_RESULT_ERROR; + } + gvSet(gvarIndex, gvarValue); + } + break; #endif case MSP2_COMMON_SET_MOTOR_MIXER: sbufReadU8Safe(&tmp_u8, src); diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index b44aa539887..696d426cd78 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -122,5 +122,6 @@ #define MSP2_INAV_SET_GEOZONE 0x2211 #define MSP2_INAV_GEOZONE_VERTEX 0x2212 #define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213 +#define MSP2_INAV_SET_GVAR 0x2214 -#define MSP2_INAV_FULL_LOCAL_POSE 0x2220 \ No newline at end of file +#define MSP2_INAV_FULL_LOCAL_POSE 0x2220 From e672d23fa3abff61e78f5b72b4a3b050084cba61 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 30 Nov 2025 02:13:30 -0600 Subject: [PATCH 12/67] Add GitHub Action to suggest maintenance branches for PRs targeting master --- .github/workflows/pr-branch-suggestion.yml | 37 ++++++++++++++++++++++ 1 file changed, 37 insertions(+) create mode 100644 .github/workflows/pr-branch-suggestion.yml diff --git a/.github/workflows/pr-branch-suggestion.yml b/.github/workflows/pr-branch-suggestion.yml new file mode 100644 index 00000000000..aea758f5a00 --- /dev/null +++ b/.github/workflows/pr-branch-suggestion.yml @@ -0,0 +1,37 @@ +name: PR Branch Suggestion + +on: + pull_request: + types: [opened] + branches: + - master + +jobs: + suggest-branch: + runs-on: ubuntu-latest + permissions: + pull-requests: write + steps: + - name: Suggest maintenance branch + uses: actions/github-script@v7 + with: + script: | + const comment = `### Branch Targeting Suggestion + + You've targeted the \`master\` branch with this PR. Please consider if a version branch might be more appropriate: + + - **\`maintenance-9.x\`** - If your change is backward-compatible and won't create compatibility issues between INAV firmware and Configurator 9.x versions. This will allow your PR to be included in the next 9.x release. + + - **\`maintenance-10.x\`** - If your change introduces compatibility requirements between firmware and configurator that would break 9.x compatibility. This is for PRs which will be included in INAV 10.x + + If \`master\` is the correct target for this change, no action is needed. + + --- + *This is an automated suggestion to help route contributions to the appropriate branch.*`; + + github.rest.issues.createComment({ + issue_number: context.issue.number, + owner: context.repo.owner, + repo: context.repo.repo, + body: comment + }); From 15fc53ae6aeb68d543ccff4a23b7635434eba7ee Mon Sep 17 00:00:00 2001 From: Sensei Date: Sun, 30 Nov 2025 02:18:42 -0600 Subject: [PATCH 13/67] Update .github/workflows/pr-branch-suggestion.yml Co-authored-by: qodo-merge-pro[bot] <151058649+qodo-merge-pro[bot]@users.noreply.github.com> --- .github/workflows/pr-branch-suggestion.yml | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/.github/workflows/pr-branch-suggestion.yml b/.github/workflows/pr-branch-suggestion.yml index aea758f5a00..ab233969451 100644 --- a/.github/workflows/pr-branch-suggestion.yml +++ b/.github/workflows/pr-branch-suggestion.yml @@ -29,9 +29,13 @@ jobs: --- *This is an automated suggestion to help route contributions to the appropriate branch.*`; - github.rest.issues.createComment({ - issue_number: context.issue.number, - owner: context.repo.owner, - repo: context.repo.repo, - body: comment - }); + try { + await github.rest.issues.createComment({ + issue_number: context.issue.number, + owner: context.repo.owner, + repo: context.repo.repo, + body: comment + }); + } catch (err) { + core.setFailed(`Failed to post suggestion comment: ${err}`); + } From 82021b5e8358826775a71069ffb2885c1dc2a8ed Mon Sep 17 00:00:00 2001 From: Sensei Date: Sun, 30 Nov 2025 02:32:27 -0600 Subject: [PATCH 14/67] Github action change pull_request to pull_request_target event --- .github/workflows/pr-branch-suggestion.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pr-branch-suggestion.yml b/.github/workflows/pr-branch-suggestion.yml index ab233969451..110deb98338 100644 --- a/.github/workflows/pr-branch-suggestion.yml +++ b/.github/workflows/pr-branch-suggestion.yml @@ -1,7 +1,7 @@ name: PR Branch Suggestion on: - pull_request: + pull_request_target: types: [opened] branches: - master From 557c35db416b0ee347c2d206d73373cbb2d0a6c3 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 30 Nov 2025 02:53:55 -0600 Subject: [PATCH 15/67] Add release creation guide to developer documentation --- docs/development/release-create.md | 333 +++++++++++++++++++++++++++++ 1 file changed, 333 insertions(+) create mode 100644 docs/development/release-create.md diff --git a/docs/development/release-create.md b/docs/development/release-create.md new file mode 100644 index 00000000000..3e0391411ce --- /dev/null +++ b/docs/development/release-create.md @@ -0,0 +1,333 @@ +# Creating INAV Releases + +This document describes the process for creating INAV firmware and configurator releases. + +> **Note:** This document is designed to be used with coding assistants (such as Claude Code) that can execute the commands and automate parts of the release process. Update this document with lessons learned after each release. + +## Overview + +INAV releases include both firmware (for flight controllers) and the configurator application (for configuration). Both repositories must be tagged with matching version numbers. + +**Repositories:** +- Firmware: https://github.com/iNavFlight/inav +- Configurator: https://github.com/iNavFlight/inav-configurator + +## Version Numbering + +INAV uses semantic versioning: `MAJOR.MINOR.PATCH` + +- **MAJOR:** Breaking changes, major new features +- **MINOR:** New features, significant improvements +- **PATCH:** Bug fixes, minor improvements + +Version numbers are set in: +- Firmware: `CMakeLists.txt` (line ~54): `project(INAV VERSION X.Y.Z)` +- Configurator: `package.json`: `"version": "X.Y.Z"` + +## Pre-Release Checklist + +### Code Readiness + +- [ ] All planned PRs merged +- [ ] CI passing on master branch +- [ ] No critical open issues blocking release +- [ ] Version numbers updated in both repositories +- [ ] SITL binaries updated in configurator + +### Documentation + +- [ ] Release notes drafted +- [ ] Breaking changes documented +- [ ] New features documented + +## Release Workflow + +``` +1. Verify release readiness + ā”œā”€ā”€ All PRs merged + ā”œā”€ā”€ CI passing + └── Version numbers updated + +2. Update SITL binaries in Configurator + ā”œā”€ā”€ Download from nightly or build for each platform + └── Commit updated binaries to configurator repo + +3. Create tags + ā”œā”€ā”€ inav: git tag + └── inav-configurator: git tag + +4. Generate changelog + ā”œā”€ā”€ List PRs since last tag + ā”œā”€ā”€ Categorize changes + └── Format release notes + +5. Download/build artifacts + ā”œā”€ā”€ Firmware: from nightly builds + └── Configurator: from CI artifacts + +6. Create draft releases + ā”œā”€ā”€ Upload firmware artifacts + ā”œā”€ā”€ Upload configurator artifacts + └── Add release notes + +7. Review and publish + ā”œā”€ā”€ Maintainer review + └── Publish releases +``` + +## Updating SITL Binaries + +SITL binaries must be updated before tagging the configurator. They are stored in: +``` +inav-configurator/resources/public/sitl/ +ā”œā”€ā”€ linux/ +│ ā”œā”€ā”€ inav_SITL +│ └── arm64/inav_SITL +ā”œā”€ā”€ macos/ +│ └── inav_SITL +└── windows/ + ā”œā”€ā”€ inav_SITL.exe + └── cygwin1.dll +``` + +### Download from Nightly + +```bash +# Find matching nightly release +gh release list --repo iNavFlight/inav-nightly --limit 5 + +# Download SITL resources +curl -L -o /tmp/sitl-resources.zip \ + "https://github.com/iNavFlight/inav-nightly/releases/download//sitl-resources.zip" +unzip /tmp/sitl-resources.zip -d /tmp/sitl-extract + +# Copy to configurator +cd inav-configurator +cp /tmp/sitl-extract/resources/sitl/linux/inav_SITL resources/public/sitl/linux/ +cp /tmp/sitl-extract/resources/sitl/linux/arm64/inav_SITL resources/public/sitl/linux/arm64/ +cp /tmp/sitl-extract/resources/sitl/macos/inav_SITL resources/public/sitl/macos/ +cp /tmp/sitl-extract/resources/sitl/windows/inav_SITL.exe resources/public/sitl/windows/ + +# Commit +git add resources/public/sitl/ +git commit -m "Update SITL binaries for " +``` + +## Tagging + +### Check Latest Tags + +```bash +# Firmware +cd inav +git fetch --tags +git tag --sort=-v:refname | head -10 + +# Configurator +cd inav-configurator +git fetch --tags +git tag --sort=-v:refname | head -10 +``` + +### Create New Tags + +```bash +# Firmware +cd inav +git checkout master && git pull +git tag -a -m "INAV " +git push origin + +# Configurator +cd inav-configurator +git checkout master && git pull +git tag -a -m "INAV Configurator " +git push origin +``` + +## Changelog Generation + +### List PRs Since Last Tag + +```bash +cd inav +LAST_TAG=$(git describe --tags --abbrev=0) +gh pr list --state merged --search "merged:>=$(git log -1 --format=%ai $LAST_TAG | cut -d' ' -f1)" --limit 100 +``` + +### Using git log + +```bash +LAST_TAG=$(git describe --tags --abbrev=0) +git log $LAST_TAG..HEAD --oneline --merges +``` + +### Changelog Format + +```markdown +## INAV Release Notes + +### Firmware Changes + +#### New Features +- PR #1234: Description (@contributor) + +#### Bug Fixes +- PR #1236: Description (@contributor) + +#### Improvements +- PR #1237: Description (@contributor) + +### Configurator Changes + +#### New Features +- PR #100: Description (@contributor) + +### Full Changelog +**Firmware:** https://github.com/iNavFlight/inav/compare/... +**Configurator:** https://github.com/iNavFlight/inav-configurator/compare/... +``` + +## Downloading Release Artifacts + +### Firmware Hex Files + +Firmware is available from the nightly build system: + +```bash +# List recent nightlies +gh release list --repo iNavFlight/inav-nightly --limit 5 + +# Download hex files +gh release download --repo iNavFlight/inav-nightly --pattern "*.hex" +``` + +#### Renaming Firmware Files + +Remove CI suffix and add RC number for RC releases: + +```bash +RC_NUM="RC2" # Empty for final releases + +for f in *.hex; do + target=$(echo "$f" | sed -E 's/inav_[0-9]+\.[0-9]+\.[0-9]+_(.*)_ci-.*/\1/') + version=$(echo "$f" | sed -E 's/inav_([0-9]+\.[0-9]+\.[0-9]+)_.*/\1/') + if [ -n "$RC_NUM" ]; then + mv "$f" "inav_${version}_${RC_NUM}_${target}.hex" + else + mv "$f" "inav_${version}_${target}.hex" + fi +done +``` + +### Configurator Builds + +Download from GitHub Actions CI: + +```bash +# List recent workflow runs +gh run list --repo iNavFlight/inav-configurator --limit 10 + +# Download artifacts +gh run download --repo iNavFlight/inav-configurator + +# Flatten directory structure +find . -mindepth 2 -type f -exec mv {} . \; +rm -rf */ +``` + +## Creating GitHub Releases + +### Create Draft Release + +```bash +# Firmware +cd inav +gh release create --draft --title "INAV " --notes-file release-notes.md +gh release upload *.hex + +# Configurator +cd inav-configurator +gh release create --draft --title "INAV Configurator " --notes-file release-notes.md +gh release upload *.zip *.dmg *.exe *.AppImage *.deb *.rpm *.msi +``` + +### Managing Release Assets + +#### Rename Assets via API + +```bash +# Get release and asset IDs +gh api repos/iNavFlight/inav/releases --jq '.[] | select(.draft == true) | {id: .id, name: .name}' +gh api repos/iNavFlight/inav/releases/RELEASE_ID/assets --paginate --jq '.[] | "\(.id) \(.name)"' + +# Rename an asset +gh api -X PATCH "repos/iNavFlight/inav/releases/assets/ASSET_ID" -f name="new-filename.hex" +``` + +#### Delete Outdated Assets from Draft Release + +If a draft release has outdated assets that need to be replaced (e.g., from a previous upload attempt), delete them before uploading new ones: + +```bash +gh api -X DELETE "repos/iNavFlight/inav/releases/assets/ASSET_ID" +``` + +### Publish Release + +```bash +gh release edit --draft=false +``` + +## Asset Naming Conventions + +**Firmware (RC releases):** `inav__RC_.hex` +**Firmware (final):** `inav__.hex` + +**Configurator (RC releases):** `INAV-Configurator___RC.` +**Configurator (final):** `INAV-Configurator__.` + +## Maintenance Branches + +When releasing a new major version, create maintenance branches: + +- **maintenance-X.x** - For bugfixes to version X +- **maintenance-(X+1).x** - For breaking changes targeting the next major version + +### Creating Maintenance Branches + +```bash +COMMIT_SHA="" + +# inav +gh api repos/iNavFlight/inav/git/refs -f ref="refs/heads/maintenance-9.x" -f sha="$COMMIT_SHA" + +# inav-configurator +gh api repos/iNavFlight/inav-configurator/git/refs -f ref="refs/heads/maintenance-9.x" -f sha="$COMMIT_SHA" +``` + +### Branch Usage + +- **X.x bugfixes** → PR to maintenance-X.x +- **Breaking changes** → PR to maintenance-(X+1).x +- **Non-breaking features** → PR to master + +Lower version branches are periodically merged into higher version branches (e.g., maintenance-9.x → maintenance-10.x → master). + +## Hotfix Releases + +For critical bugs discovered after release: + +1. Create hotfix branch from release tag +2. Cherry-pick or create fix +3. Tag as `X.Y.Z+1` (patch increment) +4. Build and release following normal process +5. Document as hotfix in release notes + +## Post-Release Tasks + +- [ ] Announce release (Discord, forums, etc.) +- [ ] Update any pinned issues +- [ ] Monitor for critical bug reports +- [ ] Prepare hotfix if needed +- [ ] Update this document with any lessons learned From 50736c12f1db03ed9c5341c9c05cc9f9f3eacd27 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Tue, 2 Dec 2025 22:44:31 -0600 Subject: [PATCH 16/67] Fix missing magnetometer support on NEXUSX target The NEXUSX target was missing USE_MAG definition, which caused all magnetometer-related CLI settings to be unavailable. Users received "Invalid name" errors when attempting to configure align_mag_roll, align_mag_pitch, align_mag_yaw, and other compass settings. Changes: - Added USE_MAG to NEXUSX target.h - Configured MAG_I2C_BUS to use I2C3 (same bus as barometer) - Enables external magnetometer support for GPS navigation Hardware compatibility: - NEXUSX has I2C3 available (SCL: PA8, SDA: PC9) - Barometer already on I2C3 (SPL06) Testing: - Built NEXUSX target successfully - Verified settings present in binary via strings command - All compass settings now available in settings table: * align_mag_roll, align_mag_pitch, align_mag_yaw * mag_hardware, mag_declination * magzero_x/y/z, maggain_x/y/z * mag_calibration_time --- src/main/target/NEXUSX/target.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/target/NEXUSX/target.h b/src/main/target/NEXUSX/target.h index def2ada57b0..1de8a5d1fba 100644 --- a/src/main/target/NEXUSX/target.h +++ b/src/main/target/NEXUSX/target.h @@ -57,6 +57,9 @@ #define BARO_I2C_BUS BUS_I2C3 #define USE_BARO_SPL06 +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C3 + #define TEMPERATURE_I2C_BUS DEFAULT_I2C #define PITOT_I2C_BUS DEFAULT_I2C From 0fca2e4b35e437be9bed1c2086d0bf23393af100 Mon Sep 17 00:00:00 2001 From: functionpointer Date: Wed, 3 Dec 2025 12:39:34 +0100 Subject: [PATCH 17/67] VANTAC_RF007: Add MAG support --- src/main/target/VANTAC_RF007/target.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/target/VANTAC_RF007/target.h b/src/main/target/VANTAC_RF007/target.h index 59188a44142..25bd1373171 100644 --- a/src/main/target/VANTAC_RF007/target.h +++ b/src/main/target/VANTAC_RF007/target.h @@ -59,6 +59,10 @@ #define USE_BARO_SPL06 #define SPL06_I2C_ADDR 119 +#define USE_MAG +#define MAG_I2C_BUS EXTERNAL_I2C +#define USE_MAG_ALL + #define TEMPERATURE_I2C_BUS EXTERNAL_I2C #define PITOT_I2C_BUS EXTERNAL_I2C From f28f725445528adb1c9fe57777d1efb143ad523c Mon Sep 17 00:00:00 2001 From: Barnabasek <35784551+Barnabasek@users.noreply.github.com> Date: Wed, 3 Dec 2025 20:53:53 +0100 Subject: [PATCH 18/67] Update LedStrip.md updated link to Oscar Liang's guide --- docs/LedStrip.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/LedStrip.md b/docs/LedStrip.md index cecd630ecc9..262d91b183a 100644 --- a/docs/LedStrip.md +++ b/docs/LedStrip.md @@ -71,7 +71,7 @@ Enable the Led Strip feature via the GUI under setup. Configure the leds from the Led Strip tab in the INAV GUI. First setup how the led's are laid out so that you can visualize it later as you configure and so the flight controller knows how many led's there are available. -There is a step by step guide on how to use the GUI to configure the Led Strip feature using the GUI http://blog.oscarliang.net/setup-rgb-led-cleanflight/ which was published early 2015 by Oscar Liang which may or may not be up-to-date by the time you read this. +There is a step by step guide on how to use the GUI to configure the Led Strip feature using the GUI https://oscarliang.com/setup-led-betaflight/ which was published early 2015 by Oscar Liang which may or may not be up-to-date by the time you read this. CLI: Enable the `LED_STRIP` feature via the cli: @@ -605,4 +605,4 @@ This also means that you can make sure that each R,G and B LED in each LED modul After a short delay the LEDs will show the unarmed color sequence and or low-battery warning sequence. -Also check that the feature `LED_STRIP` was correctly enabled and that it does not conflict with other features, as above. \ No newline at end of file +Also check that the feature `LED_STRIP` was correctly enabled and that it does not conflict with other features, as above. From ad8d8c2ba427d9fb559eb5c4dcf4c3673ee6bdb8 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 6 Dec 2025 12:31:11 -0600 Subject: [PATCH 19/67] Fix NEXUSX magnetometer to use accessible I2C2 bus I2C3 is not physically accessible on NEXUSX hardware. Changed MAG_I2C_BUS from BUS_I2C3 to DEFAULT_I2C (BUS_I2C2). Added USE_MAG_ALL for auto-detection of magnetometer models. --- src/main/target/NEXUSX/target.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/target/NEXUSX/target.h b/src/main/target/NEXUSX/target.h index 1de8a5d1fba..24c035b4cae 100644 --- a/src/main/target/NEXUSX/target.h +++ b/src/main/target/NEXUSX/target.h @@ -58,7 +58,8 @@ #define USE_BARO_SPL06 #define USE_MAG -#define MAG_I2C_BUS BUS_I2C3 +#define MAG_I2C_BUS DEFAULT_I2C +#define USE_MAG_ALL #define TEMPERATURE_I2C_BUS DEFAULT_I2C From 5c3f1be137499d76b9fc13d5d3cb02848f700c36 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 6 Dec 2025 12:45:00 -0600 Subject: [PATCH 20/67] Add support for Puya PY25Q128HA flash chip The Puya PY25Q128HA is a W25Q128-compatible 128Mbit (16MB) SPI NOR flash chip. This PR adds detection support by including its JEDEC ID in the flash configuration table. Changes: - Added PY25Q128HA JEDEC ID (0x856018) to m25p16FlashConfig[] array - Updated Blackbox documentation with PY25Q128HA in supported chips list The chip uses the same SPI command set as other supported flash chips, so no driver modifications are required beyond adding the JEDEC ID for auto-detection during initialization. --- docs/Blackbox.md | 1 + src/main/drivers/flash_m25p16.c | 3 +++ 2 files changed, 4 insertions(+) diff --git a/docs/Blackbox.md b/docs/Blackbox.md index 3d2fb68290d..b4528d8dd23 100644 --- a/docs/Blackbox.md +++ b/docs/Blackbox.md @@ -120,6 +120,7 @@ These chips are also supported: * Winbond W25Q64 - 64 Mbit / 8 MByte * Micron N25Q0128 - 128 Mbit / 16 MByte * Winbond W25Q128 - 128 Mbit / 16 MByte +* Puya PY25Q128HA - 128 Mbit / 16 MByte * Winbond W25N01 - 1 Gbit / 128 MByte * Winbond W25N02 - 2 Gbit / 256 MByte diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index 9842a80995d..2db61a3a166 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -99,6 +99,9 @@ struct { // Winbond W25Q128_DTR // Datasheet: https://www.winbond.com/resource-files/w25q128jv%20dtr%20revb%2011042016.pdf {0xEF7018, 256, 256}, + // Puya PY25Q128HA + // Datasheet: https://www.puyasemi.com/cpzx3/info_271_itemid_87.html + {0x856018, 256, 256}, // Winbond W25Q256 // Datasheet: https://www.winbond.com/resource-files/w25q256jv%20spi%20revb%2009202016.pdf {0xEF4019, 512, 256}, From 29215e0e94b1db2e5285d4e002813414b1a783bd Mon Sep 17 00:00:00 2001 From: Sensei Date: Sat, 6 Dec 2025 13:01:20 -0600 Subject: [PATCH 21/67] Update docs/development/release-create.md Co-authored-by: qodo-code-review[bot] <151058649+qodo-code-review[bot]@users.noreply.github.com> --- docs/development/release-create.md | 23 ++++++++++++++--------- 1 file changed, 14 insertions(+), 9 deletions(-) diff --git a/docs/development/release-create.md b/docs/development/release-create.md index 3e0391411ce..39651ae1168 100644 --- a/docs/development/release-create.md +++ b/docs/development/release-create.md @@ -209,15 +209,20 @@ Remove CI suffix and add RC number for RC releases: ```bash RC_NUM="RC2" # Empty for final releases -for f in *.hex; do - target=$(echo "$f" | sed -E 's/inav_[0-9]+\.[0-9]+\.[0-9]+_(.*)_ci-.*/\1/') - version=$(echo "$f" | sed -E 's/inav_([0-9]+\.[0-9]+\.[0-9]+)_.*/\1/') - if [ -n "$RC_NUM" ]; then - mv "$f" "inav_${version}_${RC_NUM}_${target}.hex" - else - mv "$f" "inav_${version}_${target}.hex" - fi -done +# Check if any .hex files exist to avoid errors with the glob +if compgen -G "*.hex" > /dev/null; then + for f in *.hex; do + target=$(echo "$f" | sed -E 's/inav_[0-9]+\.[0-9]+\.[0-9]+_(.*)_ci-.*/\1/') + version=$(echo "$f" | sed -E 's/inav_([0-9]+\.[0-9]+\.[0-9]+)_.*/\1/') + if [ -n "$RC_NUM" ]; then + mv "$f" "inav_${version}_${RC_NUM}_${target}.hex" + else + mv "$f" "inav_${version}_${target}.hex" + fi + done +else + echo "No .hex files found to rename." +fi ``` ### Configurator Builds From 96b9501eb2333ba6918a2d3c3cc76162f781128a Mon Sep 17 00:00:00 2001 From: Sensei Date: Sat, 6 Dec 2025 13:01:36 -0600 Subject: [PATCH 22/67] Update docs/development/release-create.md Co-authored-by: qodo-code-review[bot] <151058649+qodo-code-review[bot]@users.noreply.github.com> --- docs/development/release-create.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/docs/development/release-create.md b/docs/development/release-create.md index 39651ae1168..ef4bc06bbd8 100644 --- a/docs/development/release-create.md +++ b/docs/development/release-create.md @@ -237,8 +237,9 @@ gh run list --repo iNavFlight/inav-configurator --limit 10 gh run download --repo iNavFlight/inav-configurator # Flatten directory structure -find . -mindepth 2 -type f -exec mv {} . \; -rm -rf */ +find . -mindepth 2 -type f -exec mv -t . {} + +# Remove the now-empty subdirectories +find . -mindepth 1 -type d -empty -delete ``` ## Creating GitHub Releases From b8cfd7c941c51f3f91828e80ed049d4429918bb7 Mon Sep 17 00:00:00 2001 From: Sensei Date: Sat, 6 Dec 2025 13:02:07 -0600 Subject: [PATCH 23/67] Update docs/development/release-create.md Co-authored-by: qodo-code-review[bot] <151058649+qodo-code-review[bot]@users.noreply.github.com> --- docs/development/release-create.md | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/docs/development/release-create.md b/docs/development/release-create.md index ef4bc06bbd8..ec362da0911 100644 --- a/docs/development/release-create.md +++ b/docs/development/release-create.md @@ -21,8 +21,14 @@ INAV uses semantic versioning: `MAJOR.MINOR.PATCH` - **PATCH:** Bug fixes, minor improvements Version numbers are set in: -- Firmware: `CMakeLists.txt` (line ~54): `project(INAV VERSION X.Y.Z)` -- Configurator: `package.json`: `"version": "X.Y.Z"` +- Firmware: in `CMakeLists.txt` via `project(INAV VERSION X.Y.Z)` + Verify/update: + - View: `grep -E 'project\\(INAV VERSION' CMakeLists.txt` + - Update: edit `CMakeLists.txt` to set the desired version +- Configurator: in `package.json` field `"version"` + Verify/update: + - View: `jq -r .version package.json` (or `node -p "require('./package.json').version"`) + - Update: `npm version --no-git-tag-version` ## Pre-Release Checklist From 11ca2361d79983dfd1ae1d627c4b591bf20b4ae6 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Mon, 8 Dec 2025 10:42:46 -0600 Subject: [PATCH 24/67] Add MSP2_INAV_LOGIC_CONDITIONS_CONFIGURED command Returns 8-byte bitmask indicating which logic conditions differ from defaults. Enables configurator optimization to reduce MSP requests from 64 to 1+N. --- src/main/fc/fc_msp.c | 23 +++++++++++++++++++++++ src/main/msp/msp_protocol_v2_inav.h | 1 + 2 files changed, 24 insertions(+) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 936c708030d..53daf9f524e 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -564,6 +564,29 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU32(dst, logicConditionGetValue(i)); } break; + case MSP2_INAV_LOGIC_CONDITIONS_CONFIGURED: + { + // Returns 8-byte bitmask where bit N = 1 if logic condition N is configured (non-default) + uint64_t mask = 0; + for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) { + const logicCondition_t *lc = logicConditions(i); + // Check if any field differs from default reset values + bool isConfigured = (lc->enabled != 0) || + (lc->activatorId != -1) || + (lc->operation != 0) || + (lc->operandA.type != LOGIC_CONDITION_OPERAND_TYPE_VALUE) || + (lc->operandA.value != 0) || + (lc->operandB.type != LOGIC_CONDITION_OPERAND_TYPE_VALUE) || + (lc->operandB.value != 0) || + (lc->flags != 0); + if (isConfigured) { + mask |= ((uint64_t)1 << i); + } + } + sbufWriteU32(dst, (uint32_t)(mask & 0xFFFFFFFF)); // Lower 32 bits + sbufWriteU32(dst, (uint32_t)((mask >> 32) & 0xFFFFFFFF)); // Upper 32 bits + } + break; case MSP2_INAV_GVAR_STATUS: for (int i = 0; i < MAX_GLOBAL_VARIABLES; i++) { sbufWriteU32(dst, gvGet(i)); diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 696d426cd78..0b893916895 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -89,6 +89,7 @@ #define MSP2_INAV_MISC2 0x203A #define MSP2_INAV_LOGIC_CONDITIONS_SINGLE 0x203B +#define MSP2_INAV_LOGIC_CONDITIONS_CONFIGURED 0x203C // Returns 8-byte bitmask of non-default logic conditions #define MSP2_INAV_ESC_RPM 0x2040 #define MSP2_INAV_ESC_TELEM 0x2041 From 111894c119d4646c7aa9ffd621c280668e142685 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Tue, 9 Dec 2025 14:14:29 -0600 Subject: [PATCH 25/67] Fix cppcheck critical bugs: integer overflow and buffer overrun Two bugs found by cppcheck static analysis: 1. fc/config.h:66 - Integer overflow in FEATURE_FW_AUTOTRIM - `1 << 31` could cause signed integer overflow (undefined behavior in C) - Fixed by using `1U << 31` for unsigned shift 2. sensors/temperature.c:101 - Buffer overrun in memset - sizeof(array) is already the size in bytes, so should not be multiplied by element size. - Fixed by using just `sizeof(sensorStatus)` --- src/main/fc/config.h | 2 +- src/main/sensors/temperature.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/config.h b/src/main/fc/config.h index 17c8ded8c1e..e3bde5f3eb7 100644 --- a/src/main/fc/config.h +++ b/src/main/fc/config.h @@ -63,7 +63,7 @@ typedef enum { FEATURE_PWM_OUTPUT_ENABLE = 1 << 28, FEATURE_OSD = 1 << 29, FEATURE_FW_LAUNCH = 1 << 30, - FEATURE_FW_AUTOTRIM = 1 << 31, + FEATURE_FW_AUTOTRIM = 1U << 31, } features_e; typedef struct systemConfig_s { diff --git a/src/main/sensors/temperature.c b/src/main/sensors/temperature.c index 3d5c05f179c..fe5e80c792f 100644 --- a/src/main/sensors/temperature.c +++ b/src/main/sensors/temperature.c @@ -98,7 +98,7 @@ static void newSensorCheckAndEnter(uint8_t type, uint64_t addr) void temperatureInit(void) { - memset(sensorStatus, 0, sizeof(sensorStatus) * sizeof(*sensorStatus)); + memset(sensorStatus, 0, sizeof(sensorStatus)); sensorsSet(SENSOR_TEMP); From cdca77e981552fe33dfda064f8a1e41469a53cd7 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Tue, 9 Dec 2025 23:19:57 -0600 Subject: [PATCH 26/67] Fix CRSF buffer overflow and dashboard sizeof bug MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit CRSF buffer overflow (rx/crsf.c): - fullFrameLength computed from untrusted frameLength field - Malformed packet with large frameLength could overflow crsfFrame.bytes[] - Added bounds check against CRSF_FRAME_SIZE_MAX before writing Dashboard sizeof bug (io/dashboard.c): - tickerCharacters was a pointer, so sizeof() returned pointer size (4/8) - On 64-bit systems, TICKER_CHARACTER_COUNT was 8 instead of 4 - Could read past end of string when indexing tickerCharacters[] - Changed to array declaration and sizeof()-1 for correct count šŸ¤– Generated with [Claude Code](https://claude.com/claude-code) Co-Authored-By: Claude --- src/main/io/dashboard.c | 4 ++-- src/main/rx/crsf.c | 5 +++++ 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/src/main/io/dashboard.c b/src/main/io/dashboard.c index 26fde5f2378..18be89d85d1 100644 --- a/src/main/io/dashboard.c +++ b/src/main/io/dashboard.c @@ -172,8 +172,8 @@ static const char* const gpsFixTypeText[] = { "3D" }; -static const char* tickerCharacters = "|/-\\"; // use 2/4/8 characters so that the divide is optimal. -#define TICKER_CHARACTER_COUNT (sizeof(tickerCharacters) / sizeof(char)) +static const char tickerCharacters[] = "|/-\\"; // use 2/4/8 characters so that the divide is optimal. +#define TICKER_CHARACTER_COUNT (sizeof(tickerCharacters) - 1) static timeUs_t nextPageAt; static bool forcePageChange; diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index 6ac184b9c66..267f8176c69 100755 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -160,6 +160,11 @@ STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *rxCallbackData) // full frame length includes the length of the address and framelength fields const int fullFrameLength = crsfFramePosition < 3 ? 5 : crsfFrame.frame.frameLength + CRSF_FRAME_LENGTH_ADDRESS + CRSF_FRAME_LENGTH_FRAMELENGTH; + if (fullFrameLength > CRSF_FRAME_SIZE_MAX) { + crsfFramePosition = 0; + return; + } + if (crsfFramePosition < fullFrameLength) { crsfFrame.bytes[crsfFramePosition++] = (uint8_t)c; crsfFrameDone = crsfFramePosition < fullFrameLength ? false : true; From 691996ed746baadad67385aa0bfffa34108f8234 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Tue, 9 Dec 2025 23:38:46 -0600 Subject: [PATCH 27/67] guard if max conditions is increased beyond 64 --- src/main/fc/fc_msp.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 53daf9f524e..3e81b028de2 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -568,7 +568,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF { // Returns 8-byte bitmask where bit N = 1 if logic condition N is configured (non-default) uint64_t mask = 0; - for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) { + for (int i = 0; i < MIN(MAX_LOGIC_CONDITIONS, 64); i++) { const logicCondition_t *lc = logicConditions(i); // Check if any field differs from default reset values bool isConfigured = (lc->enabled != 0) || From 89850d7fc31fa8c3e4c00648350a5d75891fe9a4 Mon Sep 17 00:00:00 2001 From: shota hayashi Date: Thu, 11 Dec 2025 01:03:03 +0900 Subject: [PATCH 28/67] update on tpa --- src/main/fc/controlrate_profile.c | 1 + src/main/fc/controlrate_profile_config_struct.h | 1 + src/main/fc/settings.yaml | 10 ++++++++-- src/main/flight/pid.c | 10 +++++----- 4 files changed, 15 insertions(+), 7 deletions(-) diff --git a/src/main/fc/controlrate_profile.c b/src/main/fc/controlrate_profile.c index a7794e47eed..d004908b72b 100644 --- a/src/main/fc/controlrate_profile.c +++ b/src/main/fc/controlrate_profile.c @@ -48,6 +48,7 @@ void pgResetFn_controlRateProfiles(controlRateConfig_t *instance) .pa_breakpoint = SETTING_TPA_BREAKPOINT_DEFAULT, .fixedWingTauMs = SETTING_FW_TPA_TIME_CONSTANT_DEFAULT, .apa_pow = SETTING_APA_POW_DEFAULT, + .tpa_pitch_compensation = SETTING_TPA_PITCH_COMPENSATION_DEFAULT }, .stabilized = { diff --git a/src/main/fc/controlrate_profile_config_struct.h b/src/main/fc/controlrate_profile_config_struct.h index 2ac4aa421ee..7f46fb57a83 100644 --- a/src/main/fc/controlrate_profile_config_struct.h +++ b/src/main/fc/controlrate_profile_config_struct.h @@ -33,6 +33,7 @@ typedef struct controlRateConfig_s { uint16_t pa_breakpoint; // Breakpoint where TPA is activated uint16_t fixedWingTauMs; // Time constant of airplane TPA PT1-filter uint16_t apa_pow; // Use airspeed instead of throttle position for TPA calculation,0 to disable + uint8_t tpa_pitch_compensation; // Pitch angle based throttle compensation for fixed wing } throttle; struct { diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5e513b328f3..19dbb0ce5f6 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1387,17 +1387,23 @@ groups: min: 0 max: 200 - name: tpa_rate - description: "Throttle based PID attenuation(TPA) reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate." + description: "Throttle based PID attenuation(TPA) reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. On multirotor, For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. for fixedwing modifies PIDFF. See **PID Attenuation and scaling** Wiki for full details." default_value: 0 field: throttle.dynPID min: 0 - max: 100 + max: 200 - name: tpa_breakpoint description: "See tpa_rate." default_value: 1500 field: throttle.pa_breakpoint min: PWM_RANGE_MIN max: PWM_RANGE_MAX + - name: tpa_pitch_compensation + description: "Pitch angle based throttle compensation for fixed wing. Positive values will increase throttle when pitching up, and decrease throttle when pitching down." + default_value: 8 + field: throttle.tpa_pitch_compensation + min: 0 + max: 20 - name: tpa_on_yaw description: "Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should be set to ON for tilting rotors." type: bool diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index a5e34c6f795..b529b30b511 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -460,9 +460,6 @@ static float calculateFixedWingTPAFactor(uint16_t throttle) if (throttle > getThrottleIdleValue()) { // Calculate TPA according to throttle tpaFactor = 0.5f + ((float)(currentControlRateProfile->throttle.pa_breakpoint - getThrottleIdleValue()) / (throttle - getThrottleIdleValue()) / 2.0f); - - // Limit to [0.5; 2] range - tpaFactor = constrainf(tpaFactor, 0.5f, 2.0f); } else { tpaFactor = 2.0f; @@ -470,6 +467,8 @@ static float calculateFixedWingTPAFactor(uint16_t throttle) // Attenuate TPA curve according to configured amount tpaFactor = 1.0f + (tpaFactor - 1.0f) * (currentControlRateProfile->throttle.dynPID / 100.0f); + // Limit to [0.5; 2] range + tpaFactor = constrainf(tpaFactor, 0.3f, 2.0f); } else { tpaFactor = 1.0f; @@ -488,7 +487,7 @@ static float calculateMultirotorTPAFactor(uint16_t throttle) } else if (throttle < getMaxThrottle()) { tpaFactor = (100 - (uint16_t)currentControlRateProfile->throttle.dynPID * (throttle - currentControlRateProfile->throttle.pa_breakpoint) / (float)(getMaxThrottle() - currentControlRateProfile->throttle.pa_breakpoint)) / 100.0f; } else { - tpaFactor = (100 - currentControlRateProfile->throttle.dynPID) / 100.0f; + tpaFactor = (100 - constrain(currentControlRateProfile->throttle.dynPID, 0, 100)) / 100.0f; } return tpaFactor; @@ -502,7 +501,8 @@ static float calculateTPAThtrottle(void) if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { //fixed wing TPA with filtering fpVector3_t vForward = { .v = { HeadVecEFFiltered.x, -HeadVecEFFiltered.y, -HeadVecEFFiltered.z } }; float groundCos = vectorDotProduct(&vForward, &vDown); - int16_t throttleAdjustment = currentBatteryProfile->nav.fw.pitch_to_throttle * groundCos * 90.0f; // 90 degrees is to scale from cos to throttle adjustment + int16_t throttleAdjustment = currentControlRateProfile->throttle.tpa_pitch_compensation * groundCos * 90.0f / (PI/2); //when 1deg pitch up, increase throttle by pitch(deg)_to_throttle. cos(89 deg)*90/(pi/2)=0.99995,cos(80 deg)*90/(pi/2)=9.9493, + throttleAdjustment= throttleAdjustment<0? throttleAdjustment/2:throttleAdjustment; //reduce throttle compensation when pitch down uint16_t throttleAdjusted = rcCommand[THROTTLE] + constrain(throttleAdjustment, -1000, 1000); tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, constrain(throttleAdjusted, 1000, 2000)); } From 4690775c8489723d1567128f562195fd015c30f8 Mon Sep 17 00:00:00 2001 From: shota hayashi Date: Thu, 11 Dec 2025 01:06:18 +0900 Subject: [PATCH 29/67] update docs --- docs/Settings.md | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 02cae38e59b..daf6990dacb 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -6462,13 +6462,23 @@ Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should b --- +### tpa_pitch_compensation + +Pitch angle based throttle compensation for fixed wing. Positive values will increase throttle when pitching up, and decrease throttle when pitching down. + +| Default | Min | Max | +| --- | --- | --- | +| 8 | 0 | 20 | + +--- + ### tpa_rate -Throttle based PID attenuation(TPA) reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. +Throttle based PID attenuation(TPA) reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. On multirotor, For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. for fixedwing modifies PIDFF. See **PID Attenuation and scaling** Wiki for full details. | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 100 | +| 0 | 0 | 200 | --- From 31a5cbea8d74fd5ca8652e04b66a0fe83c9daab3 Mon Sep 17 00:00:00 2001 From: shota hayashi Date: Thu, 11 Dec 2025 01:10:23 +0900 Subject: [PATCH 30/67] minor fix on comments --- src/main/flight/pid.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index b529b30b511..62e3d7f0dd8 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -502,7 +502,7 @@ static float calculateTPAThtrottle(void) fpVector3_t vForward = { .v = { HeadVecEFFiltered.x, -HeadVecEFFiltered.y, -HeadVecEFFiltered.z } }; float groundCos = vectorDotProduct(&vForward, &vDown); int16_t throttleAdjustment = currentControlRateProfile->throttle.tpa_pitch_compensation * groundCos * 90.0f / (PI/2); //when 1deg pitch up, increase throttle by pitch(deg)_to_throttle. cos(89 deg)*90/(pi/2)=0.99995,cos(80 deg)*90/(pi/2)=9.9493, - throttleAdjustment= throttleAdjustment<0? throttleAdjustment/2:throttleAdjustment; //reduce throttle compensation when pitch down + throttleAdjustment= throttleAdjustment<0? throttleAdjustment/2:throttleAdjustment; //reduce throttle compensation when pitch up(when throttleAdjustment is negative which means trying to reduce "throttle") uint16_t throttleAdjusted = rcCommand[THROTTLE] + constrain(throttleAdjustment, -1000, 1000); tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, constrain(throttleAdjusted, 1000, 2000)); } From 253cd41085fc18f9b495d0a861d1c3c4f4cb24ed Mon Sep 17 00:00:00 2001 From: shota hayashi Date: Thu, 11 Dec 2025 01:30:56 +0900 Subject: [PATCH 31/67] minor fix --- src/main/flight/pid.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 82257897c01..b67ec110519 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -501,8 +501,7 @@ static float calculateTPAThtrottle(void) if (usedPidControllerType == PID_TYPE_PIFF && (currentControlProfile->throttle.fixedWingTauMs > 0)) { //fixed wing TPA with filtering fpVector3_t vForward = { .v = { HeadVecEFFiltered.x, -HeadVecEFFiltered.y, -HeadVecEFFiltered.z } }; float groundCos = vectorDotProduct(&vForward, &vDown); - int16_t throttleAdjustment = currentControlProfile->throttle.tpa_pitch_compensation * groundCos * 90.0f / (PI/2); //when 1deg pitch up, increase throttle by pitch(deg)_to_throttle. cos(89 deg)*90/(pi/2)=0.99995,cos(80 deg)*90/(pi/2)=9.9493, - throttleAdjustment= throttleAdjustment<0? throttleAdjustment/2:throttleAdjustment; //reduce throttle compensation when pitch up(when throttleAdjustment is negative which means trying to reduce "throttle") + int16_t throttleAdjustment = currentControlProfile->throttle.tpa_pitch_compensation * groundCos * 90.0f / 1.57079632679; //when 1deg pitch up, increase throttle by pitch(deg)_to_throttle. cos(89 deg)*90/(pi/2)=0.99995,cos(80 deg)*90/(pi/2)=9.9493, uint16_t throttleAdjusted = rcCommand[THROTTLE] + constrain(throttleAdjustment, -1000, 1000); tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, constrain(throttleAdjusted, 1000, 2000)); } From 4d3ee07ac0418cd1922c89f96ecc728777bc1e3a Mon Sep 17 00:00:00 2001 From: shota hayashi Date: Thu, 11 Dec 2025 01:56:32 +0900 Subject: [PATCH 32/67] fix: correct floating-point division in throttle adjustment calculation --- src/main/flight/pid.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index b67ec110519..7a112ff8f4f 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -501,7 +501,7 @@ static float calculateTPAThtrottle(void) if (usedPidControllerType == PID_TYPE_PIFF && (currentControlProfile->throttle.fixedWingTauMs > 0)) { //fixed wing TPA with filtering fpVector3_t vForward = { .v = { HeadVecEFFiltered.x, -HeadVecEFFiltered.y, -HeadVecEFFiltered.z } }; float groundCos = vectorDotProduct(&vForward, &vDown); - int16_t throttleAdjustment = currentControlProfile->throttle.tpa_pitch_compensation * groundCos * 90.0f / 1.57079632679; //when 1deg pitch up, increase throttle by pitch(deg)_to_throttle. cos(89 deg)*90/(pi/2)=0.99995,cos(80 deg)*90/(pi/2)=9.9493, + int16_t throttleAdjustment = currentControlProfile->throttle.tpa_pitch_compensation * groundCos * 90.0f / 1.57079632679f; //when 1deg pitch up, increase throttle by pitch(deg)_to_throttle. cos(89 deg)*90/(pi/2)=0.99995,cos(80 deg)*90/(pi/2)=9.9493, uint16_t throttleAdjusted = rcCommand[THROTTLE] + constrain(throttleAdjustment, -1000, 1000); tpaThrottle = pt1FilterApply(&fixedWingTpaFilter, constrain(throttleAdjusted, 1000, 2000)); } From 687314b046e75b9225053fb36942045c1fb33184 Mon Sep 17 00:00:00 2001 From: Wayne <118108543+wchnflr@users.noreply.github.com> Date: Mon, 15 Dec 2025 12:17:31 -0500 Subject: [PATCH 33/67] Update CMakeLists.txt Add new target with support for ICM42605/ICM42688 gyro --- src/main/target/OMNIBUSF4/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/target/OMNIBUSF4/CMakeLists.txt b/src/main/target/OMNIBUSF4/CMakeLists.txt index a6ccb483bf5..5a56e8abc93 100644 --- a/src/main/target/OMNIBUSF4/CMakeLists.txt +++ b/src/main/target/OMNIBUSF4/CMakeLists.txt @@ -9,3 +9,4 @@ target_stm32f405xg(OMNIBUSF4V3_S6_SS) # OMNIBUSF4V3 is a (almost identical) variant of OMNIBUSF4PRO target, # except for an inverter on UART6. target_stm32f405xg(OMNIBUSF4V3) +target_stm32f405xg(OMNIBUSF4V3_ICM) From 296277f6d89097c1fb73fa9b951809c01a281449 Mon Sep 17 00:00:00 2001 From: Wayne <118108543+wchnflr@users.noreply.github.com> Date: Mon, 15 Dec 2025 12:26:59 -0500 Subject: [PATCH 34/67] Update CMakeLists.txt Mark as SKIP_RELEASES. --- src/main/target/OMNIBUSF4/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/OMNIBUSF4/CMakeLists.txt b/src/main/target/OMNIBUSF4/CMakeLists.txt index 5a56e8abc93..0e2bf2002c0 100644 --- a/src/main/target/OMNIBUSF4/CMakeLists.txt +++ b/src/main/target/OMNIBUSF4/CMakeLists.txt @@ -9,4 +9,4 @@ target_stm32f405xg(OMNIBUSF4V3_S6_SS) # OMNIBUSF4V3 is a (almost identical) variant of OMNIBUSF4PRO target, # except for an inverter on UART6. target_stm32f405xg(OMNIBUSF4V3) -target_stm32f405xg(OMNIBUSF4V3_ICM) +target_stm32f405xg(OMNIBUSF4V3_ICM SKIP_RELEASES) From 938a63cbb9a9f5b05aa4762bbec258d97d636053 Mon Sep 17 00:00:00 2001 From: Wayne <118108543+wchnflr@users.noreply.github.com> Date: Mon, 15 Dec 2025 12:40:22 -0500 Subject: [PATCH 35/67] Update target.h Add new target OMNIBUSF4V3_ICM with board ID OB4I to support ICM42605/ICM42688 gyro. --- src/main/target/OMNIBUSF4/target.h | 31 +++++++++++++++++++----------- 1 file changed, 20 insertions(+), 11 deletions(-) diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 2c5a27afbb6..eb6cafe4dfa 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -30,6 +30,8 @@ #define TARGET_BOARD_IDENTIFIER "OBSD" #elif defined(OMNIBUSF4V3) #define TARGET_BOARD_IDENTIFIER "OB43" +#elif defined(OMNIBUSF4V3_ICM) +#define TARGET_BOARD_IDENTIFIER "OB4I" #elif defined(DYSF4PRO) #define TARGET_BOARD_IDENTIFIER "DYS4" #elif defined(DYSF4PROV2) @@ -67,7 +69,14 @@ #define MPU6000_CS_PIN PA4 #define MPU6000_SPI_BUS BUS_SPI1 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) +#if defined(OMNIBUSF4V3_ICM) + #define USE_IMU_ICM42605 + #define IMU_ICM42605_ALIGN CW180_DEG + #define ICM42605_CS_PIN PA4 + #define ICM42605_SPI_BUS BUS_SPI1 +#endif + +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM) #define USE_IMU_MPU6000 #define IMU_MPU6000_ALIGN CW270_DEG #else @@ -75,8 +84,8 @@ #define IMU_MPU6000_ALIGN CW180_DEG #endif -// Support for OMNIBUS F4 PRO CORNER - it has ICM20608 instead of MPU6000 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) +// Support for OMNIBUS F4 PRO CORNER - it has MPU6500 instead of MPU6000 +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM) #define MPU6500_CS_PIN MPU6000_CS_PIN #define MPU6500_SPI_BUS MPU6000_SPI_BUS #define USE_IMU_MPU6500 @@ -97,7 +106,7 @@ #define USE_BARO -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM) #define USE_BARO_BMP280 #define BMP280_SPI_BUS BUS_SPI3 #define BMP280_CS_PIN PB3 // v1 @@ -121,7 +130,7 @@ #define VBUS_SENSING_PIN PC5 #define VBUS_SENSING_ENABLED -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM) #define USE_UART_INVERTER #endif @@ -140,12 +149,12 @@ #define USE_UART6 #define UART6_RX_PIN PC7 #define UART6_TX_PIN PC6 -#if defined(OMNIBUSF4V3) +#if defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM) #define INVERTER_PIN_UART6_RX PC8 #define INVERTER_PIN_UART6_TX PC9 #endif -#if defined(OMNIBUSF4V3) && !(defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) +#if (defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM)) && !(defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)) #define USE_SOFTSERIAL1 #define SOFTSERIAL_1_RX_PIN PC6 // shared with UART6 TX #define SOFTSERIAL_1_TX_PIN PC6 // shared with UART6 TX @@ -193,7 +202,7 @@ #define USE_SPI_DEVICE_1 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM) #define USE_SPI_DEVICE_2 #define SPI2_NSS_PIN PB12 #define SPI2_SCK_PIN PB13 @@ -202,7 +211,7 @@ #endif #define USE_SPI_DEVICE_3 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM) #define SPI3_NSS_PIN PA15 #else #define SPI3_NSS_PIN PB3 @@ -215,7 +224,7 @@ #define MAX7456_SPI_BUS BUS_SPI3 #define MAX7456_CS_PIN PA15 -#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) +#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM) #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT #define USE_SDCARD #define USE_SDCARD_SPI @@ -250,7 +259,7 @@ #define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO) #define USE_LED_STRIP -#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5) +#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM)) || defined(OMNIBUSF4V3_ICM) && !defined(OMNIBUSF4PRO_LEDSTRIPM5) #define WS2811_PIN PB6 #else #define WS2811_PIN PA1 From 66efa02bb8c497a10dc3014fdade244a90b619c2 Mon Sep 17 00:00:00 2001 From: Wayne <118108543+wchnflr@users.noreply.github.com> Date: Mon, 15 Dec 2025 12:54:21 -0500 Subject: [PATCH 36/67] Edit text on line 87. --- src/main/target/OMNIBUSF4/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index eb6cafe4dfa..51d70f2309b 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -84,7 +84,7 @@ #define IMU_MPU6000_ALIGN CW180_DEG #endif -// Support for OMNIBUS F4 PRO CORNER - it has MPU6500 instead of MPU6000 +// Support for OMNIBUS F4 PRO CORNER - it has MPU6500/ICM20608 instead of MPU6000 #if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM) #define MPU6500_CS_PIN MPU6000_CS_PIN #define MPU6500_SPI_BUS MPU6000_SPI_BUS From c54d150f4e4bae1f49a657c5d0e58d52ff6c71ea Mon Sep 17 00:00:00 2001 From: Wayne <118108543+wchnflr@users.noreply.github.com> Date: Mon, 15 Dec 2025 12:59:00 -0500 Subject: [PATCH 37/67] Fix typo on Line 262 --- src/main/target/OMNIBUSF4/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index 51d70f2309b..fcd89fb0e46 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -259,7 +259,7 @@ #define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO) #define USE_LED_STRIP -#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM)) || defined(OMNIBUSF4V3_ICM) && !defined(OMNIBUSF4PRO_LEDSTRIPM5) +#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_ICM)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5) #define WS2811_PIN PB6 #else #define WS2811_PIN PA1 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 38/67] 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 From 5012f3c71d3352b05c660447e3c2489db3c0653a Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Wed, 17 Dec 2025 23:31:51 -0600 Subject: [PATCH 39/67] Docs: Add Power and Current Limiting documentation to Battery.md INAV has had power/current limiting since version 3.0.0 but it was never documented in the main Battery.md documentation file. This commit adds comprehensive documentation for the existing feature. Added sections: - Power and Current Limiting overview - Why use power limiting (battery protection, safety, compliance) - How it works (burst vs continuous limits, PI controller) - Configuration settings table (current and power limits) - Three practical example configurations - Understanding burst mode with timeline example - OSD elements for monitoring - Calibration tips and best practices The power limiting feature protects batteries and ESCs by smoothly reducing throttle when current or power exceeds configured limits. It uses a sophisticated burst reserve system that allows brief high-power maneuvers while protecting during sustained flight. Settings documented: - limit_cont_current, limit_burst_current - limit_burst_current_time, limit_burst_current_falldown_time - limit_cont_power, limit_burst_power - limit_burst_power_time, limit_burst_power_falldown_time - limit_pi_p, limit_pi_i, limit_attn_filter_cutoff This documentation helps users understand and configure a feature that has existed for years but remained largely unknown due to lack of user-facing documentation. --- docs/Battery.md | 149 ++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 149 insertions(+) diff --git a/docs/Battery.md b/docs/Battery.md index e519c325410..4354e31ddf6 100644 --- a/docs/Battery.md +++ b/docs/Battery.md @@ -169,6 +169,155 @@ current_meter_scale = (reported_draw_mAh / charging_data_mAh) * old_current_mete = 435 ``` +## Power and Current Limiting + +INAV includes an advanced power and current limiting system to protect your battery and ESCs from excessive discharge rates. This feature automatically reduces throttle output when current or power draw exceeds configured limits. + +### Why Use Power Limiting? + +Power and current limiting helps: +- **Protect batteries** from exceeding their C-rating and getting damaged +- **Prevent voltage sag** and brown-outs during high-throttle maneuvers +- **Extend battery lifespan** by avoiding excessive discharge rates +- **Improve safety** by preventing ESC or battery overheating +- **Comply with regulations** that may limit power output + +### How It Works + +The power limiter uses a PI (Proportional-Integral) controller to smoothly reduce throttle when current or power exceeds limits. It supports two operating modes: + +1. **Continuous Limit**: The sustained current/power that can be drawn indefinitely +2. **Burst Limit**: A higher current/power allowed for a short duration before falling back to the continuous limit + +This burst mode allows brief high-power maneuvers (like punch-outs or quick climbs) while protecting the battery during sustained high-throttle flight. + +### Configuration + +Power limiting requires a current sensor (`CURRENT_METER` feature). Power-based limiting additionally requires voltage measurement (`VBAT` feature). + +#### Basic Settings (per battery profile) + +| Setting | Description | Unit | Range | +|---------|-------------|------|-------| +| `limit_cont_current` | Continuous current limit | dA (deci-amps) | 0-2000 (0-200A) | +| `limit_burst_current` | Burst current limit | dA | 0-2000 (0-200A) | +| `limit_burst_current_time` | Duration burst is allowed | ds (deci-seconds) | 0-600 (0-60s) | +| `limit_burst_current_falldown_time` | Ramp-down duration from burst to continuous | ds | 0-600 (0-60s) | +| `limit_cont_power` | Continuous power limit | dW (deci-watts) | 0-20000 (0-2000W) | +| `limit_burst_power` | Burst power limit | dW | 0-20000 (0-2000W) | +| `limit_burst_power_time` | Duration burst power is allowed | ds | 0-600 (0-60s) | +| `limit_burst_power_falldown_time` | Ramp-down duration for power | ds | 0-600 (0-60s) | + +**Note**: Set any limit to `0` to disable that specific limiter. + +#### Advanced Tuning Settings + +| Setting | Description | Default | Range | +|---------|-------------|---------|-------| +| `limit_pi_p` | Proportional gain for PI controller | 100 | 10-500 | +| `limit_pi_i` | Integral gain for PI controller | 15 | 10-200 | +| `limit_attn_filter_cutoff` | Low-pass filter cutoff frequency | 50 Hz | 10-200 | + +### Example Configurations + +#### Example 1: Simple Current Limiting (50A continuous) + +Protect a 1500mAh 4S 50C battery (75A max burst, 50A continuous safe): + +``` +battery_profile 1 + +set limit_cont_current = 500 # 50A continuous +set limit_burst_current = 750 # 75A burst +set limit_burst_current_time = 100 # 10 seconds +set limit_burst_current_falldown_time = 20 # 2 second ramp-down +``` + +#### Example 2: Power Limiting for Racing (500W limit) + +Limit total system power for racing class restrictions: + +``` +battery_profile 1 + +set limit_cont_power = 4500 # 450W continuous +set limit_burst_power = 5000 # 500W burst +set limit_burst_power_time = 50 # 5 seconds +set limit_burst_power_falldown_time = 10 # 1 second ramp-down +``` + +#### Example 3: Combined Current and Power Limiting + +Protect both battery (current) and ESCs (power): + +``` +battery_profile 1 + +# Current limits (battery protection) +set limit_cont_current = 600 # 60A continuous +set limit_burst_current = 800 # 80A burst +set limit_burst_current_time = 100 # 10 seconds + +# Power limits (ESC protection) +set limit_cont_power = 8000 # 800W continuous +set limit_burst_power = 10000 # 1000W burst +set limit_burst_power_time = 100 # 10 seconds +``` + +### Understanding Burst Mode + +When you exceed the continuous limit, the system uses "burst reserve" (like a capacitor): +- **Burst reserve** starts full and depletes when current/power exceeds the continuous limit +- When reserve is empty, the limit drops to the continuous value +- The `falldown_time` setting creates a smooth ramp-down instead of an abrupt drop +- Reserve recharges when current/power drops below the continuous limit + +**Example timeline** (60A continuous, 80A burst, 10s burst time, 2s falldown): +``` +Time Limit Reason +---- ----- ------ +0s 80A Full burst reserve +5s 80A Still have reserve (using 5s of 10s) +10s 80A Reserve depleted +10-12s 80→60A Ramping down over 2 seconds +12s+ 60A Continuous limit active +``` + +### OSD Elements + +Three OSD elements display power limiting status: + +- **`OSD_PLIMIT_REMAINING_BURST_TIME`**: Shows remaining burst time in seconds +- **`OSD_PLIMIT_ACTIVE_CURRENT_LIMIT`**: Shows current limit being enforced (blinks when limiting) +- **`OSD_PLIMIT_ACTIVE_POWER_LIMIT`**: Shows power limit being enforced (blinks when limiting) + +Enable these in the OSD tab to monitor limiting during flight. + +### Calibration Tips + +1. **Find your battery's limits**: Check manufacturer specifications for continuous and burst C-ratings + - Continuous limit = `battery_capacity_mAh Ɨ continuous_C_rating / 1000` (in dA) + - Burst limit = `battery_capacity_mAh Ɨ burst_C_rating / 1000` (in dA) + +2. **Test incrementally**: Start with conservative limits and increase gradually + +3. **Monitor in flight**: Use OSD elements to see when limiting activates + +4. **Calibrate current sensor**: Accurate current readings are critical - see "Current Monitoring" section above + +5. **Tune PI controller**: If limiting feels abrupt or causes oscillation, adjust `limit_pi_p` and `limit_pi_i`: + - Increase P for faster response (may cause oscillation) + - Increase I for better steady-state accuracy + - Decrease if throttle oscillates during limiting + +### Notes + +- Power limiting is part of the battery profile system - each profile can have different limits +- Both current and power limiting can be active simultaneously - the most restrictive applies +- Limiting is applied smoothly via PI controller to avoid abrupt throttle cuts +- The system uses instantaneous current/power readings for responsive limiting +- Set limits to `0` to disable a specific limiter while keeping others active + ## Battery capacity monitoring For the capacity monitoring to work you need a current sensor (`CURRENT_METER` feature). For monitoring energy in milliWatt hour you also need voltage measurement (`VBAT` feature). For best results the current and voltage readings have to be calibrated. From e4cc1dfda79bd678f7f4ad1548d7ce17187c1e95 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Thu, 18 Dec 2025 00:10:02 -0600 Subject: [PATCH 40/67] Fix power limiting treating 0 (disabled) as less than continuous The power limiting initialization incorrectly treated burst limit of 0 as numerically less than continuous limit, and would automatically set burst = continuous. However, 0 means 'disabled/unlimited' not 'zero amps/watts allowed'. This fix allows the valid configuration: - limit_cont_current = 1000 (100A continuous limit) - limit_burst_current = 0 (no burst limiting - unlimited bursts) Changes: - Only enforce burst >= continuous when burst is enabled (> 0) - Applied to both current and power limit initialization - Added comments explaining the 0 = disabled semantics --- src/main/flight/power_limits.c | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/main/flight/power_limits.c b/src/main/flight/power_limits.c index 1fe13240fe7..1770fd71a7f 100644 --- a/src/main/flight/power_limits.c +++ b/src/main/flight/power_limits.c @@ -73,7 +73,10 @@ static bool wasLimitingPower = false; #endif void powerLimiterInit(void) { - if (currentBatteryProfile->powerLimits.burstCurrent < currentBatteryProfile->powerLimits.continuousCurrent) { + // Only enforce burst >= continuous if burst is enabled (non-zero) + // A value of 0 means "disabled/unlimited", not "zero amps allowed" + if (currentBatteryProfile->powerLimits.burstCurrent > 0 && + currentBatteryProfile->powerLimits.burstCurrent < currentBatteryProfile->powerLimits.continuousCurrent) { currentBatteryProfileMutable->powerLimits.burstCurrent = currentBatteryProfile->powerLimits.continuousCurrent; } @@ -87,7 +90,9 @@ void powerLimiterInit(void) { pt1FilterInitRC(¤tThrLimitingBaseFilter, LIMITING_THR_FILTER_TCONST, 0); #ifdef USE_ADC - if (currentBatteryProfile->powerLimits.burstPower < currentBatteryProfile->powerLimits.continuousPower) { + // Only enforce burst >= continuous if burst is enabled (non-zero) + if (currentBatteryProfile->powerLimits.burstPower > 0 && + currentBatteryProfile->powerLimits.burstPower < currentBatteryProfile->powerLimits.continuousPower) { currentBatteryProfileMutable->powerLimits.burstPower = currentBatteryProfile->powerLimits.continuousPower; } From 8eb2930b0c5ab4e494ff8005960123a5785c7878 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Thu, 18 Dec 2025 00:19:26 -0600 Subject: [PATCH 41/67] Fix formula divisor in power limit calibration tips MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Changed divisor from 1000 to 100 to correctly convert from mAh to dA. Example: 1500 mAh Ɨ 50C / 100 = 750 dA (75A) āœ“ Previously: 1500 mAh Ɨ 50C / 1000 = 75 dA (7.5A) āœ— Thanks to Qodo code review for catching this. --- docs/Battery.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Battery.md b/docs/Battery.md index 4354e31ddf6..a66e6ae5361 100644 --- a/docs/Battery.md +++ b/docs/Battery.md @@ -296,8 +296,8 @@ Enable these in the OSD tab to monitor limiting during flight. ### Calibration Tips 1. **Find your battery's limits**: Check manufacturer specifications for continuous and burst C-ratings - - Continuous limit = `battery_capacity_mAh Ɨ continuous_C_rating / 1000` (in dA) - - Burst limit = `battery_capacity_mAh Ɨ burst_C_rating / 1000` (in dA) + - Continuous limit = `battery_capacity_mAh Ɨ continuous_C_rating / 100` (in dA) + - Burst limit = `battery_capacity_mAh Ɨ burst_C_rating / 100` (in dA) 2. **Test incrementally**: Start with conservative limits and increase gradually From ec656259cf946e44d812468b46a06a681ef96851 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Fri, 19 Dec 2025 11:41:30 -0600 Subject: [PATCH 42/67] docs: Update Development.md with maintenance branch workflow MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Replace outdated branching documentation with current maintenance branch strategy. Uses generic terminology (current/next version) with examples so documentation remains valid across versions. Changes: - Document maintenance-X.x branches for backward-compatible changes - Document maintenance-(X+1).x for breaking changes - Update workflow examples to branch from maintenance branches - Remove outdated release_x.y.z branch references - Add guidance on choosing correct target branch šŸ¤– Generated with [Claude Code](https://claude.com/claude-code) Co-Authored-By: Claude Sonnet 4.5 --- docs/development/Development.md | 92 ++++++++++++++++++++++++++++++--- 1 file changed, 86 insertions(+), 6 deletions(-) diff --git a/docs/development/Development.md b/docs/development/Development.md index 03dbc5b0952..ced9571f2fe 100755 --- a/docs/development/Development.md +++ b/docs/development/Development.md @@ -107,11 +107,13 @@ The main flow for a contributing is as follows: 7. `git add ` 8. `git commit` 9. `git push origin my-new-code` -10. Create pull request using github UI to merge your changes from your new branch into `inav/master` +10. Create pull request using github UI to merge your changes from your new branch into the appropriate target branch (see "Branching and release workflow" below) 11. Repeat from step 4 for new other changes. The primary thing to remember is that separate pull requests should be created for separate branches. Never create a pull request from your `master` branch. +**Important:** Most contributions should target a maintenance branch, not `master`. See the branching section below for guidance on choosing the correct target branch. + Later, you can get the changes from the INAV repo into your `master` branch by adding INAV as a git remote and merging from it as follows: 1. `git remote add upstream https://github.com/iNavFlight/inav.git` @@ -125,10 +127,88 @@ You can also perform the git commands using the git client inside Eclipse. Refe ## Branching and release workflow -Normally, all development occurs on the `master` branch. Every release will have it's own branch named `release_x.y.z`. +INAV uses maintenance branches for active development and releases. The `master` branch receives merges from maintenance branches. + +### Branch Types + +#### Maintenance Branches (Current and Next Major Version) + +**Current version branch** (e.g., `maintenance-9.x`): +- Used for backward-compatible changes +- Bug fixes, new features, and improvements that don't break compatibility +- Changes here will be included in the next release of the current major version (e.g., 9.1, 9.2) +- Does not create compatibility issues between firmware and configurator within the same major version + +**Next major version branch** (e.g., `maintenance-10.x`): +- Used for changes that introduce compatibility requirements +- Breaking changes that would cause issues between different major versions +- New features that require coordinated firmware and configurator updates +- Changes here will be included in the next major version release (e.g., 10.0) + +#### Master Branch + +The `master` branch receives periodic merges from maintenance branches. + +### Choosing the Right Target Branch + +When creating a pull request, target the appropriate branch: + +**Target the current version branch** (e.g., `maintenance-9.x`) if your change: +- Fixes a bug +- Adds a new feature that is backward-compatible +- Updates documentation +- Adds or updates hardware targets +- Makes improvements that work with existing releases + +**Target the next major version branch** (e.g., `maintenance-10.x`) if your change: +- Breaks compatibility with the current major version +- Requires coordinated firmware and configurator updates +- Changes MSP protocol in an incompatible way +- Modifies data structures in a breaking way + +### Release Workflow -During release candidate cycle we will follow the process outlined below: +1. Development occurs on the current version maintenance branch (e.g., `maintenance-9.x`) +2. When ready for release, a release candidate is tagged from the maintenance branch +3. Bug fixes during the RC period continue on the maintenance branch +4. After final release, the maintenance branch is periodically merged into `master` +5. The cycle continues with the maintenance branch receiving new changes for the next release -1. Create a release branch `release_x.y.z` -2. All bug fixes found in the release candidates will be merged into `release_x.y.z` branch and not into the `master`. -3. After final release is made, the branch `release_x.y.z` is locked, and merged into `master` bringing all of the bug fixes into the development branch. Merge conflicts that may arise at this stage are resolved manually. +### Example Timeline + +Current state (example): +- `maintenance-9.x` - Active development for INAV 9.1, 9.2, etc. +- `maintenance-10.x` - Breaking changes for future INAV 10.0 +- `master` - Receives periodic merges from maintenance branches + +After INAV 10.0 is released: +- `maintenance-10.x` - Active development for INAV 10.1, 10.2, etc. +- `maintenance-11.x` - Breaking changes for future INAV 11.0 +- `master` - Continues receiving merges + +### Working with Maintenance Branches + +To branch from the current maintenance branch instead of master: + +```bash +# Fetch latest changes +git fetch upstream + +# Create your feature branch from the maintenance branch +git checkout -b my-new-feature upstream/maintenance-9.x + +# Make changes, commit, and push +git push origin my-new-feature + +# Create PR targeting maintenance-9.x (not master) +``` + +When updating your fork: + +```bash +# Get the latest maintenance branch changes +git fetch upstream +git checkout maintenance-9.x +git merge upstream/maintenance-9.x +git push origin maintenance-9.x +``` From 6458e3729ba6077e66dac1a60aa79b56b7e7f366 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 20 Dec 2025 19:57:48 -0600 Subject: [PATCH 43/67] Docs: Update JavaScript Programming documentation to use namespaced syntax Update all code examples in JavaScript Programming documentation to use the fully namespaced inav.* syntax instead of destructuring. Changes: - Remove const { flight, override, ... } = inav; destructuring - Replace flight.* with inav.flight.* - Replace override.* with inav.override.* - Replace gvar[ with inav.gvar[ - Replace rc[ with inav.rc[ - Replace waypoint.* with inav.waypoint.* - Replace edge() with inav.events.edge() - Replace sticky() with inav.events.sticky() - Replace delay() with inav.events.delay() - Replace timer() with inav.events.timer() - Replace whenChanged() with inav.events.whenChanged() This aligns the documentation with the transpiler changes that removed backward compatibility for destructuring syntax. Users now access all INAV APIs through the fully qualified inav namespace. Files updated: - index.md - JAVASCRIPT_PROGRAMMING_GUIDE.md - OPERATIONS_REFERENCE.md - TESTING_GUIDE.md - TIMER_WHENCHANGED_EXAMPLES.md - TIMER_WHENCHANGED_IMPLEMENTATION.md - api_definitions_summary.md - api_maintenance_guide.md - implementation_summary.md - GENERATE_CONSTANTS_README.md --- .../GENERATE_CONSTANTS_README.md | 7 +- .../JAVASCRIPT_PROGRAMMING_GUIDE.md | 95 +++++------ .../OPERATIONS_REFERENCE.md | 35 +++-- docs/javascript_programming/TESTING_GUIDE.md | 39 +++-- .../TIMER_WHENCHANGED_EXAMPLES.md | 147 +++++++++--------- .../TIMER_WHENCHANGED_IMPLEMENTATION.md | 37 +++-- .../api_definitions_summary.md | 6 +- .../api_maintenance_guide.md | 26 +++- .../implementation_summary.md | 31 ++-- docs/javascript_programming/index.md | 6 +- 10 files changed, 236 insertions(+), 193 deletions(-) diff --git a/docs/javascript_programming/GENERATE_CONSTANTS_README.md b/docs/javascript_programming/GENERATE_CONSTANTS_README.md index c012a24f120..dfea3be7979 100644 --- a/docs/javascript_programming/GENERATE_CONSTANTS_README.md +++ b/docs/javascript_programming/GENERATE_CONSTANTS_README.md @@ -87,6 +87,7 @@ const FLIGHT_PARAM = { }; // ... exports + ``` ## Build Integration @@ -109,21 +110,23 @@ This ensures constants are regenerated before each build. Currently, API definitions have hardcoded values: ```javascript -// flight.js - WRONG (hardcoded) +// inav.flight.js - WRONG (hardcoded) yaw: { inavOperand: { type: 2, value: 17 } // Wrong value! } + ``` Change to reference constants: ```javascript -// flight.js - CORRECT (references constants) +// inav.flight.js - CORRECT (references constants) const { OPERAND_TYPE, FLIGHT_PARAM } = require('../../transpiler/inav_constants.js'); yaw: { inavOperand: { type: OPERAND_TYPE.FLIGHT, value: FLIGHT_PARAM.ATTITUDE_YAW } } + ``` Benefits: diff --git a/docs/javascript_programming/JAVASCRIPT_PROGRAMMING_GUIDE.md b/docs/javascript_programming/JAVASCRIPT_PROGRAMMING_GUIDE.md index 6609aa873b6..9c7dad4a8a9 100644 --- a/docs/javascript_programming/JAVASCRIPT_PROGRAMMING_GUIDE.md +++ b/docs/javascript_programming/JAVASCRIPT_PROGRAMMING_GUIDE.md @@ -22,12 +22,12 @@ conditions behind the scenes. Use `if` statements for conditions that should check and execute **every cycle**: ```javascript -const { flight, override } = inav; // Checks every cycle - adjusts VTX power continuously -if (flight.homeDistance > 100) { - override.vtx.power = 3; +if (inav.flight.homeDistance > 100) { + inav.override.vtx.power = 3; } + ``` **Use when:** You want the action to happen continuously while the condition is true. @@ -38,13 +38,13 @@ if (flight.homeDistance > 100) { Use `edge()` for actions that should execute **only once** when a condition becomes true: ```javascript -const { flight, gvar, edge } = inav; // Executes ONCE when armTimer reaches 1000ms -edge(() => flight.armTimer > 1000, { duration: 0 }, () => { - gvar[0] = flight.yaw; // Save initial heading - gvar[1] = 0; // Initialize counter +inav.events.edge(() => inav.flight.armTimer > 1000, { duration: 0 }, () => { + inav.gvar[0] = inav.flight.yaw; // Save initial heading + inav.gvar[1] = 0; // Initialize counter }); + ``` **Parameters:** @@ -64,16 +64,16 @@ edge(() => flight.armTimer > 1000, { duration: 0 }, () => { Use `sticky()` for conditions that latch ON and stay ON until reset: ```javascript -const { flight, gvar, sticky } = inav; // Latches ON when RSSI < 30, stays ON until RSSI > 70 -sticky( - () => flight.rssi < 30, // ON condition - () => flight.rssi > 70, // OFF condition +inav.events.sticky( + () => inav.flight.rssi < 30, // ON condition + () => inav.flight.rssi > 70, // OFF condition () => { - override.vtx.power = 4; // Executes while latched + inav.override.vtx.power = 4; // Executes while latched } ); + ``` **Parameters:** @@ -92,12 +92,12 @@ sticky( Use `delay()` to execute after a condition has been true for a duration: ```javascript -const { flight, gvar, delay } = inav; // Executes only if RSSI < 30 for 2 seconds continuously -delay(() => flight.rssi < 30, { duration: 2000 }, () => { - gvar[0] = 1; // Set failsafe flag +inav.events.delay(() => inav.flight.rssi < 30, { duration: 2000 }, () => { + inav.gvar[0] = 1; // Set failsafe flag }); + ``` **Parameters:** @@ -116,73 +116,73 @@ delay(() => flight.rssi < 30, { duration: 2000 }, () => { ### Initialize on Arm ```javascript -const { flight, gvar, edge } = inav; -edge(() => flight.armTimer > 1000, { duration: 0 }, () => { - gvar[0] = 0; // Reset counter - gvar[1] = flight.yaw; // Save heading - gvar[2] = flight.altitude; // Save starting altitude +inav.events.edge(() => inav.flight.armTimer > 1000, { duration: 0 }, () => { + inav.gvar[0] = 0; // Reset counter + inav.gvar[1] = inav.flight.yaw; // Save heading + inav.gvar[2] = inav.flight.altitude; // Save starting altitude }); + ``` ### Count Events ```javascript -const { flight, gvar, edge } = inav; // Initialize -edge(() => flight.armTimer > 1000, { duration: 0 }, () => { - gvar[0] = 0; +inav.events.edge(() => inav.flight.armTimer > 1000, { duration: 0 }, () => { + inav.gvar[0] = 0; }); // Count each time RSSI drops below 30 (counts transitions, not duration) -edge(() => flight.rssi < 30, { duration: 100 }, () => { - gvar[0] = gvar[0] + 1; +inav.events.edge(() => inav.flight.rssi < 30, { duration: 100 }, () => { + inav.gvar[0] = inav.gvar[0] + 1; }); + ``` ### Debounce Noisy Signals ```javascript -const { flight, override, edge } = inav; // Only trigger if RSSI < 30 for at least 500ms -edge(() => flight.rssi < 30, { duration: 500 }, () => { - override.vtx.power = 4; +inav.events.edge(() => inav.flight.rssi < 30, { duration: 500 }, () => { + inav.override.vtx.power = 4; }); + ``` ### Multi-Stage Logic ```javascript -const { flight, override } = inav; // Stage 1: Far away -if (flight.homeDistance > 500) { - override.vtx.power = 4; +if (inav.flight.homeDistance > 500) { + inav.override.vtx.power = 4; } // Stage 2: Medium distance -if (flight.homeDistance > 200 && flight.homeDistance <= 500) { - override.vtx.power = 3; +if (inav.flight.homeDistance > 200 && inav.flight.homeDistance <= 500) { + inav.override.vtx.power = 3; } // Stage 3: Close to home -if (flight.homeDistance <= 200) { - override.vtx.power = 2; +if (inav.flight.homeDistance <= 200) { + inav.override.vtx.power = 2; } + ``` ### Hysteresis/Deadband ```javascript -const { flight, gvar, sticky } = inav; // Turn ON at low voltage, turn OFF when recovered -sticky( - () => flight.cellVoltage < 330, // Warning threshold - () => flight.cellVoltage > 350, // Recovery threshold +inav.events.sticky( + () => inav.flight.cellVoltage < 330, // Warning threshold + () => inav.flight.cellVoltage > 350, // Recovery threshold () => { - override.throttleScale = 50; // Reduce throttle while in warning - gvar[0] = 1; // Warning flag + inav.override.throttleScale = 50; // Reduce throttle while in warning + inav.gvar[0] = 1; // Warning flag } ); + ``` --- @@ -211,6 +211,7 @@ const { sticky, // Latching conditions delay // Delayed execution } = inav; + ``` --- @@ -231,17 +232,17 @@ const { Use global variables to track state: ```javascript -const { flight, gvar, edge } = inav; // Debug counter -edge(() => flight.armTimer > 1000, { duration: 0 }, () => { - gvar[7] = 0; // Use gvar[7] as debug counter +inav.events.edge(() => inav.flight.armTimer > 1000, { duration: 0 }, () => { + inav.gvar[7] = 0; // Use inav.gvar[7] as debug counter }); // Increment on each event -edge(() => flight.rssi < 30, { duration: 0 }, () => { - gvar[7] = gvar[7] + 1; +inav.events.edge(() => inav.flight.rssi < 30, { duration: 0 }, () => { + inav.gvar[7] = inav.gvar[7] + 1; }); -// Check gvar[7] value in OSD or Configurator to see event count +// Check inav.gvar[7] value in OSD or Configurator to see event count + ``` diff --git a/docs/javascript_programming/OPERATIONS_REFERENCE.md b/docs/javascript_programming/OPERATIONS_REFERENCE.md index 3506abd2c56..eb967ae31bb 100644 --- a/docs/javascript_programming/OPERATIONS_REFERENCE.md +++ b/docs/javascript_programming/OPERATIONS_REFERENCE.md @@ -24,24 +24,25 @@ All INAV logic condition operations supported by the firmware are now fully impl ```javascript // XOR - true when exactly one condition is true -if (xor(flight.armed, flight.mode.failsafe)) { +if (xor(inav.flight.armed, inav.flight.mode.failsafe)) { // One or the other, but not both } // NAND - false only when both are true -if (nand(flight.armed, gvar[0] > 100)) { +if (nand(inav.flight.armed, inav.gvar[0] > 100)) { // Not both conditions true } // NOR - true only when both are false -if (nor(flight.mode.failsafe, flight.mode.rth)) { +if (nor(inav.flight.mode.failsafe, inav.flight.mode.rth)) { // Neither failsafe nor RTH active } // Approximate equality with tolerance -if (approxEqual(flight.altitude, 1000, 50)) { +if (approxEqual(inav.flight.altitude, 1000, 50)) { // Altitude is 1000 ± 50 } + ``` ### Scaling/Mapping Operations @@ -49,7 +50,7 @@ if (approxEqual(flight.altitude, 1000, 50)) { ```javascript // mapInput: Scale from [0:maxValue] to [0:1000] // Example: RC value (1000-2000) to normalized (0-1000) -const normalizedThrottle = mapInput(rc[3].value - 1000, 1000); +const normalizedThrottle = mapInput(inav.rc[3].value - 1000, 1000); // mapOutput: Scale from [0:1000] to [0:maxValue] // Example: normalized (0-1000) to servo angle (0-180) @@ -57,41 +58,43 @@ const servoAngle = mapOutput(normalizedThrottle, 180); // Chaining for full range mapping // Map altitude (0-5000m) to percentage (0-100) -const altitudePercent = mapOutput(mapInput(flight.altitude, 5000), 100); +const altitudePercent = mapOutput(mapInput(inav.flight.altitude, 5000), 100); + ``` ### RC Channel State Detection ```javascript // LOW state - RC value < 1333us -if (rc[0].low) { +if (inav.rc[0].low) { // Roll stick is in low position - gvar[0] = 1; + inav.gvar[0] = 1; } // MID state - RC value between 1333-1666us -if (rc[1].mid) { +if (inav.rc[1].mid) { // Pitch stick is centered - gvar[1] = 1; + inav.gvar[1] = 1; } // HIGH state - RC value > 1666us -if (rc[2].high) { +if (inav.rc[2].high) { // Throttle stick is in high position - override.vtx.power = 4; + inav.override.vtx.power = 4; } // Access raw RC value -if (rc[3].value > 1700) { +if (inav.rc[3].value > 1700) { // Custom threshold on yaw channel - gvar[2] = 1; + inav.gvar[2] = 1; } // Combined with logical operations -if (rc[0].low && rc[1].mid && rc[2].high) { +if (inav.rc[0].low && inav.rc[1].mid && inav.rc[2].high) { // Specific stick combination detected - override.armSafety = 1; + inav.override.armSafety = 1; } + ``` ## Notes diff --git a/docs/javascript_programming/TESTING_GUIDE.md b/docs/javascript_programming/TESTING_GUIDE.md index 2e6910e8854..c44f4ad9202 100644 --- a/docs/javascript_programming/TESTING_GUIDE.md +++ b/docs/javascript_programming/TESTING_GUIDE.md @@ -51,11 +51,10 @@ import { Transpiler } from './transpiler/index.js'; import { Decompiler } from './transpiler/decompiler.js'; const testCode = ` -const { flight, gvar } = inav; // Your test code here -if (flight.altitude > 100) { - gvar[0] = 1; +if (inav.flight.altitude > 100) { + inav.gvar[0] = 1; } `; @@ -97,6 +96,7 @@ if (decompileResult.success) { } else { console.error('\nāŒ Decompilation failed:', decompileResult.error); } + ``` ### Running Tests @@ -120,42 +120,45 @@ When making changes, test these scenarios: ### 1. Basic Functionality ```javascript -const { flight, gvar } = inav; -if (flight.altitude > 100) { - gvar[0] = 1; +if (inav.flight.altitude > 100) { + inav.gvar[0] = 1; } + ``` Expected: 2 commands (condition + action) ### 2. Error Handling ```javascript // Invalid syntax - should produce helpful error -if (flight.invalidProperty > 100) { - gvar[0] = 1; +if (inav.flight.invalidProperty > 100) { + inav.gvar[0] = 1; } + ``` Expected: Error with suggestion for correct property ### 3. Edge Cases ```javascript // Test boundary values -if (rc[0].low) { // Channel 0 (first) - gvar[0] = 1; +if (inav.rc[0].low) { // Channel 0 (first) + inav.gvar[0] = 1; } -if (rc[17].high) { // Channel 17 (last valid) - gvar[1] = 1; +if (inav.rc[17].high) { // Channel 17 (last valid) + inav.gvar[1] = 1; } + ``` Expected: Valid generation for both ### 4. Complex Combinations ```javascript // Test multiple operations together -if (xor(rc[0].low, flight.armed)) { - gvar[0] = Math.max(100, flight.altitude); +if (xor(inav.rc[0].low, inav.flight.armed)) { + inav.gvar[0] = Math.max(100, inav.flight.altitude); } + ``` Expected: Proper nesting of operations @@ -205,6 +208,7 @@ const OPERATION = { FOOBAR: 99, // Check this exists // ... }; + ``` **2. Update Codegen** @@ -223,6 +227,7 @@ case 'CallExpression': { return resultIndex; } } + ``` **3. Update Decompiler** @@ -230,24 +235,26 @@ case 'CallExpression': { // In transpiler/decompiler.js case OPERATION.FOOBAR: return 'foobar()'; + ``` **4. Update Analyzer (if needed)** ```javascript // In transpiler/analyzer.js // Add validation for foobar() usage + ``` **5. Test Round-Trip** ```javascript const testCode = ` -const { flight } = inav; if (foobar()) { - gvar[0] = 1; + inav.gvar[0] = 1; } `; // Run round-trip test... + ``` **6. Update Documentation** diff --git a/docs/javascript_programming/TIMER_WHENCHANGED_EXAMPLES.md b/docs/javascript_programming/TIMER_WHENCHANGED_EXAMPLES.md index 14a8635e81a..35b89d30f8c 100644 --- a/docs/javascript_programming/TIMER_WHENCHANGED_EXAMPLES.md +++ b/docs/javascript_programming/TIMER_WHENCHANGED_EXAMPLES.md @@ -4,184 +4,185 @@ ### Example 1: Periodic VTX Power Boost ```javascript -const { override, timer } = inav; // Boost VTX power to maximum for 1 second every 5 seconds -timer(1000, 5000, () => { - override.vtx.power = 4; +inav.events.timer(1000, 5000, () => { + inav.override.vtx.power = 4; }); + ``` ### Example 2: Flashing OSD Layout ```javascript -const { override, timer } = inav; // Alternate between OSD layout 0 and 1 every second -timer(1000, 1000, () => { - override.osdLayout = 1; +inav.events.timer(1000, 1000, () => { + inav.override.osdLayout = 1; }); + ``` ### Example 3: Periodic Status Check ```javascript -const { flight, gvar, timer } = inav; // Record battery voltage every 10 seconds for 100ms -timer(100, 10000, () => { - gvar[0] = flight.vbat; - gvar[1] = flight.current; +inav.events.timer(100, 10000, () => { + inav.gvar[0] = inav.flight.vbat; + inav.gvar[1] = inav.flight.current; }); + ``` ### Example 4: Warning Beep Pattern ```javascript -const { override, timer } = inav; // Beep pattern: 200ms on, 200ms off, 200ms on, 5s off // (Would need multiple timers or different approach for complex patterns) -timer(200, 200, () => { - override.rcChannel(8, 2000); // Beeper channel +inav.events.timer(200, 200, () => { + inav.override.rcChannel(8, 2000); // Beeper channel }); + ``` ## whenChanged() Examples ### Example 1: Altitude Change Logger ```javascript -const { flight, gvar, whenChanged } = inav; // Log altitude whenever it changes by 50cm or more -whenChanged(flight.altitude, 50, () => { - gvar[0] = flight.altitude; +inav.events.whenChanged(inav.flight.altitude, 50, () => { + inav.gvar[0] = inav.flight.altitude; }); + ``` ### Example 2: RSSI Drop Detection ```javascript -const { flight, override, whenChanged } = inav; // Boost VTX power when RSSI drops by 10 or more -whenChanged(flight.rssi, 10, () => { - if (flight.rssi < 50) { - override.vtx.power = 4; +inav.events.whenChanged(inav.flight.rssi, 10, () => { + if (inav.flight.rssi < 50) { + inav.override.vtx.power = 4; } }); + ``` ### Example 3: Speed Change Tracker ```javascript -const { flight, gvar, whenChanged } = inav; // Track ground speed changes of 100cm/s or more -whenChanged(flight.groundSpeed, 100, () => { - gvar[1] = flight.groundSpeed; +inav.events.whenChanged(inav.flight.groundSpeed, 100, () => { + inav.gvar[1] = inav.flight.groundSpeed; }); + ``` ### Example 4: Battery Voltage Monitor ```javascript -const { flight, gvar, whenChanged } = inav; // Record voltage whenever it changes by 1 unit (0.1V) -whenChanged(flight.vbat, 1, () => { - gvar[2] = flight.vbat; - gvar[3] = flight.mahDrawn; +inav.events.whenChanged(inav.flight.vbat, 1, () => { + inav.gvar[2] = inav.flight.vbat; + inav.gvar[3] = inav.flight.mahDrawn; }); + ``` ### Example 5: Climb Rate Detection ```javascript -const { flight, override, whenChanged } = inav; // Detect rapid climbs (>50cm/s change in vertical speed) -whenChanged(flight.verticalSpeed, 50, () => { - if (flight.verticalSpeed > 200) { +inav.events.whenChanged(inav.flight.verticalSpeed, 50, () => { + if (inav.flight.verticalSpeed > 200) { // Climbing fast - reduce throttle scale - override.throttleScale = 80; + inav.override.throttleScale = 80; } }); + ``` ## Combined Examples ### Example 1: Timer + WhenChanged ```javascript -const { flight, override, gvar, timer, whenChanged } = inav; // Periodic VTX boost -timer(1000, 5000, () => { - override.vtx.power = 4; +inav.events.timer(1000, 5000, () => { + inav.override.vtx.power = 4; }); // Log altitude changes -whenChanged(flight.altitude, 100, () => { - gvar[0] = flight.altitude; +inav.events.whenChanged(inav.flight.altitude, 100, () => { + inav.gvar[0] = inav.flight.altitude; }); + ``` ### Example 2: Conditional Timer ```javascript -const { flight, override, timer } = inav; // Only run timer when armed -if (flight.isArmed) { - timer(500, 500, () => { - override.osdLayout = 2; +if (inav.flight.isArmed) { + inav.events.timer(500, 500, () => { + inav.override.osdLayout = 2; }); } + ``` ### Example 3: Emergency Response System ```javascript -const { flight, override, gvar, whenChanged } = inav; // Monitor RSSI drops -whenChanged(flight.rssi, 5, () => { - if (flight.rssi < 30) { +inav.events.whenChanged(inav.flight.rssi, 5, () => { + if (inav.flight.rssi < 30) { // RSSI critical - max VTX power - override.vtx.power = 4; - gvar[7] = 1; // Set emergency flag + inav.override.vtx.power = 4; + inav.gvar[7] = 1; // Set emergency flag } }); // Monitor altitude changes -whenChanged(flight.altitude, 200, () => { - if (flight.altitude > 10000) { +inav.events.whenChanged(inav.flight.altitude, 200, () => { + if (inav.flight.altitude > 10000) { // Too high - warn - gvar[6] = flight.altitude; + inav.gvar[6] = inav.flight.altitude; } }); + ``` ### Example 4: Data Logging System ```javascript -const { flight, gvar, timer, whenChanged } = inav; // Periodic logging every 5 seconds -timer(100, 5000, () => { - gvar[0] = flight.vbat; - gvar[1] = flight.current; - gvar[2] = flight.altitude; +inav.events.timer(100, 5000, () => { + inav.gvar[0] = inav.flight.vbat; + inav.gvar[1] = inav.flight.current; + inav.gvar[2] = inav.flight.altitude; }); // Event-based logging on significant changes -whenChanged(flight.altitude, 500, () => { - gvar[3] = flight.altitude; - gvar[4] = flight.verticalSpeed; +inav.events.whenChanged(inav.flight.altitude, 500, () => { + inav.gvar[3] = inav.flight.altitude; + inav.gvar[4] = inav.flight.verticalSpeed; }); -whenChanged(flight.groundSpeed, 200, () => { - gvar[5] = flight.groundSpeed; +inav.events.whenChanged(inav.flight.groundSpeed, 200, () => { + inav.gvar[5] = inav.flight.groundSpeed; }); + ``` ## Logic Condition Output Examples ### timer() Output ```javascript -timer(1000, 2000, () => { - gvar[0] = 1; +inav.events.timer(1000, 2000, () => { + inav.gvar[0] = 1; }); + ``` Generates: ``` @@ -191,9 +192,10 @@ logic 1 1 0 18 0 0 0 0 1 0 # gvar[0] = 1 ### whenChanged() Output ```javascript -whenChanged(flight.altitude, 50, () => { - gvar[0] = flight.altitude; +inav.events.whenChanged(inav.flight.altitude, 50, () => { + inav.gvar[0] = inav.flight.altitude; }); + ``` Generates: ``` @@ -239,29 +241,32 @@ logic 1 1 0 18 0 0 2 12 0 # gvar[0] = altitude ### Pattern 1: Status Monitor ```javascript // Log key parameters when they change significantly -whenChanged(flight.vbat, 2, () => { gvar[0] = flight.vbat; }); -whenChanged(flight.rssi, 10, () => { gvar[1] = flight.rssi; }); -whenChanged(flight.altitude, 100, () => { gvar[2] = flight.altitude; }); +inav.events.whenChanged(inav.flight.vbat, 2, () => { inav.gvar[0] = inav.flight.vbat; }); +inav.events.whenChanged(inav.flight.rssi, 10, () => { inav.gvar[1] = inav.flight.rssi; }); +inav.events.whenChanged(inav.flight.altitude, 100, () => { inav.gvar[2] = inav.flight.altitude; }); + ``` ### Pattern 2: Periodic Beacon ```javascript // Boost VTX power briefly every 10 seconds -timer(500, 10000, () => { - override.vtx.power = 4; +inav.events.timer(500, 10000, () => { + inav.override.vtx.power = 4; }); + ``` ### Pattern 3: Adaptive Response ```javascript // React to rapid altitude changes -whenChanged(flight.altitude, 200, () => { - if (flight.altitude < 1000) { - override.throttleScale = 120; // Boost +inav.events.whenChanged(inav.flight.altitude, 200, () => { + if (inav.flight.altitude < 1000) { + inav.override.throttleScale = 120; // Boost } else { - override.throttleScale = 80; // Reduce + inav.override.throttleScale = 80; // Reduce } }); + ``` ## Troubleshooting diff --git a/docs/javascript_programming/TIMER_WHENCHANGED_IMPLEMENTATION.md b/docs/javascript_programming/TIMER_WHENCHANGED_IMPLEMENTATION.md index e26e96683c8..8befa685ff2 100644 --- a/docs/javascript_programming/TIMER_WHENCHANGED_IMPLEMENTATION.md +++ b/docs/javascript_programming/TIMER_WHENCHANGED_IMPLEMENTATION.md @@ -8,9 +8,10 @@ The `timer()` and `whenChanged()` functions provide advanced timing and change-d ### Syntax ```javascript -timer(onMs, offMs, () => { +inav.events.timer(onMs, offMs, () => { // actions }); + ``` ### Description @@ -23,12 +24,12 @@ Execute actions on a periodic timer with on/off cycling. The action executes dur ### Example ```javascript -const { override, timer } = inav; // Flash VTX power: ON for 1 second, OFF for 2 seconds, repeat -timer(1000, 2000, () => { - override.vtx.power = 4; +inav.events.timer(1000, 2000, () => { + inav.override.vtx.power = 4; }); + ``` **Generated Logic Conditions:** @@ -47,9 +48,10 @@ logic 1 1 0 25 0 0 0 0 4 0 # Set VTX power = 4 ### Syntax ```javascript -whenChanged(value, threshold, () => { +inav.events.whenChanged(value, threshold, () => { // actions }); + ``` ### Description @@ -62,12 +64,12 @@ Execute actions when a monitored value changes by more than the specified thresh ### Example ```javascript -const { flight, gvar, whenChanged } = inav; // Log altitude whenever it changes by 50cm or more -whenChanged(flight.altitude, 50, () => { - gvar[0] = flight.altitude; +inav.events.whenChanged(inav.flight.altitude, 50, () => { + inav.gvar[0] = inav.flight.altitude; }); + ``` **Generated Logic Conditions:** @@ -89,31 +91,33 @@ Both functions support perfect round-trip transpilation/decompilation: ### timer() Round-Trip ```javascript // Original JavaScript -timer(1000, 2000, () => { gvar[0] = 1; }); +inav.events.timer(1000, 2000, () => { inav.gvar[0] = 1; }); // Transpiled to logic conditions logic 0 1 -1 49 0 1000 0 2000 0 logic 1 1 0 18 0 0 0 0 1 0 // Decompiled back to JavaScript -timer(1000, 2000, () => { - gvar[0] = 1; +inav.events.timer(1000, 2000, () => { + inav.gvar[0] = 1; }); + ``` ### whenChanged() Round-Trip ```javascript // Original JavaScript -whenChanged(flight.altitude, 50, () => { gvar[0] = flight.altitude; }); +inav.events.whenChanged(inav.flight.altitude, 50, () => { inav.gvar[0] = inav.flight.altitude; }); // Transpiled to logic conditions logic 0 1 -1 50 2 12 0 50 0 logic 1 1 0 18 0 0 2 12 0 // Decompiled back to JavaScript -whenChanged(flight.altitude, 50, () => { - gvar[0] = flight.altitude; +inav.events.whenChanged(inav.flight.altitude, 50, () => { + inav.gvar[0] = inav.flight.altitude; }); + ``` ## API Definitions @@ -129,7 +133,7 @@ timer: { offMs: { type: 'number', unit: 'ms', desc: 'Duration to wait between executions' }, action: { type: 'function', desc: 'Action to execute during on-time' } }, - example: 'timer(1000, 5000, () => { override.vtx.power = 4; })' + example: 'inav.events.timer(1000, 5000, () => { inav.override.vtx.power = 4; })' }, whenChanged: { @@ -140,8 +144,9 @@ whenChanged: { threshold: { type: 'number', desc: 'Change threshold' }, action: { type: 'function', desc: 'Action to execute on change' } }, - example: 'whenChanged(flight.altitude, 100, () => { gvar[0] = flight.altitude; })' + example: 'inav.events.whenChanged(inav.flight.altitude, 100, () => { inav.gvar[0] = inav.flight.altitude; })' } + ``` ## See Also diff --git a/docs/javascript_programming/api_definitions_summary.md b/docs/javascript_programming/api_definitions_summary.md index 710af423808..a7e74bd3bcb 100644 --- a/docs/javascript_programming/api_definitions_summary.md +++ b/docs/javascript_programming/api_definitions_summary.md @@ -204,13 +204,15 @@ Once these files are created: const apiDefinitions = require('./../api/definitions/index.js'); this.inavAPI = this.buildAPIStructure(apiDefinitions); // No code changes needed! + ``` ### 2. Decompiler Auto-Updates ```javascript // decompiler.js automatically maps operands this.operandToProperty = this.buildOperandMapping(apiDefinitions); -// Decompiles FLIGHT(40) → flight.compassHeading automatically +// Decompiles FLIGHT(40) → inav.flight.compassHeading automatically + ``` ### 3. TypeScript Auto-Generation @@ -218,6 +220,7 @@ this.operandToProperty = this.buildOperandMapping(apiDefinitions); // types.js generates Monaco definitions const dts = generateTypeDefinitions(apiDefinitions); // IntelliSense shows all properties automatically + ``` ### 4. Adding New Properties @@ -230,6 +233,7 @@ newSensor: { desc: 'New sensor value', inavOperand: { type: 2, value: 50 } } + ``` 2. Done! Everything updates automatically: diff --git a/docs/javascript_programming/api_maintenance_guide.md b/docs/javascript_programming/api_maintenance_guide.md index 8e9c4c9f773..85804c1e8d3 100644 --- a/docs/javascript_programming/api_maintenance_guide.md +++ b/docs/javascript_programming/api_maintenance_guide.md @@ -56,6 +56,7 @@ module.exports = { } } }; + ``` ## What Uses These Definitions @@ -103,6 +104,7 @@ module.exports = { } } }; + ``` **2. Update `inav_constants.js` (if needed):** @@ -119,6 +121,7 @@ const FLIGHT_PARAM_NAMES = { // ... existing names ... [FLIGHT_PARAM.COMPASS_HEADING]: 'compassHeading' }; + ``` **3. That's it!** @@ -159,6 +162,7 @@ module.exports = { } } }; + ``` **2. Update `inav_constants.js`:** @@ -168,6 +172,7 @@ const OPERATION = { // ... existing operations ... OVERRIDE_VTX_FREQUENCY: 50 }; + ``` **3. Update `codegen.js` (manual):** @@ -176,7 +181,7 @@ Add code generation logic: ```javascript // In generateAction() method -if (stmt.target === 'override.vtx.frequency') { +if (stmt.target === 'inav.override.vtx.frequency') { return this.pushLogicCommand( OPERATION.OVERRIDE_VTX_FREQUENCY, { type: OPERAND_TYPE.VALUE, value: 0 }, @@ -184,6 +189,7 @@ if (stmt.target === 'override.vtx.frequency') { activatorId ); } + ``` ## Adding a New Top-Level API Object @@ -218,6 +224,7 @@ module.exports = { // ... more sensors }; + ``` **2. Update `js/transpiler/api/definitions/index.js`:** @@ -226,16 +233,17 @@ module.exports = { 'use strict'; module.exports = { - flight: require('./flight.js'), - override: require('./override.js'), + flight: require('./inav.flight.js'), + override: require('./inav.override.js'), rc: require('./rc.js'), gvar: require('./gvar.js'), - waypoint: require('./waypoint.js'), + waypoint: require('./inav.waypoint.js'), pid: require('./pid.js'), helpers: require('./helpers.js'), events: require('./events.js'), sensors: require('./sensors.js') // ADD THIS }; + ``` **3. Update TypeScript types in `types.js` generation:** @@ -245,6 +253,7 @@ The type generator should automatically pick it up, but verify: ```javascript // In generateTypeDefinitions() dts += generateInterfaceFromDefinition('sensors', apiDefinitions.sensors); + ``` ## Validation Checklist @@ -271,7 +280,6 @@ After modifying definitions: ```javascript // 1. Test semantic analysis const code = ` -const { sensors } = inav; if (sensors.acc) { // ... } @@ -288,6 +296,7 @@ const dts = generateTypeDefinitions(apiDefinitions); // 3. Test in Monaco Editor // Open configurator, verify autocomplete shows new properties + ``` ## Common Mistakes @@ -300,11 +309,12 @@ this.inavAPI = { properties: ['homeDistance', 'newProperty'] // Hard-coded! } }; + ``` ### āœ… Right: Edit definition file ```javascript -// DO THIS in flight.js: +// DO THIS in inav.flight.js: module.exports = { newProperty: { type: 'number', @@ -312,6 +322,7 @@ module.exports = { // ... } }; + ``` ### āŒ Wrong: Duplicating definitions @@ -324,6 +335,7 @@ const FLIGHT_PARAMS = { // analyzer.js - NO! properties: ['homeDistance'] + ``` ### āœ… Right: Use centralized definitions @@ -331,6 +343,7 @@ properties: ['homeDistance'] // DO THIS - import from definitions const apiDefinitions = require('./../api/definitions/index.js'); const flightDef = apiDefinitions.flight; + ``` ## File Dependencies @@ -378,6 +391,7 @@ this.inavAPI = { // After (using definitions) const apiDefinitions = require('./../api/definitions/index.js'); this.inavAPI = this.buildAPIStructure(apiDefinitions); + ``` ## Summary diff --git a/docs/javascript_programming/implementation_summary.md b/docs/javascript_programming/implementation_summary.md index ea23161d4fd..2f6e532ce8b 100644 --- a/docs/javascript_programming/implementation_summary.md +++ b/docs/javascript_programming/implementation_summary.md @@ -113,11 +113,11 @@ The INAV JavaScript Transpiler is a bidirectional JavaScript ↔ INAV Logic Cond **Input JavaScript:** ```javascript -const { flight, override } = inav; -if (flight.homeDistance > 100) { - override.vtx.power = 3; +if (inav.flight.homeDistance > 100) { + inav.override.vtx.power = 3; } + ``` **Output INAV Commands:** @@ -136,11 +136,11 @@ logic 1 1 0 25 0 0 0 50 0 **Output JavaScript:** ```javascript -const { flight, override } = inav; -if (flight.cellVoltage < 350) { - override.throttleScale = 50; +if (inav.flight.cellVoltage < 350) { + inav.override.throttleScale = 50; } + ``` ### Example 3: Full Round-Trip @@ -148,13 +148,14 @@ if (flight.cellVoltage < 350) { **Original Code:** ```javascript on.arm({ delay: 1 }, () => { - gvar[0] = flight.yaw; + inav.gvar[0] = inav.flight.yaw; }); -if (flight.homeDistance > 500) { - override.vtx.power = 4; - override.throttleScale = 75; +if (inav.flight.homeDistance > 500) { + inav.override.vtx.power = 4; + inav.override.throttleScale = 75; } + ``` **Transpiled → Saved to FC → Loaded from FC:** @@ -162,16 +163,16 @@ if (flight.homeDistance > 500) { // INAV Logic Conditions - Decompiled to JavaScript // Note: Comments, variable names, and some structure may be lost -const { flight, override, rc, gvar, on } = inav; on.arm({ delay: 1 }, () => { - gvar[0] = flight.yaw; + inav.gvar[0] = inav.flight.yaw; }); -if (flight.homeDistance > 500) { - override.vtx.power = 4; - override.throttleScale = 75; +if (inav.flight.homeDistance > 500) { + inav.override.vtx.power = 4; + inav.override.throttleScale = 75; } + ``` ## Known Limitations diff --git a/docs/javascript_programming/index.md b/docs/javascript_programming/index.md index 272d344eb7a..03f0f17fa0b 100644 --- a/docs/javascript_programming/index.md +++ b/docs/javascript_programming/index.md @@ -28,12 +28,12 @@ The INAV JavaScript transpiler converts JavaScript code into INAV logic conditio ### Basic Example ```javascript -const { flight, override } = inav; // Increase VTX power when far from home -if (flight.homeDistance > 500) { - override.vtx.power = 4; +if (inav.flight.homeDistance > 500) { + inav.override.vtx.power = 4; } + ``` ![VTX Power Control Example](example_vtx_power.png) From b3809856234453c0e2f7f2e17be093279974bc54 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 21 Dec 2025 00:39:45 -0600 Subject: [PATCH 44/67] Fix H743 USB MSC regression using standalone MSC mode MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Issue: USB Mass Storage mode broken on H743 in INAV 8.0.1+ due to USB library update v2.5.3 → v2.11.3. Windows shows 'Virtual COM Port in FS Mode' error instead of enumerating MSC device. Root Cause: H7 MSC initialization used VCP_Desc (CDC descriptor) then added MSC class. New USB library interprets this as composite mode but INAV wasn't configured for composite, causing descriptor conflicts that Windows rejects. Solution: Standalone MSC Mode (not composite) - Created MSC_Desc descriptor structure for pure MSC device - MSC mode now uses MSC descriptors (device class 0x00, PID 22314) - Normal VCP mode unchanged (still uses VCP_Desc) - No CDC functionality during MSC mode - Simpler than composite mode, no API changes needed Changes: - src/main/vcp_hal/usbd_desc.c: Add MSC_Desc and descriptor functions - src/main/vcp_hal/usbd_desc.h: Export MSC_Desc - src/main/drivers/usb_msc_h7xx.c: Use MSC_Desc instead of VCP_Desc Testing Results: āœ… USB enumeration works on Linux āœ… Device detected as 'STM32 Mass Storage in FS Mode' āœ… SCSI device created (sda) āœ… Size detected correctly (31.3 GB) āš ļø Requires SD card inserted for storage backend to work Benefits: - Normal VCP operation completely unaffected - MSC mode enumerates properly on Windows/Linux - No composite mode complexity - Matches F4 architecture (MSC-only mode) References: - Issue: https://github.com/iNavFlight/inav/issues/10800 --- src/main/drivers/usb_msc_h7xx.c | 4 +- src/main/vcp_hal/usbd_desc.c | 91 +++++++++++++++++++++++++++++++++ src/main/vcp_hal/usbd_desc.h | 4 ++ 3 files changed, 98 insertions(+), 1 deletion(-) diff --git a/src/main/drivers/usb_msc_h7xx.c b/src/main/drivers/usb_msc_h7xx.c index 9bd6bdc8b37..396a5951ba8 100644 --- a/src/main/drivers/usb_msc_h7xx.c +++ b/src/main/drivers/usb_msc_h7xx.c @@ -84,7 +84,9 @@ uint8_t mscStart(void) IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0, 0); IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0, 0); - USBD_Init(&USBD_Device, &VCP_Desc, 0); + // Use MSC descriptor for standalone MSC mode (not composite) + // This fixes Windows enumeration issue with new USB library v2.11.3 + USBD_Init(&USBD_Device, &MSC_Desc, 0); /** Regsiter class */ USBD_RegisterClass(&USBD_Device, USBD_MSC_CLASS); diff --git a/src/main/vcp_hal/usbd_desc.c b/src/main/vcp_hal/usbd_desc.c index 48806761364..62834e83382 100644 --- a/src/main/vcp_hal/usbd_desc.c +++ b/src/main/vcp_hal/usbd_desc.c @@ -91,6 +91,24 @@ USBD_DescriptorsTypeDef VCP_Desc = { USBD_VCP_InterfaceStrDescriptor, }; +#ifdef USE_USB_MSC +/* MSC-specific descriptor functions */ +static uint8_t *USBD_MSC_DeviceDescriptorCallback(USBD_SpeedTypeDef speed, uint16_t *length); +static uint8_t *USBD_MSC_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); +static uint8_t *USBD_MSC_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); +static uint8_t *USBD_MSC_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length); + +USBD_DescriptorsTypeDef MSC_Desc = { + USBD_MSC_DeviceDescriptorCallback, + USBD_VCP_LangIDStrDescriptor, // Reuse VCP LangID + USBD_VCP_ManufacturerStrDescriptor, // Reuse VCP Manufacturer + USBD_MSC_ProductStrDescriptor, // MSC-specific + USBD_VCP_SerialStrDescriptor, // Reuse VCP Serial + USBD_MSC_ConfigStrDescriptor, // MSC-specific + USBD_MSC_InterfaceStrDescriptor, // MSC-specific +}; +#endif + /* USB Standard Device Descriptor */ #if defined ( __ICCARM__ ) /*!< IAR Compiler */ #pragma data_alignment=4 @@ -338,4 +356,77 @@ static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len) pbuf[ 2* idx + 1] = 0; } } + +#ifdef USE_USB_MSC +/** + * @brief Returns the MSC device descriptor. + * @param speed: Current device speed + * @param length: Pointer to data length variable + * @retval Pointer to descriptor buffer + */ +static uint8_t *USBD_MSC_DeviceDescriptorCallback(USBD_SpeedTypeDef speed, uint16_t *length) +{ + (void)speed; + *length = sizeof(USBD_MSC_DeviceDesc); + return (uint8_t*)USBD_MSC_DeviceDesc; +} + +/** + * @brief Returns the MSC product string descriptor. + * @param speed: Current device speed + * @param length: Pointer to data length variable + * @retval Pointer to descriptor buffer + */ +static uint8_t *USBD_MSC_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) +{ + if (speed == USBD_SPEED_HIGH) + { + USBD_GetString((uint8_t *)"STM32 Mass Storage in HS Mode", USBD_StrDesc, length); + } + else + { + USBD_GetString((uint8_t *)"STM32 Mass Storage in FS Mode", USBD_StrDesc, length); + } + return USBD_StrDesc; +} + +/** + * @brief Returns the MSC configuration string descriptor. + * @param speed: Current device speed + * @param length: Pointer to data length variable + * @retval Pointer to descriptor buffer + */ +static uint8_t *USBD_MSC_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) +{ + if (speed == USBD_SPEED_HIGH) + { + USBD_GetString((uint8_t *)"MSC Config", USBD_StrDesc, length); + } + else + { + USBD_GetString((uint8_t *)"MSC Config", USBD_StrDesc, length); + } + return USBD_StrDesc; +} + +/** + * @brief Returns the MSC interface string descriptor. + * @param speed: Current device speed + * @param length: Pointer to data length variable + * @retval Pointer to descriptor buffer + */ +static uint8_t *USBD_MSC_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length) +{ + if (speed == USBD_SPEED_HIGH) + { + USBD_GetString((uint8_t *)"MSC Interface", USBD_StrDesc, length); + } + else + { + USBD_GetString((uint8_t *)"MSC Interface", USBD_StrDesc, length); + } + return USBD_StrDesc; +} +#endif /* USE_USB_MSC */ + /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/vcp_hal/usbd_desc.h b/src/main/vcp_hal/usbd_desc.h index 3baad094f40..57d50c4da30 100644 --- a/src/main/vcp_hal/usbd_desc.h +++ b/src/main/vcp_hal/usbd_desc.h @@ -60,6 +60,10 @@ /* Exported functions ------------------------------------------------------- */ extern USBD_DescriptorsTypeDef VCP_Desc; +#ifdef USE_USB_MSC +extern USBD_DescriptorsTypeDef MSC_Desc; +#endif + #endif /* __USBD_DESC_H */ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ From 146ff5616ca7270633dd283732742b88440301e6 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 21 Dec 2025 02:02:33 -0600 Subject: [PATCH 45/67] Fix H7 SDIO alignment issue and add retry logic This commit fixes two critical issues with H7 SDIO SD card access: 1. **USB MSC alignment bug**: H7 SDIO DMA requires 32-byte aligned buffers, but the USB MSC library's bot_data buffer is only 16-byte aligned. This caused all USB MSC read/write operations to fail with SD_ADDR_MISALIGNED errors. Fix: Use an aligned intermediate buffer for H7+SDIO in USB MSC mode. 2. **Aggressive error handling**: Any SDIO DMA failure immediately triggered a full card reset, causing recording gaps and reliability issues. This was particularly problematic when USB interrupts interfered with SDIO DMA. Fix: Retry operations up to 3 times with 1ms delays before resetting card. Technical details: - Added __attribute__((aligned(32))) buffer for H7 USB MSC SDIO operations - Added operationRetries counter and SDCARD_MAX_OPERATION_RETRIES constant - Both read and write paths now retry transient failures - Retry counter reset on successful operations and card init This should significantly improve H7 SDIO reliability for both blackbox logging and USB mass storage mode. Fixes #10800 --- src/main/drivers/sdcard/sdcard_impl.h | 2 ++ src/main/drivers/sdcard/sdcard_sdio.c | 32 +++++++++++++++++-- src/main/msc/usbd_storage_sd_spi.c | 44 +++++++++++++++++++++++++-- 3 files changed, 72 insertions(+), 6 deletions(-) diff --git a/src/main/drivers/sdcard/sdcard_impl.h b/src/main/drivers/sdcard/sdcard_impl.h index 9fcb9a46902..3eba6095904 100644 --- a/src/main/drivers/sdcard/sdcard_impl.h +++ b/src/main/drivers/sdcard/sdcard_impl.h @@ -32,6 +32,7 @@ #define SDCARD_TIMEOUT_INIT_MILLIS 200 #define SDCARD_MAX_CONSECUTIVE_FAILURES 8 +#define SDCARD_MAX_OPERATION_RETRIES 3 typedef enum { // In these states we run at the initialization 400kHz clockspeed: @@ -62,6 +63,7 @@ typedef struct sdcard_t { uint32_t operationStartTime; uint8_t failureCount; + uint8_t operationRetries; // Retry count for current operation before reset uint8_t version; bool highCapacity; diff --git a/src/main/drivers/sdcard/sdcard_sdio.c b/src/main/drivers/sdcard/sdcard_sdio.c index e0fcb3f05d6..d7cd8ff3c54 100644 --- a/src/main/drivers/sdcard/sdcard_sdio.c +++ b/src/main/drivers/sdcard/sdcard_sdio.c @@ -460,18 +460,29 @@ static sdcardOperationStatus_e sdcardSdio_writeBlock(uint32_t blockIndex, uint8_ sdcard.state = SDCARD_STATE_SENDING_WRITE; if (SD_WriteBlocks_DMA(blockIndex, (uint32_t*) buffer, 512, block_count) != SD_OK) { - /* Our write was rejected! This could be due to a bad address but we hope not to attempt that, so assume - * the card is broken and needs reset. + /* Our write was rejected! Try a few times before giving up. + * This handles transient DMA/bus issues without full card reset. */ + if (sdcard.operationRetries < SDCARD_MAX_OPERATION_RETRIES) { + sdcard.operationRetries++; + // Brief delay before retry + delay(1); + return SDCARD_OPERATION_BUSY; + } + + // Max retries exceeded, reset card + sdcard.operationRetries = 0; sdcardSdio_reset(); // Announce write failure: if (sdcard.pendingOperation.callback) { sdcard.pendingOperation.callback(SDCARD_BLOCK_OPERATION_WRITE, sdcard.pendingOperation.blockIndex, NULL, sdcard.pendingOperation.callbackData); } - return SDCARD_OPERATION_FAILURE; + return SDCARD_OPERATION_FAILURE; } + // Success - reset retry counter + sdcard.operationRetries = 0; return SDCARD_OPERATION_IN_PROGRESS; } @@ -545,8 +556,22 @@ static bool sdcardSdio_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_op sdcard.state = SDCARD_STATE_READING; sdcard.operationStartTime = millis(); + // Success - reset retry counter + sdcard.operationRetries = 0; return true; } else { + /* Read was rejected! Try a few times before giving up. + * This handles transient DMA/bus issues without full card reset. + */ + if (sdcard.operationRetries < SDCARD_MAX_OPERATION_RETRIES) { + sdcard.operationRetries++; + // Brief delay before retry + delay(1); + return false; + } + + // Max retries exceeded, reset card + sdcard.operationRetries = 0; sdcardSdio_reset(); if (sdcard.pendingOperation.callback) { sdcard.pendingOperation.callback( @@ -601,6 +626,7 @@ void sdcardSdio_init(void) sdcard.operationStartTime = millis(); sdcard.state = SDCARD_STATE_RESET; sdcard.failureCount = 0; + sdcard.operationRetries = 0; } /** diff --git a/src/main/msc/usbd_storage_sd_spi.c b/src/main/msc/usbd_storage_sd_spi.c index 4573d156bd8..0e30e1e0df1 100644 --- a/src/main/msc/usbd_storage_sd_spi.c +++ b/src/main/msc/usbd_storage_sd_spi.c @@ -29,6 +29,7 @@ /* Includes ------------------------------------------------------------------*/ #include #include +#include #include "platform.h" #include "common/utils.h" @@ -39,6 +40,7 @@ #include "drivers/light_led.h" #include "drivers/io.h" #include "drivers/bus_spi.h" +#include "drivers/time.h" /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ @@ -56,6 +58,12 @@ #define STORAGE_BLK_NBR 0x10000 #define STORAGE_BLK_SIZ 0x200 +// H7 SDIO DMA requires 32-byte aligned buffers +// USB MSC bot_data buffer is only 16-byte aligned, so we need an intermediate buffer +#if defined(STM32H7) && defined(USE_SDCARD_SDIO) +__attribute__((aligned(32))) static uint8_t alignedBuffer[512]; +#endif + static int8_t STORAGE_Init (uint8_t lun); #ifdef USE_HAL_DRIVER @@ -143,10 +151,21 @@ static int8_t STORAGE_Init (uint8_t lun) { UNUSED(lun); LED0_OFF; - sdcard_init(); - while (sdcard_poll() == 0); + + // Only initialize if not already initialized (e.g., by blackbox) + if (!sdcard_isInitialized()) { + sdcard_init(); + } + + // Poll with timeout to avoid infinite loop + uint32_t timeout = 0; + while (sdcard_poll() == 0 && timeout < 1000) { + timeout++; + delay(1); + } + LED0_ON; - return 0; + return (timeout < 1000) ? 0 : -1; } /******************************************************************************* @@ -213,9 +232,18 @@ static int8_t STORAGE_Read (uint8_t lun, UNUSED(lun); LED1_ON; for (int i = 0; i < blk_len; i++) { +#if defined(STM32H7) && defined(USE_SDCARD_SDIO) + // H7 SDIO DMA requires 32-byte aligned buffers + // USB MSC buffer may not be aligned, so use intermediate buffer + while (sdcard_readBlock(blk_addr + i, alignedBuffer, NULL, 0) == 0) + sdcard_poll(); + while (sdcard_poll() == 0); + memcpy(buf + (512 * i), alignedBuffer, 512); +#else while (sdcard_readBlock(blk_addr + i, buf + (512 * i), NULL, 0) == 0) sdcard_poll(); while (sdcard_poll() == 0); +#endif } LED1_OFF; return 0; @@ -235,10 +263,20 @@ static int8_t STORAGE_Write (uint8_t lun, UNUSED(lun); LED1_ON; for (int i = 0; i < blk_len; i++) { +#if defined(STM32H7) && defined(USE_SDCARD_SDIO) + // H7 SDIO DMA requires 32-byte aligned buffers + // USB MSC buffer may not be aligned, so use intermediate buffer + memcpy(alignedBuffer, buf + (i * 512), 512); + while (sdcard_writeBlock(blk_addr + i, alignedBuffer, NULL, 0) != SDCARD_OPERATION_IN_PROGRESS) { + sdcard_poll(); + } + while (sdcard_poll() == 0); +#else while (sdcard_writeBlock(blk_addr + i, buf + (i * 512), NULL, 0) != SDCARD_OPERATION_IN_PROGRESS) { sdcard_poll(); } while (sdcard_poll() == 0); +#endif } LED1_OFF; return 0; From 01249161c947ac12c6f3d2e85eb99035c818916c Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 21 Dec 2025 02:16:07 -0600 Subject: [PATCH 46/67] Add timeout protection to USB MSC read/write loops Implements Qodo bot suggestion to prevent infinite hangs if SD card becomes unresponsive during USB MSC operations. Changes: - Added 5-second timeout to all polling loops in STORAGE_Read() - Added 5-second timeout to all polling loops in STORAGE_Write() - Returns error (-1) to USB host if timeout occurs - Timeout applies to both 'waiting for operation to start' and 'waiting for operation to complete' phases This prevents system hangs when: - SD card becomes unresponsive - SDIO DMA completion interrupts are blocked - Card is removed during operation Timeout is generous (5 seconds per block) to handle slow cards while still providing protection against total system freeze. --- src/main/msc/usbd_storage_sd_spi.c | 68 +++++++++++++++++++++++++++--- 1 file changed, 62 insertions(+), 6 deletions(-) diff --git a/src/main/msc/usbd_storage_sd_spi.c b/src/main/msc/usbd_storage_sd_spi.c index 0e30e1e0df1..26a38e00b6a 100644 --- a/src/main/msc/usbd_storage_sd_spi.c +++ b/src/main/msc/usbd_storage_sd_spi.c @@ -232,17 +232,46 @@ static int8_t STORAGE_Read (uint8_t lun, UNUSED(lun); LED1_ON; for (int i = 0; i < blk_len; i++) { + uint32_t timeout; #if defined(STM32H7) && defined(USE_SDCARD_SDIO) // H7 SDIO DMA requires 32-byte aligned buffers // USB MSC buffer may not be aligned, so use intermediate buffer - while (sdcard_readBlock(blk_addr + i, alignedBuffer, NULL, 0) == 0) + timeout = 0; + while (sdcard_readBlock(blk_addr + i, alignedBuffer, NULL, 0) == 0) { sdcard_poll(); - while (sdcard_poll() == 0); + if (++timeout > 5000) { + LED1_OFF; + return -1; // Timeout waiting for read to start + } + delay(1); + } + timeout = 0; + while (sdcard_poll() == 0) { + if (++timeout > 5000) { + LED1_OFF; + return -1; // Timeout waiting for read to complete + } + delay(1); + } memcpy(buf + (512 * i), alignedBuffer, 512); #else - while (sdcard_readBlock(blk_addr + i, buf + (512 * i), NULL, 0) == 0) + timeout = 0; + while (sdcard_readBlock(blk_addr + i, buf + (512 * i), NULL, 0) == 0) { sdcard_poll(); - while (sdcard_poll() == 0); + if (++timeout > 5000) { + LED1_OFF; + return -1; // Timeout waiting for read to start + } + delay(1); + } + timeout = 0; + while (sdcard_poll() == 0) { + if (++timeout > 5000) { + LED1_OFF; + return -1; // Timeout waiting for read to complete + } + delay(1); + } #endif } LED1_OFF; @@ -263,19 +292,46 @@ static int8_t STORAGE_Write (uint8_t lun, UNUSED(lun); LED1_ON; for (int i = 0; i < blk_len; i++) { + uint32_t timeout; #if defined(STM32H7) && defined(USE_SDCARD_SDIO) // H7 SDIO DMA requires 32-byte aligned buffers // USB MSC buffer may not be aligned, so use intermediate buffer memcpy(alignedBuffer, buf + (i * 512), 512); + timeout = 0; while (sdcard_writeBlock(blk_addr + i, alignedBuffer, NULL, 0) != SDCARD_OPERATION_IN_PROGRESS) { sdcard_poll(); + if (++timeout > 5000) { + LED1_OFF; + return -1; // Timeout waiting for write to start + } + delay(1); + } + timeout = 0; + while (sdcard_poll() == 0) { + if (++timeout > 5000) { + LED1_OFF; + return -1; // Timeout waiting for write to complete + } + delay(1); } - while (sdcard_poll() == 0); #else + timeout = 0; while (sdcard_writeBlock(blk_addr + i, buf + (i * 512), NULL, 0) != SDCARD_OPERATION_IN_PROGRESS) { sdcard_poll(); + if (++timeout > 5000) { + LED1_OFF; + return -1; // Timeout waiting for write to start + } + delay(1); + } + timeout = 0; + while (sdcard_poll() == 0) { + if (++timeout > 5000) { + LED1_OFF; + return -1; // Timeout waiting for write to complete + } + delay(1); } - while (sdcard_poll() == 0); #endif } LED1_OFF; From 535291b6427c3dff64613bf89ce63854e75ab282 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 21 Dec 2025 10:58:34 -0600 Subject: [PATCH 47/67] docs: Add branch propagation section and simplify fork update Apply Qodo bot suggestions to improve documentation: 1. Add "Propagating Changes Between Maintenance Branches" section - Explains how changes should be merged forward from current to next version - Prevents regressions and lost fixes in future major versions - Provides clear example for maintainers 2. Simplify fork update workflow - Replace multi-step checkout/merge/push with direct push command - More efficient: git push origin upstream/maintenance-9.x:maintenance-9.x - No local checkout needed --- docs/development/Development.md | 23 ++++++++++++++++++++--- 1 file changed, 20 insertions(+), 3 deletions(-) diff --git a/docs/development/Development.md b/docs/development/Development.md index ced9571f2fe..de8fbdecbfe 100755 --- a/docs/development/Development.md +++ b/docs/development/Development.md @@ -174,6 +174,23 @@ When creating a pull request, target the appropriate branch: 4. After final release, the maintenance branch is periodically merged into `master` 5. The cycle continues with the maintenance branch receiving new changes for the next release +### Propagating Changes Between Maintenance Branches + +Changes committed to the current version branch should be merged forward to the next major version branch to prevent regressions. + +**Maintainer workflow:** +- Changes merged to `maintenance-9.x` should be regularly merged into `maintenance-10.x` +- This ensures fixes and features aren't lost when the next major version is released +- Prevents users from experiencing bugs in v10.0 that were already fixed in v9.x + +**Example:** +```bash +# Merge changes from current to next major version +git checkout maintenance-10.x +git merge maintenance-9.x +git push upstream maintenance-10.x +``` + ### Example Timeline Current state (example): @@ -208,7 +225,7 @@ When updating your fork: ```bash # Get the latest maintenance branch changes git fetch upstream -git checkout maintenance-9.x -git merge upstream/maintenance-9.x -git push origin maintenance-9.x + +# Push directly from upstream to your fork (no local checkout needed) +git push origin upstream/maintenance-9.x:maintenance-9.x ``` From fd9ca51a0586c5a3c0a73074d7a63f3babdb2cd0 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 21 Dec 2025 16:53:41 -0600 Subject: [PATCH 48/67] Docs: Add new JavaScript features (PID, flight modes, let/const, ternary) Adds documentation for new INAV 9.0 JavaScript programming features: New Features: - PID controller output access (inav.pid[0-3].output) - Flight mode detection (inav.flight.mode.poshold, .rth, etc.) - Let/const variables for compile-time named expressions - Ternary operator for conditional value assignment Changes: - Add Variables section with let/const and ternary operator docs - Update Available Objects to list PID and flight modes - Add Flight Mode Detection subsection with examples - Add PID Controller Outputs subsection with examples - Update index.md feature list - Update Tips section for consistency All examples use namespaced syntax (inav.flight.*, inav.override.*, etc.) for clarity and explicitness. --- .../JAVASCRIPT_PROGRAMMING_GUIDE.md | 97 ++++++++++++++++--- docs/javascript_programming/index.md | 9 +- 2 files changed, 91 insertions(+), 15 deletions(-) diff --git a/docs/javascript_programming/JAVASCRIPT_PROGRAMMING_GUIDE.md b/docs/javascript_programming/JAVASCRIPT_PROGRAMMING_GUIDE.md index 9c7dad4a8a9..fedda8bb7ac 100644 --- a/docs/javascript_programming/JAVASCRIPT_PROGRAMMING_GUIDE.md +++ b/docs/javascript_programming/JAVASCRIPT_PROGRAMMING_GUIDE.md @@ -198,28 +198,101 @@ inav.events.sticky( --- +## Variables + +### Let/Const Variables + +Use `let` or `const` to define reusable expressions that are compiled into the logic: + +```javascript +// Define reusable calculations +let distanceThreshold = 500; +let altitudeLimit = 100; +let combinedCondition = inav.flight.homeDistance > distanceThreshold && inav.flight.altitude > altitudeLimit; + +// Use in conditions +if (combinedCondition) { + inav.override.vtx.power = 4; +} +``` + +**Benefits:** +- Makes code more readable with named values +- Compiler automatically optimizes duplicate expressions +- Variables preserve their custom names through compile/decompile cycles + +**Important:** `let`/`const` variables are **compile-time substituted**, not runtime variables. For runtime state, use `inav.gvar[]`. + +### Ternary Operator + +Use ternary expressions for conditional values: + +```javascript +// Assign based on condition +let throttleLimit = inav.flight.cellVoltage < 330 ? 25 : 50; + +if (inav.flight.cellVoltage < 350) { + inav.override.throttleScale = throttleLimit; +} + +// Inline in expressions +inav.override.vtx.power = inav.flight.homeDistance > 500 ? 4 : 2; +``` + +**Use when:** You need conditional value assignment in a single expression. + +--- + ## Available Objects +The `inav` namespace provides access to all flight controller data and control functions: + +- `inav.flight` - Flight telemetry (including `flight.mode.*`) +- `inav.override` - Override flight parameters +- `inav.rc` - RC channels +- `inav.gvar` - Global variables (0-7) +- `inav.pid` - Programming PID outputs (`pid[0-3].output`) +- `inav.waypoint` - Waypoint navigation +- `inav.events.edge` - Edge detection +- `inav.events.sticky` - Latching conditions +- `inav.events.delay` - Delayed execution + +### Flight Mode Detection + +Check which flight modes are currently active via `inav.flight.mode.*`: + +```javascript +if (inav.flight.mode.poshold === 1) { + inav.gvar[0] = 1; // Flag: in position hold +} + +if (inav.flight.mode.rth === 1) { + inav.override.vtx.power = 4; // Max power during RTH +} +``` + +**Available modes:** `failsafe`, `manual`, `rth`, `poshold`, `cruise`, `althold`, `angle`, `horizon`, `air`, `acro`, `courseHold`, `waypointMission`, `user1` through `user4` + +### PID Controller Outputs + +Read output values from the 4 programming PID controllers (configured in Programming PID tab): + ```javascript -const { - flight, // Flight telemetry - override, // Override flight parameters - rc, // RC channels - gvar, // Global variables (0-7) - waypoint, // Waypoint navigation - edge, // Edge detection - sticky, // Latching conditions - delay // Delayed execution -} = inav; +if (inav.pid[0].output > 500) { + inav.override.throttle = 1600; +} +inav.gvar[0] = inav.pid[0].output; // Store for OSD display ``` +**Available:** `inav.pid[0].output` through `inav.pid[3].output` + --- ## Tips -1. **Initialize variables on arm** using `edge()` with `flight.armTimer > 1000` -2. **Use gvars for state** - they persist between logic condition evaluations +1. **Initialize variables on arm** using `inav.events.edge()` with `inav.flight.armTimer > 1000` +2. **Use inav.gvar for state** - they persist between logic condition evaluations 3. **edge() duration = 0** means instant trigger on condition becoming true 4. **edge() duration > 0** adds debounce time 5. **if statements are continuous** - they execute every cycle diff --git a/docs/javascript_programming/index.md b/docs/javascript_programming/index.md index 03f0f17fa0b..ce8ad26dd27 100644 --- a/docs/javascript_programming/index.md +++ b/docs/javascript_programming/index.md @@ -178,15 +178,18 @@ Instructions for: - Waypoint navigation **JavaScript Features:** -- `const` destructuring: `const { flight, override } = inav;` -- `let` variables: compile-time constant substitution +- Namespaced API access: `inav.flight.*`, `inav.override.*`, `inav.events.*` +- `let`/`const` variables: compile-time constant substitution - `var` variables: allocated to global variables +- Ternary operator: `condition ? value1 : value2` - Arrow functions: `() => condition` -- Object property access: `flight.altitude`, `rc[0].value` +- Object property access: `inav.flight.altitude`, `inav.rc[0].value` - Binary expressions: `+`, `-`, `*`, `/`, `%` - Comparison operators: `>`, `<`, `===` - Logical operators: `&&`, `||`, `!` - Math methods: `Math.min()`, `Math.max()`, `Math.sin()`, etc. +- Flight mode detection: `inav.flight.mode.poshold`, `inav.flight.mode.rth`, etc. +- PID controller outputs: `inav.pid[0-3].output` ### Validation From b7bfdeed541486afdb5ba927980a18733b3d8cb5 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Tue, 23 Dec 2025 09:11:01 -0600 Subject: [PATCH 49/67] BLUEBERRYF435WING: Disable dynamic notch filter by default This wing target is performance-constrained and wing aircraft typically don't benefit from dynamic notch filtering, which is primarily designed for detecting and filtering multirotor motor noise. Disabling the dynamic notch filter by default reduces CPU overhead and improves task scheduling margin on this board. --- src/main/target/BLUEBERRYF435WING/config.c | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/main/target/BLUEBERRYF435WING/config.c b/src/main/target/BLUEBERRYF435WING/config.c index 050bfa4e750..2c6de82ad87 100644 --- a/src/main/target/BLUEBERRYF435WING/config.c +++ b/src/main/target/BLUEBERRYF435WING/config.c @@ -30,6 +30,7 @@ #include "fc/fc_msp_box.h" #include "io/serial.h" #include "io/piniobox.h" +#include "sensors/gyro.h" void targetConfiguration(void) { @@ -38,4 +39,11 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].msp_baudrateIndex = BAUD_115200; //pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + +#ifdef USE_DYNAMIC_FILTERS + // Disable dynamic notch filter by default (performance optimization for wing) + // This board is performance-constrained and wing aircraft typically don't need + // dynamic notch filtering (designed for multirotor motor noise) + gyroConfigMutable()->dynamicGyroNotchEnabled = 0; +#endif } From e6306f830ade47be6259f3a353e8d14151ed1403 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Tue, 23 Dec 2025 21:07:41 -0600 Subject: [PATCH 50/67] Include cygwin1.dll in Windows SITL artifact MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Adds cygwin1.dll to the Windows SITL build artifact so users don't need Cygwin installed to run the SITL executable. Cherry-picked from PR #11133. šŸ¤– Generated with [Claude Code](https://claude.com/claude-code) Co-Authored-By: Claude Opus 4.5 --- .github/workflows/ci.yml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 78896ddf5d3..bf911321f14 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -256,11 +256,15 @@ jobs: for f in ./build_SITL/*_SITL.exe; do mv $f $(echo $f | sed -e 's/_[0-9]\+\.[0-9]\+\.[0-9]\+//') done + - name: Copy cygwin1.dll + run: cp /bin/cygwin1.dll ./build_SITL/ - name: Upload artifacts uses: actions/upload-artifact@v4 with: name: ${{ env.BUILD_NAME }}_SITL-WIN - path: ./build_SITL/*.exe + path: | + ./build_SITL/*.exe + ./build_SITL/cygwin1.dll test: #needs: [build] From d890dd13b9584777d472bdd447a2687fc8e10715 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Wed, 24 Dec 2025 15:54:33 -0600 Subject: [PATCH 51/67] Add maintenance-9.x to nightly build workflow This enables automatic pre-release builds when commits are pushed to the maintenance-9.x branch, providing complete firmware artifacts for RC releases. --- .github/workflows/nightly-build.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/nightly-build.yml b/.github/workflows/nightly-build.yml index 033b492b0f1..51dd16650e5 100644 --- a/.github/workflows/nightly-build.yml +++ b/.github/workflows/nightly-build.yml @@ -2,11 +2,12 @@ name: Build pre-release # Don't enable CI on push, just on PR. If you # are working on the main repo and want to trigger # a CI build submit a draft PR. -on: +on: push: branches: - master - maintenance-8.x.x + - maintenance-9.x paths: - 'src/**' - '.github/**' From ba2e80017ce762370410fad37906bda165a52da6 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 28 Dec 2025 07:08:09 +0000 Subject: [PATCH 52/67] Update OSD elements in documentation --- docs/OSD.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/OSD.md b/docs/OSD.md index e64aaef9d9b..44084266f8f 100644 --- a/docs/OSD.md +++ b/docs/OSD.md @@ -200,6 +200,7 @@ Here are the OSD Elements provided by INAV. | 165 | OSD_V_DIST_TO_FENCE | 8.0.0 | | | 166 | OSD_NAV_FW_ALT_CONTROL_RESPONSE | 8.0.0 | | | 167 | OSD_NAV_MIN_GROUND_SPEED | 9.0.0 | | +| 168 | OSD_THROTTLE_GAUGE | 9.0.0 | | # Pilot Logos From 402c2d5f15b2ec17d162b583de5beba34ac55f40 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Wed, 31 Dec 2025 02:23:06 -0600 Subject: [PATCH 53/67] Fix blackbox MOTORS condition mismatch causing null byte padding MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Problem: - Field definitions use AT_LEAST_MOTORS_N (checks motorCount AND flag) - I-frame write used MOTORS (checks flag only) - When motorCount=0 and flag=true: header declares 0 fields, I-frame writes 1 byte - motor[0] - getThrottleIdleValue() = 0 - 0 = 0 → encodes as 0x00 - Decoder expects frame marker, finds null byte → catastrophic failure Fix: - Change I-frame write from FLIGHT_LOG_FIELD_CONDITION_MOTORS to FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 - Change P-frame write for consistency - Now matches field definition condition exactly Testing: - Board with motorCount=0, MOTORS flag enabled - Before: 207 decoder failures (0.050s duration) - After: 3 decoder failures (12s duration) - matches baseline Files: - src/main/blackbox/blackbox.c lines 1079, 1346 šŸ¤– Generated with [Claude Code](https://claude.com/claude-code) Co-Authored-By: Claude Sonnet 4.5 --- src/main/blackbox/blackbox.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 1027f25379d..e4c2afb3eec 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -987,7 +987,7 @@ static void writeIntraframe(void) blackboxWriteSignedVBArray(blackboxCurrent->debug, DEBUG32_VALUE_COUNT); } - if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MOTORS)) { + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1)) { //Motors can be below minthrottle when disarmed, but that doesn't happen much blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - getThrottleIdleValue()); @@ -1254,7 +1254,7 @@ static void writeInterframe(void) blackboxWriteArrayUsingAveragePredictor32(offsetof(blackboxMainState_t, debug), DEBUG32_VALUE_COUNT); } - if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MOTORS)) { + if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1)) { blackboxWriteArrayUsingAveragePredictor16(offsetof(blackboxMainState_t, motor), getMotorCount()); } From 4329d4fa5e6a68504b5cf24bea9f6047fa00ce5c Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Wed, 31 Dec 2025 11:17:48 -0600 Subject: [PATCH 54/67] Add prominent download links to README MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit This change makes it easier for users to find and download INAV Configurator and firmware by adding a dedicated Downloads section near the top of the README. Previously, download links were buried in the Tools section lower in the document, requiring users to scroll and search. The new Downloads section appears right after the Community section, making it immediately visible to new users. Benefits: - Reduces user friction - fewer clicks to find downloads - Improves user experience for new users - Links use /releases/latest URLs that automatically show the latest version - Clear instructions to select platform from Assets section šŸ¤– Generated with [Claude Code](https://claude.com/claude-code) Co-Authored-By: Claude Sonnet 4.5 --- readme.md | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/readme.md b/readme.md index 16401701e1f..b8dbadf3909 100644 --- a/readme.md +++ b/readme.md @@ -51,6 +51,20 @@ Fly safe, fly smart with INAV 7.1 and a compass by your side! * [INAV Discord Server](https://discord.gg/peg2hhbYwN) * [INAV Official on Facebook](https://www.facebook.com/groups/INAVOfficial) +## Downloads + +### INAV Configurator + +**Get the latest version:** **[Download INAV Configurator](https://github.com/iNavFlight/inav-configurator/releases/latest)** - Available for Windows, macOS, and Linux + +The INAV Configurator is the official desktop application for configuring your INAV flight controller. Choose your platform from the Assets section on the releases page. + +### INAV Firmware + +**Get the latest firmware:** **[Download INAV Firmware](https://github.com/iNavFlight/inav/releases/latest)** + +Download the latest INAV flight controller firmware. Flash it to your flight controller using the configurator. + ## Features * Runs on the most popular F4, AT32, F7 and H7 flight controllers From 9ff99432e9afbb819b3f6bea82c45436e84e7c8b Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 3 Jan 2026 00:14:13 -0600 Subject: [PATCH 55/67] Add GPS-based pitot sensor validation with automatic fallback Implements pitot sensor validation by comparing hardware pitot readings against virtual airspeed (GPS + wind estimator). Detects blocked or failed pitot tubes and automatically falls back to GPS-based airspeed. Features: - Compares pitot against virtual airspeed (wind-corrected, not raw GPS) - Wide thresholds (30%-200%) catch gross failures while avoiding false positives - Sustained failure detection (1 second) before declaring sensor failed - Automatic fallback to GPS airspeed when pitot fails validation - OSD warning displays "PITOT FAIL" when sensor invalid - Automatic recovery after 0.5 seconds of good readings - Conservative approach: only validates when GPS available and moving >7 m/s Safety improvements: - Detects blocked pitot tubes (forgotten cover, insects, ice) - Prevents dangerous high gains with invalid pitot data - Maintains aircraft controllability when pitot fails - Clear pilot awareness via OSD warning Addresses GitHub issue #11208 --- src/main/io/osd.c | 10 +++ src/main/sensors/pitotmeter.c | 152 ++++++++++++++++++++++++++++++++++ src/main/sensors/pitotmeter.h | 1 + 3 files changed, 163 insertions(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index c7a40e982cc..6ad55632c17 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -6568,6 +6568,16 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff) } } #endif + +#if defined(USE_PITOT) + // Pitot sensor validation failure (blocked/failed pitot tube) + if (sensors(SENSOR_PITOT) && detectedSensors[SENSOR_INDEX_PITOT] != PITOT_VIRTUAL) { + if (osdCheckWarning(pitotHasFailed(), warningFlagID <<= 1, &warningsCount)) { + messages[messageCount++] = "PITOT FAIL"; + } + } +#endif + // Vibration levels TODO - needs better vibration measurement to be useful // const float vibrationLevel = accGetVibrationLevel(); // warningCondition = vibrationLevel > 1.5f; diff --git a/src/main/sensors/pitotmeter.c b/src/main/sensors/pitotmeter.c index edcc5b9219d..ce0f65df64a 100755 --- a/src/main/sensors/pitotmeter.c +++ b/src/main/sensors/pitotmeter.c @@ -48,6 +48,13 @@ #include "sensors/barometer.h" #include "sensors/sensors.h" +#include "io/gps.h" + +#ifdef USE_WIND_ESTIMATOR +#include "flight/wind_estimator.h" +#include "navigation/navigation.h" +#include "navigation/navigation_private.h" +#endif //#include "build/debug.h" @@ -58,6 +65,12 @@ extern baro_t baro; pitot_t pitot = {.lastMeasurementUs = 0, .lastSeenHealthyMs = 0}; +// Pitot sensor validation state +static bool pitotHardwareFailed = false; +static uint16_t pitotFailureCounter = 0; +#define PITOT_FAILURE_THRESHOLD 100 // 1 second at 100Hz (sustained failure required) +#define PITOT_RECOVERY_THRESHOLD 50 // 0.5 seconds of good readings to recover + PG_REGISTER_WITH_RESET_TEMPLATE(pitotmeterConfig_t, pitotmeterConfig, PG_PITOTMETER_CONFIG, 2); #define PITOT_HARDWARE_TIMEOUT_MS 500 // Accept 500ms of non-responsive sensor, report HW failure otherwise @@ -312,13 +325,152 @@ bool pitotIsHealthy(void) return (millis() - pitot.lastSeenHealthyMs) < PITOT_HARDWARE_TIMEOUT_MS; } +/** + * Calculate virtual airspeed estimate (same as virtual pitot) + * + * Uses GPS velocity with wind correction when available, providing a reference + * airspeed that already accounts for wind conditions. + * + * @return virtual airspeed in cm/s, or 0 if GPS unavailable + */ +static float getVirtualAirspeedEstimate(void) +{ +#if defined(USE_GPS) && defined(USE_WIND_ESTIMATOR) + if (!STATE(GPS_FIX)) { + return 0.0f; + } + + float airSpeed = 0.0f; + + // Use wind estimator if available (matches virtual pitot logic) + if (isEstimatedWindSpeedValid()) { + uint16_t windHeading; // centidegrees + float windSpeed = getEstimatedHorizontalWindSpeed(&windHeading); // cm/s + float horizontalWindSpeed = windSpeed * cos_approx(CENTIDEGREES_TO_RADIANS(windHeading - posControl.actualState.yaw)); + airSpeed = posControl.actualState.velXY - horizontalWindSpeed; + airSpeed = calc_length_pythagorean_2D(airSpeed, getEstimatedActualVelocity(Z) + getEstimatedWindSpeed(Z)); + } else { + // Fall back to raw GPS velocity if no wind estimator + airSpeed = calc_length_pythagorean_3D(gpsSol.velNED[X], gpsSol.velNED[Y], gpsSol.velNED[Z]); + } + + return airSpeed; +#elif defined(USE_GPS) + // No wind estimator, use raw GPS velocity + if (!STATE(GPS_FIX)) { + return 0.0f; + } + return calc_length_pythagorean_3D(gpsSol.velNED[X], gpsSol.velNED[Y], gpsSol.velNED[Z]); +#else + return 0.0f; +#endif +} + +/** + * Pitot sensor sanity check against virtual airspeed + * + * Compares hardware pitot reading against virtual airspeed (GPS + wind estimator) + * to detect gross sensor failures like blocked pitot tubes. + * + * Uses wide thresholds to catch implausible readings while avoiding false positives: + * - Compares against wind-corrected virtual airspeed (not raw GPS groundspeed) + * - Wide tolerance (30%-200%) catches gross failures only + * - Detects: blocked pitot reading 25 km/h when virtual shows 85 km/h + * - Avoids: false positives from sensor accuracy differences + * + * @return true if pitot reading appears plausible, false if likely failed + */ +static bool isPitotReadingPlausible(void) +{ +#ifdef USE_GPS + if (!STATE(GPS_FIX)) { + return true; + } + + const float virtualAirspeedCmS = getVirtualAirspeedEstimate(); + const float minValidationSpeed = 700.0f; // 7 m/s + + if (virtualAirspeedCmS < minValidationSpeed) { + return true; + } + + const float pitotAirspeedCmS = pitot.airSpeed; + + // Wide thresholds to catch gross failures (blocked pitot) only + const float minPlausibleAirspeed = virtualAirspeedCmS * 0.3f; // 30% of virtual + const float maxPlausibleAirspeed = virtualAirspeedCmS * 2.0f; // 200% of virtual + + if (pitotAirspeedCmS < minPlausibleAirspeed || pitotAirspeedCmS > maxPlausibleAirspeed) { + return false; + } + + return true; +#else + return true; +#endif +} + +/** + * Check if pitot sensor has failed validation + * + * @return true if pitot has failed sanity checks and should not be trusted + */ +bool pitotHasFailed(void) +{ + return pitotHardwareFailed; +} + bool pitotValidForAirspeed(void) { bool ret = false; ret = pitotIsHealthy() && pitotIsCalibrationComplete(); + + // For virtual pitot, we need GPS fix if (detectedSensors[SENSOR_INDEX_PITOT] == PITOT_VIRTUAL) { ret = ret && STATE(GPS_FIX); } + + // For hardware pitot sensors, validate readings against GPS when armed + // This detects blocked or failed pitot tubes + if (ret && detectedSensors[SENSOR_INDEX_PITOT] != PITOT_VIRTUAL && + detectedSensors[SENSOR_INDEX_PITOT] != PITOT_NONE) { + + if (ARMING_FLAG(ARMED)) { + // Check if pitot reading is plausible + if (!isPitotReadingPlausible()) { + pitotFailureCounter++; + } else if (pitotFailureCounter > 0) { + // Decay counter if sensor appears healthy + pitotFailureCounter--; + } + + // Declare failure after sustained implausible readings + if (pitotFailureCounter >= PITOT_FAILURE_THRESHOLD) { + pitotHardwareFailed = true; + } + + // Recovery: require sustained good readings to clear failure + if (pitotHardwareFailed && isPitotReadingPlausible()) { + if (pitotFailureCounter > 0) { + pitotFailureCounter--; + } + if (pitotFailureCounter <= (PITOT_FAILURE_THRESHOLD - PITOT_RECOVERY_THRESHOLD)) { + pitotHardwareFailed = false; // Sensor has recovered + pitotFailureCounter = 0; + } + } + } else { + // Reset on disarm for next flight + pitotHardwareFailed = false; + pitotFailureCounter = 0; + } + + // If pitot has failed sanity checks, require GPS fix (like virtual pitot) + if (pitotHardwareFailed) { + ret = ret && STATE(GPS_FIX); + } + } + return ret; } #endif /* PITOT */ diff --git a/src/main/sensors/pitotmeter.h b/src/main/sensors/pitotmeter.h index 68f5a9c1a02..69451098ec8 100755 --- a/src/main/sensors/pitotmeter.h +++ b/src/main/sensors/pitotmeter.h @@ -70,5 +70,6 @@ void pitotUpdate(void); float getAirspeedEstimate(void); bool pitotIsHealthy(void); bool pitotValidForAirspeed(void); +bool pitotHasFailed(void); #endif From 80ec5cd435e341078c961fbe0bc93e59d5323316 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 3 Jan 2026 00:14:29 -0600 Subject: [PATCH 56/67] Improve APA safety: reduce I-term scaling and maximum gain MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Changes to Airspeed-based PID Attenuation (APA) for fixed-wing aircraft: 1. Reduced I-term scaling aggressiveness - I-term now scales with (apa_pow/100 - 1) instead of apa_pow/100 - Example: apa_pow=120 → I uses 0.20 exponent vs 1.20 for P/D/FF - Prevents integral windup and overshoot - Follows industry best practice (Betaflight, ArduPilot) - Maintains trim stability across speed range 2. Reduced maximum gain increase from 200% to 150% - Changed upper constraint from 2.0 to 1.5 - Prevents excessive gain multiplication at low speeds - More conservative approach reduces control sensitivity spikes - Still provides adequate authority for slow-speed flight 3. Changed default apa_pow from 120 to 0 (disabled) - APA now opt-in for safety - Users must explicitly enable after validating pitot sensor - Updated description to reflect new behavior - Safer default for new users Control theory rationale: - P/D/FF scaling compensates for dynamic pressure (½ρV²) - I-term serves different purpose (steady-state trim) - Aggressive I scaling causes windup and oscillation - Conservative I scaling improves control stability Combined with pitot validation (previous commit), these changes provide comprehensive safety improvements for APA feature. Addresses GitHub issue #11208 --- docs/Settings.md | 4 ++-- src/main/fc/settings.yaml | 4 ++-- src/main/flight/pid.c | 25 ++++++++++++++++++++++--- 3 files changed, 26 insertions(+), 7 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index b886f6702ac..3e512137c14 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -434,11 +434,11 @@ Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allo ### apa_pow -Use airspeed instead of throttle position for PID attenuation if airspeed is available on fixedwing. pid_multiplier = (referenceAirspeed/airspeed)**(apa_pow/100). Set to 0 will disable this feature and use throttle based PID attenuation; +Use airspeed instead of throttle position for PID attenuation if airspeed is available on fixedwing. Scales P/D/FF with airspeed (I-term scaled less aggressively). Gains range from 30% (high speed) to 150% (low speed). Set to 0 to disable and use throttle-based attenuation. Recommended: 120 for aircraft with validated pitot sensor. | Default | Min | Max | | --- | --- | --- | -| 120 | 0 | 200 | +| 0 | 0 | 200 | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 01ca6149bfb..1c38034dcf8 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1380,10 +1380,10 @@ groups: min: 0 max: 100 - name: apa_pow - description: "Use airspeed instead of throttle position for PID attenuation if airspeed is available on fixedwing. pid_multiplier = (referenceAirspeed/airspeed)**(apa_pow/100). Set to 0 will disable this feature and use throttle based PID attenuation;" + description: "Use airspeed instead of throttle position for PID attenuation if airspeed is available on fixedwing. Scales P/D/FF with airspeed (I-term scaled less aggressively). Gains range from 30% (high speed) to 150% (low speed). Set to 0 to disable and use throttle-based attenuation. Recommended: 120 for aircraft with validated pitot sensor." type: uint16_t field: throttle.apa_pow - default_value: 120 + default_value: 0 min: 0 max: 200 - name: tpa_rate diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 7a112ff8f4f..3857eaa6716 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -446,10 +446,25 @@ static float calculateFixedWingAirspeedTPAFactor(void){ const float airspeed = getAirspeedEstimate(); // in cm/s const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s float tpaFactor= powf(referenceAirspeed/(airspeed+0.01f), currentControlProfile->throttle.apa_pow/100.0f); - tpaFactor= constrainf(tpaFactor, 0.3f, 2.0f); + tpaFactor= constrainf(tpaFactor, 0.3f, 1.5f); // Reduced from 2.0 to 1.5 (max 50% gain increase) return tpaFactor; } +// Calculate I-term scaling factor (less aggressive than P/D/FF) +static float calculateFixedWingAirspeedITermFactor(void){ + const float airspeed = getAirspeedEstimate(); // in cm/s + const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s + const float apa_pow = currentControlProfile->throttle.apa_pow; + + if (apa_pow <= 100.0f) { + return 1.0f; + } + + float iTermFactor = powf(referenceAirspeed/(airspeed+0.01f), (apa_pow/100.0f) - 1.0f); + iTermFactor = constrainf(iTermFactor, 0.3f, 1.5f); + return iTermFactor; +} + static float calculateFixedWingTPAFactor(uint16_t throttle) { float tpaFactor; @@ -535,14 +550,18 @@ void updatePIDCoefficients(void) } float tpaFactor=1.0f; + float iTermFactor=1.0f; // Separate factor for I-term scaling if(usedPidControllerType == PID_TYPE_PIFF){ // Fixed wing TPA calculation if(currentControlProfile->throttle.apa_pow>0 && pitotValidForAirspeed()){ tpaFactor = calculateFixedWingAirspeedTPAFactor(); + iTermFactor = calculateFixedWingAirspeedITermFactor(); // Less aggressive I-term scaling }else{ tpaFactor = calculateFixedWingTPAFactor(calculateTPAThtrottle()); + iTermFactor = tpaFactor; // Use same factor for throttle-based TPA } } else { tpaFactor = calculateMultirotorTPAFactor(calculateTPAThtrottle()); + iTermFactor = tpaFactor; // Multirotor uses same factor } if (tpaFactor != tpaFactorprev) { pidGainsUpdateRequired = true; @@ -560,9 +579,9 @@ void updatePIDCoefficients(void) //TODO: Next step would be to update those only at THROTTLE or inflight adjustments change for (int axis = 0; axis < 3; axis++) { if (usedPidControllerType == PID_TYPE_PIFF) { - // Airplanes - scale all PIDs according to TPA + // Airplanes - scale PIDs according to TPA (I-term scaled less aggressively) pidState[axis].kP = pidBank()->pid[axis].P / FP_PID_RATE_P_MULTIPLIER * tpaFactor; - pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER * tpaFactor; + pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER * iTermFactor; // Less aggressive scaling pidState[axis].kD = pidBank()->pid[axis].D / FP_PID_RATE_D_MULTIPLIER * tpaFactor; pidState[axis].kFF = pidBank()->pid[axis].FF / FP_PID_RATE_FF_MULTIPLIER * tpaFactor; pidState[axis].kCD = 0.0f; From b3ac0f511b44b9a212e99d2f4451e3eb1ff88f34 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 3 Jan 2026 00:34:50 -0600 Subject: [PATCH 57/67] Add defensive airspeed clamping to prevent division issues Clamp airspeed to 100-20000 cm/s (3.6-720 km/h) before using in power calculations to prevent: - Division by zero or near-zero values - NaN results from invalid airspeed readings - Overflow from extreme values The constrainf() output clamps are still in place as the final safeguard, but this prevents bad intermediate calculations. --- src/main/flight/pid.c | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 3857eaa6716..dc3c7e44bad 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -443,16 +443,16 @@ float pidRcCommandToRate(int16_t stick, uint8_t rate) } static float calculateFixedWingAirspeedTPAFactor(void){ - const float airspeed = getAirspeedEstimate(); // in cm/s + const float airspeed = constrainf(getAirspeedEstimate(), 100.0f, 20000.0f); // cm/s, clamped to 3.6-720 km/h const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s - float tpaFactor= powf(referenceAirspeed/(airspeed+0.01f), currentControlProfile->throttle.apa_pow/100.0f); - tpaFactor= constrainf(tpaFactor, 0.3f, 1.5f); // Reduced from 2.0 to 1.5 (max 50% gain increase) + float tpaFactor= powf(referenceAirspeed/airspeed, currentControlProfile->throttle.apa_pow/100.0f); + tpaFactor= constrainf(tpaFactor, 0.3f, 1.5f); return tpaFactor; } // Calculate I-term scaling factor (less aggressive than P/D/FF) static float calculateFixedWingAirspeedITermFactor(void){ - const float airspeed = getAirspeedEstimate(); // in cm/s + const float airspeed = constrainf(getAirspeedEstimate(), 100.0f, 20000.0f); // cm/s, clamped to 3.6-720 km/h const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s const float apa_pow = currentControlProfile->throttle.apa_pow; @@ -460,7 +460,7 @@ static float calculateFixedWingAirspeedITermFactor(void){ return 1.0f; } - float iTermFactor = powf(referenceAirspeed/(airspeed+0.01f), (apa_pow/100.0f) - 1.0f); + float iTermFactor = powf(referenceAirspeed/airspeed, (apa_pow/100.0f) - 1.0f); iTermFactor = constrainf(iTermFactor, 0.3f, 1.5f); return iTermFactor; } From 65b9eb4a5754867160f1c89282480f3f68861a12 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E5=91=BD=E8=BF=90=E7=9A=84=E7=8E=A9=E7=AC=91?= <2417826860@qq.com> Date: Wed, 7 Jan 2026 22:27:44 -0800 Subject: [PATCH 58/67] RADIOLINKF722: add w25q128 flash --- src/main/target/RADIOLINKF722/target.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/target/RADIOLINKF722/target.h b/src/main/target/RADIOLINKF722/target.h index 2e38e23b74c..efa3bdea750 100644 --- a/src/main/target/RADIOLINKF722/target.h +++ b/src/main/target/RADIOLINKF722/target.h @@ -113,8 +113,12 @@ #define W25N01G_SPI_BUS BUS_SPI3 #define W25N01G_CS_PIN PD2 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PD2 + #define USE_BLACKBOX #define USE_FLASHFS +#define USE_FLASH_M25P16 #define USE_FLASH_W25N01G #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT From 7897f7f57b3179cb9dc1cf978841b6c0b087282d Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Thu, 8 Jan 2026 18:47:37 -0600 Subject: [PATCH 59/67] Fix pitot validation to use virtual airspeed on failure When hardware pitot fails validation, getAirspeedEstimate() now returns GPS-based virtual airspeed instead of the corrupted pitot value. This ensures APA (Airspeed-based PID Attenuation) continues working correctly with valid airspeed data. Changes: - getAirspeedEstimate() falls back to virtual airspeed when pitotHardwareFailed - Faster failure detection: 0.2s (20 samples) vs 1s (100 samples) - Slower recovery: 2s of consecutive good readings required - Separate recovery counter prevents underflow with asymmetric thresholds Fixes issue where blocked pitot caused APA to use invalid airspeed, resulting in incorrect PID gain scaling. Co-Authored-By: Claude Opus 4.5 --- src/main/sensors/pitotmeter.c | 39 ++++++++++++++++++++++++++--------- 1 file changed, 29 insertions(+), 10 deletions(-) diff --git a/src/main/sensors/pitotmeter.c b/src/main/sensors/pitotmeter.c index ce0f65df64a..b4b61f57669 100755 --- a/src/main/sensors/pitotmeter.c +++ b/src/main/sensors/pitotmeter.c @@ -68,8 +68,12 @@ pitot_t pitot = {.lastMeasurementUs = 0, .lastSeenHealthyMs = 0}; // Pitot sensor validation state static bool pitotHardwareFailed = false; static uint16_t pitotFailureCounter = 0; -#define PITOT_FAILURE_THRESHOLD 100 // 1 second at 100Hz (sustained failure required) -#define PITOT_RECOVERY_THRESHOLD 50 // 0.5 seconds of good readings to recover +static uint16_t pitotRecoveryCounter = 0; +#define PITOT_FAILURE_THRESHOLD 20 // 0.2 seconds at 100Hz - fast detection per LOG00002 analysis +#define PITOT_RECOVERY_THRESHOLD 200 // 2 seconds of consecutive good readings to recover + +// Forward declaration for GPS-based airspeed fallback +static float getVirtualAirspeedEstimate(void); PG_REGISTER_WITH_RESET_TEMPLATE(pitotmeterConfig_t, pitotmeterConfig, PG_PITOTMETER_CONFIG, 2); @@ -314,9 +318,18 @@ void pitotUpdate(void) /* * Airspeed estimate in cm/s + * Returns hardware pitot if valid, GPS-based virtual airspeed if pitot failed, + * or raw pitot value as last resort */ float getAirspeedEstimate(void) { + // If hardware pitot has failed validation, use GPS-based virtual airspeed + if (pitotHardwareFailed) { + float virtualAirspeed = getVirtualAirspeedEstimate(); + if (virtualAirspeed > 0.0f) { + return virtualAirspeed; + } + } return pitot.airSpeed; } @@ -447,22 +460,28 @@ bool pitotValidForAirspeed(void) // Declare failure after sustained implausible readings if (pitotFailureCounter >= PITOT_FAILURE_THRESHOLD) { pitotHardwareFailed = true; + pitotRecoveryCounter = 0; // Start recovery tracking } - // Recovery: require sustained good readings to clear failure - if (pitotHardwareFailed && isPitotReadingPlausible()) { - if (pitotFailureCounter > 0) { - pitotFailureCounter--; - } - if (pitotFailureCounter <= (PITOT_FAILURE_THRESHOLD - PITOT_RECOVERY_THRESHOLD)) { - pitotHardwareFailed = false; // Sensor has recovered - pitotFailureCounter = 0; + // Recovery: require sustained consecutive good readings to clear failure + if (pitotHardwareFailed) { + if (isPitotReadingPlausible()) { + pitotRecoveryCounter++; + if (pitotRecoveryCounter >= PITOT_RECOVERY_THRESHOLD) { + pitotHardwareFailed = false; // Sensor has recovered + pitotFailureCounter = 0; + pitotRecoveryCounter = 0; + } + } else { + // Bad reading resets recovery progress + pitotRecoveryCounter = 0; } } } else { // Reset on disarm for next flight pitotHardwareFailed = false; pitotFailureCounter = 0; + pitotRecoveryCounter = 0; } // If pitot has failed sanity checks, require GPS fix (like virtual pitot) From 933bbfc9ab7d6cfa72190d78683d0cfa0390ee0e Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 10 Jan 2026 14:08:10 -0600 Subject: [PATCH 60/67] Adjust TPA parameters for fixed-wing aircraft - Increase fw_tpa_time_constant default from 1500 to 2000ms - Raise airspeed TPA factor upper limit from 1.5 to 2.0 --- src/main/fc/settings.yaml | 2 +- src/main/flight/pid.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 1c38034dcf8..1e1932531e5 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1411,7 +1411,7 @@ groups: default_value: OFF - name: fw_tpa_time_constant description: "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. See **PID Attenuation and scaling** Wiki for full details." - default_value: 1500 + default_value: 2000 field: throttle.fixedWingTauMs min: 0 max: 5000 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index dc3c7e44bad..0a2faa648ca 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -446,7 +446,7 @@ static float calculateFixedWingAirspeedTPAFactor(void){ const float airspeed = constrainf(getAirspeedEstimate(), 100.0f, 20000.0f); // cm/s, clamped to 3.6-720 km/h const float referenceAirspeed = pidProfile()->fixedWingReferenceAirspeed; // in cm/s float tpaFactor= powf(referenceAirspeed/airspeed, currentControlProfile->throttle.apa_pow/100.0f); - tpaFactor= constrainf(tpaFactor, 0.3f, 1.5f); + tpaFactor= constrainf(tpaFactor, 0.3f, 2.0f); return tpaFactor; } From 605d365d1edbfff569995ba2c5ce9b62faa1e14b Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sat, 10 Jan 2026 14:49:57 -0600 Subject: [PATCH 61/67] Fix Settings.md documentation to match settings.yaml Updated fw_tpa_time_constant default value from 1500 to 2000 in Settings.md to match the authoritative value in settings.yaml. The discrepancy was caused by the documentation being out of sync with the YAML source. Regenerated using: python3 src/utils/update_cli_docs.py --- docs/Settings.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Settings.md b/docs/Settings.md index 3e512137c14..4e577bbedd5 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1478,7 +1478,7 @@ TPA smoothing and delay time constant to reflect non-instant speed/throttle resp | Default | Min | Max | | --- | --- | --- | -| 1500 | 0 | 5000 | +| 2000 | 0 | 5000 | --- From 797d64c862077fa12dcbcb7fb89311015d30de9f Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 11 Jan 2026 00:23:12 -0600 Subject: [PATCH 62/67] Add optional DFU mode parameter to MSP_REBOOT command MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Add optional parameter to MSP_REBOOT (message 68) to trigger DFU mode directly via MSP protocol. This provides a reliable programmatic method for tools and scripts to enter DFU mode without CLI timing issues. Changes: - Add static variable mspRebootBootloader to store DFU mode flag - Modify mspRebootFn to use the bootloader flag when calling fcReboot() - Add mspFcRebootCommand() helper to read optional parameter - Update mspFcProcessCommand() to handle MSP_REBOOT with new logic - Update USB Flashing.md documentation with proper CLI sequence - Add MSP method as recommended approach for programmatic DFU entry Backwards compatibility: - Empty payload (existing behavior) = normal reboot - Parameter 0x00 = explicit normal reboot - Parameter 0x01 = reboot to DFU/bootloader mode Tested on AOCODARCF722AIO: - āœ“ Empty payload reboots normally (backwards compatible) - āœ“ Parameter 0x00 reboots normally - āœ“ Parameter 0x01 enters DFU mode (verified with dfu-util) --- docs/USB Flashing.md | 24 ++++++++++++++++++------ src/main/fc/fc_msp.c | 34 +++++++++++++++++++++++++--------- 2 files changed, 43 insertions(+), 15 deletions(-) diff --git a/docs/USB Flashing.md b/docs/USB Flashing.md index 97787c7fb48..e1b059bb023 100644 --- a/docs/USB Flashing.md +++ b/docs/USB Flashing.md @@ -68,14 +68,26 @@ With the board connected and in bootloader mode (reset it by sending the charact Put the device into DFU mode by **one** of the following: -* Use the hardware button on the board -* Send a single 'R' character to the serial device, e.g. on POSIX OS using `/dev/ttyACM0` at 115200 baudrate. +* **Hardware button:** Press and hold the DFU/BOOT button while plugging in USB +* **Serial CLI sequence:** Send `####\r\n`, wait for CLI prompt, then send `dfu\r\n` + +```bash +# Enter CLI mode +echo -ne '####\r\n' > /dev/ttyACM0 + +# Wait for "CLI" prompt (important - don't skip!) +# Recommended: use a proper script that reads serial response + +# Send DFU command +echo -ne 'dfu\r\n' > /dev/ttyACM0 ``` -stty 115200 < /dev/ttyACM0 -echo -ne 'R' > /dev/ttyACM0 -``` -* Use the CLI command `dfu` + +**Note:** The simple single 'R' character method shown in older documentation is unreliable. The above sequence is required for proper CLI entry. + +* **CLI command:** If already connected to CLI via configurator or terminal: type `dfu` + +* **MSP command:** Use MSP_REBOOT with DFU parameter (INAV 9.x+) - most reliable programmatic method It is necessary to convert the `.hex` file into `Intel binary`. This can be done using the GCC `objcopy` command; e.g. for the notional `inav_x.y.z_NNNNNN.hex`. diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 3e81b028de2..74f5280afe6 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -183,6 +183,7 @@ typedef enum { static uint8_t mspPassthroughMode; static uint8_t mspPassthroughArgument; +static bool mspRebootBootloader; static serialPort_t *mspFindPassthroughSerialPort(void) { @@ -260,7 +261,23 @@ static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessF static void mspRebootFn(serialPort_t *serialPort) { UNUSED(serialPort); - fcReboot(false); + fcReboot(mspRebootBootloader); +} + +static void mspFcRebootCommand(sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn) +{ + const unsigned int dataSize = sbufBytesRemaining(src); + + // Read optional bootloader flag (backwards compatible) + if (dataSize >= 1) { + mspRebootBootloader = (sbufReadU8(src) != 0); // 0 = normal, non-zero = DFU + } else { + mspRebootBootloader = false; // Legacy behavior: normal reboot + } + + if (mspPostProcessFn) { + *mspPostProcessFn = mspRebootFn; + } } static void serializeSDCardSummaryReply(sbuf_t *dst) @@ -1457,14 +1474,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF break; - case MSP_REBOOT: - if (!ARMING_FLAG(ARMED)) { - if (mspPostProcessFn) { - *mspPostProcessFn = mspRebootFn; - } - } - break; - case MSP_WP_GETINFO: sbufWriteU8(dst, 0); // Reserved for waypoint capabilities sbufWriteU8(dst, NAV_MAX_WAYPOINTS); // Maximum number of waypoints supported @@ -4465,6 +4474,13 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro } else if (cmdMSP == MSP_SET_PASSTHROUGH) { mspFcSetPassthroughCommand(dst, src, mspPostProcessFn); ret = MSP_RESULT_ACK; + } else if (cmdMSP == MSP_REBOOT) { + if (!ARMING_FLAG(ARMED)) { + mspFcRebootCommand(src, mspPostProcessFn); + ret = MSP_RESULT_ACK; + } else { + ret = MSP_RESULT_ERROR; + } } else { if (!mspFCProcessInOutCommand(cmdMSP, dst, src, &ret)) { ret = mspFcProcessInCommand(cmdMSP, src); From 94420f5c458a41061e400855890369cf4fca50fa Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 11 Jan 2026 00:45:15 -0600 Subject: [PATCH 63/67] Remove unused mspPostProcessFn parameter from mspFcProcessOutCommand After moving MSP_REBOOT to mspFcProcessCommand, the mspPostProcessFn parameter in mspFcProcessOutCommand became unused. Remove it from both the function signature and call site to fix CI build warnings. --- src/main/fc/fc_msp.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 74f5280afe6..96db7f94484 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -370,7 +370,7 @@ static void serializeDataflashReadReply(sbuf_t *dst, uint32_t address, uint16_t * Returns true if the command was processd, false otherwise. * May set mspPostProcessFunc to a function to be called once the command has been processed */ -static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessFnPtr *mspPostProcessFn) +static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst) { switch (cmdMSP) { case MSP_API_VERSION: @@ -4469,7 +4469,7 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro if (MSP2_IS_SENSOR_MESSAGE(cmdMSP)) { ret = mspProcessSensorCommand(cmdMSP, src); - } else if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) { + } else if (mspFcProcessOutCommand(cmdMSP, dst)) { ret = MSP_RESULT_ACK; } else if (cmdMSP == MSP_SET_PASSTHROUGH) { mspFcSetPassthroughCommand(dst, src, mspPostProcessFn); From 483137612cddac7532c27d6792cb0c6249cc0eeb Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 11 Jan 2026 00:50:38 -0600 Subject: [PATCH 64/67] Add payload size validation to MSP_REBOOT command Validate that MSP_REBOOT payload is exactly 0 or 1 byte. Reject malformed packets with larger payloads to improve protocol robustness. Suggested-by: qodo-merge bot --- src/main/fc/fc_msp.c | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 96db7f94484..870272ba095 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -264,12 +264,17 @@ static void mspRebootFn(serialPort_t *serialPort) fcReboot(mspRebootBootloader); } -static void mspFcRebootCommand(sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn) +static mspResult_e mspFcRebootCommand(sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn) { const unsigned int dataSize = sbufBytesRemaining(src); + // Validate payload size: 0 or 1 byte only + if (dataSize > 1) { + return MSP_RESULT_ERROR; + } + // Read optional bootloader flag (backwards compatible) - if (dataSize >= 1) { + if (dataSize == 1) { mspRebootBootloader = (sbufReadU8(src) != 0); // 0 = normal, non-zero = DFU } else { mspRebootBootloader = false; // Legacy behavior: normal reboot @@ -278,6 +283,8 @@ static void mspFcRebootCommand(sbuf_t *src, mspPostProcessFnPtr *mspPostProcessF if (mspPostProcessFn) { *mspPostProcessFn = mspRebootFn; } + + return MSP_RESULT_ACK; } static void serializeSDCardSummaryReply(sbuf_t *dst) @@ -4476,8 +4483,7 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro ret = MSP_RESULT_ACK; } else if (cmdMSP == MSP_REBOOT) { if (!ARMING_FLAG(ARMED)) { - mspFcRebootCommand(src, mspPostProcessFn); - ret = MSP_RESULT_ACK; + ret = mspFcRebootCommand(src, mspPostProcessFn); } else { ret = MSP_RESULT_ERROR; } From c0f760b24ac06e428a364c28b59c773c9b724e86 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 11 Jan 2026 00:56:21 -0600 Subject: [PATCH 65/67] Revert "Remove unused mspPostProcessFn parameter from mspFcProcessOutCommand" This reverts commit 94420f5c458a41061e400855890369cf4fca50fa. --- src/main/fc/fc_msp.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 870272ba095..92d7d1f8770 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -377,8 +377,10 @@ static void serializeDataflashReadReply(sbuf_t *dst, uint32_t address, uint16_t * Returns true if the command was processd, false otherwise. * May set mspPostProcessFunc to a function to be called once the command has been processed */ -static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst) +static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessFnPtr *mspPostProcessFn) { + UNUSED(mspPostProcessFn); + switch (cmdMSP) { case MSP_API_VERSION: sbufWriteU8(dst, MSP_PROTOCOL_VERSION); @@ -4476,7 +4478,7 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro if (MSP2_IS_SENSOR_MESSAGE(cmdMSP)) { ret = mspProcessSensorCommand(cmdMSP, src); - } else if (mspFcProcessOutCommand(cmdMSP, dst)) { + } else if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) { ret = MSP_RESULT_ACK; } else if (cmdMSP == MSP_SET_PASSTHROUGH) { mspFcSetPassthroughCommand(dst, src, mspPostProcessFn); From 220e90a65646c73ec28d072e618842f135b8f73b Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 11 Jan 2026 01:29:40 -0600 Subject: [PATCH 66/67] Improve blackbox DEBUG documentation MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Add missing SERVOS field to blackbox field list - Fix typo: "blackbox MOTOR" → "blackbox MOTORS" - Add new "Debug Mode Logging" section explaining debug_mode setting - Include examples of common debug modes (FLOW_RAW, LANDING, POS_EST, GPS, ALTITUDE) - Add CLI usage examples for debug mode - Reference Blackbox Internals.md for technical details - Mention OSD_DEBUG element for real-time display This helps users discover the debug logging functionality which was previously only documented in the technical Blackbox Internals document. --- docs/Blackbox.md | 25 ++++++++++++++++++++++++- 1 file changed, 24 insertions(+), 1 deletion(-) diff --git a/docs/Blackbox.md b/docs/Blackbox.md index b4528d8dd23..45900a4c08d 100644 --- a/docs/Blackbox.md +++ b/docs/Blackbox.md @@ -166,13 +166,36 @@ The CLI command `blackbox` allows setting which Blackbox fields are recorded to * `PEAKS_R` - Roll axis noise peak * `PEAKS_P` - Pitch axis noise peak * `PEAKS_Y` - Yaw axis noise peak +* `SERVOS` - Servo outputs (for planes, tris, etc.) Usage: * `blackbox` currently enabled Blackbox fields * `blackbox list` all available fields * `blackbox -MOTORS` disable MOTORS logging -* `blackbox MOTOR` enable MOTORS logging +* `blackbox MOTORS` enable MOTORS logging + +### Debug Mode Logging + +In addition to the standard blackbox fields above, INAV supports logging debug values for troubleshooting and analysis via the `debug_mode` setting. When a debug mode is active, it populates 8 debug values (`debug[0]` through `debug[7]`) with mode-specific data that gets logged to the blackbox. + +Available debug modes include: +- `FLOW_RAW` - Optical flow sensor raw data (useful for sensor alignment) +- `LANDING` - Landing mode debugging +- `POS_EST` - Position estimation debugging +- `GPS` - GPS debugging +- `ALTITUDE` - Altitude estimation debugging +- And 20+ other modes for specific subsystems + +To use debug mode logging: +``` +set debug_mode = FLOW_RAW # Enable a specific debug mode +set debug_mode = NONE # Disable debug mode (default) +``` + +You can view current debug values in the CLI with the `debug` command, or display them in real-time on your OSD using the `OSD_DEBUG` element. + +For technical details on debug logging and blackbox internals, see the [Blackbox Internals](development/Blackbox%20Internals.md) documentation. ## Usage From c12fc841d05be31b2abe776de0c88c68ab61d8a2 Mon Sep 17 00:00:00 2001 From: Ray Morris Date: Sun, 11 Jan 2026 10:13:40 -0600 Subject: [PATCH 67/67] Refactor MSP_REBOOT: eliminate global variable MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Based on qodo-merge bot review suggestion (importance: 7). Changes: - Remove static global variable mspRebootBootloader - Add two distinct post-process functions: - mspRebootNormalFn() for normal reboot - mspRebootDfuFn() for DFU mode reboot - Update mspFcRebootCommand() to directly assign function pointer Benefits: - Eliminates global state - Makes control flow more explicit - Easier to maintain and understand - Improves code quality per qodo review Tested on AOCODARCF722AIO hardware: āœ… Backwards compatible reboot (empty payload) āœ… Explicit normal reboot (payload 0x00) āœ… DFU mode reboot (payload 0x01) --- src/main/fc/fc_msp.c | 28 +++++++++++++++++----------- 1 file changed, 17 insertions(+), 11 deletions(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 92d7d1f8770..455d5f20897 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -183,7 +183,6 @@ typedef enum { static uint8_t mspPassthroughMode; static uint8_t mspPassthroughArgument; -static bool mspRebootBootloader; static serialPort_t *mspFindPassthroughSerialPort(void) { @@ -258,10 +257,16 @@ static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessF } } -static void mspRebootFn(serialPort_t *serialPort) +static void mspRebootNormalFn(serialPort_t *serialPort) { UNUSED(serialPort); - fcReboot(mspRebootBootloader); + fcReboot(false); +} + +static void mspRebootDfuFn(serialPort_t *serialPort) +{ + UNUSED(serialPort); + fcReboot(true); } static mspResult_e mspFcRebootCommand(sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn) @@ -273,15 +278,16 @@ static mspResult_e mspFcRebootCommand(sbuf_t *src, mspPostProcessFnPtr *mspPostP return MSP_RESULT_ERROR; } - // Read optional bootloader flag (backwards compatible) - if (dataSize == 1) { - mspRebootBootloader = (sbufReadU8(src) != 0); // 0 = normal, non-zero = DFU - } else { - mspRebootBootloader = false; // Legacy behavior: normal reboot - } - + // Determine reboot type and set appropriate post-process function if (mspPostProcessFn) { - *mspPostProcessFn = mspRebootFn; + if (dataSize == 1) { + // Read bootloader flag: 0 = normal, non-zero = DFU + const bool bootloaderMode = (sbufReadU8(src) != 0); + *mspPostProcessFn = bootloaderMode ? mspRebootDfuFn : mspRebootNormalFn; + } else { + // Legacy behavior: no parameter means normal reboot + *mspPostProcessFn = mspRebootNormalFn; + } } return MSP_RESULT_ACK;