From c4d4d889417f397225c4a2fc2131bbd69f790cdc Mon Sep 17 00:00:00 2001
From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com>
Date: Mon, 16 Dec 2024 00:21:00 +0100
Subject: [PATCH 01/55] Remove legacy hdzero special case
---
src/main/io/displayport_msp_osd.c | 29 -----------------------------
1 file changed, 29 deletions(-)
diff --git a/src/main/io/displayport_msp_osd.c b/src/main/io/displayport_msp_osd.c
index 0b9be8c6d86..a39f123cdde 100644
--- a/src/main/io/displayport_msp_osd.c
+++ b/src/main/io/displayport_msp_osd.c
@@ -133,31 +133,6 @@ static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *subcmd, int
return sent;
}
-static uint8_t determineHDZeroOsdMode(void)
-{
- if (cmsInMenu) {
- return HD_5018;
- }
-
- // Check if all visible widgets are in the center 30x16 chars of the canvas.
- int activeLayout = osdGetActiveLayout(NULL);
- osd_items_e index = 0;
- do {
- index = osdIncElementIndex(index);
- uint16_t pos = osdLayoutsConfig()->item_pos[activeLayout][index];
- if (OSD_VISIBLE(pos)) {
- uint8_t elemPosX = OSD_X(pos);
- uint8_t elemPosY = OSD_Y(pos);
- if (!osdItemIsFixed(index) && (elemPosX < 10 || elemPosX > 39 || elemPosY == 0 || elemPosY == 17)) {
- return HD_5018;
- }
- }
- } while (index > 0);
-
- return HD_3016;
-}
-
-
uint8_t setAttrPage(uint8_t origAttr, uint8_t page)
{
return (origAttr & ~DISPLAYPORT_MSP_ATTR_FONTPAGE_MASK) | (page & DISPLAYPORT_MSP_ATTR_FONTPAGE_MASK);
@@ -175,10 +150,6 @@ uint8_t setAttrVersion(uint8_t origAttr, uint8_t version)
static int setDisplayMode(displayPort_t *displayPort)
{
- if (osdVideoSystem == VIDEO_SYSTEM_HDZERO) {
- currentOsdMode = determineHDZeroOsdMode(); // Can change between layouts
- }
-
uint8_t subcmd[] = { MSP_DP_OPTIONS, 0, currentOsdMode }; // Font selection, mode (SD/HD)
return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
}
From daa1ff614ec163daa1d80360b5f37af3d9ac8c8d Mon Sep 17 00:00:00 2001
From: niepingyu <1401798620@qq.com>
Date: Mon, 15 Dec 2025 13:37:16 +0800
Subject: [PATCH 02/55] add HAKRCH743 target
---
src/main/target/HAKRCH743/CMakeLists.txt | 1 +
src/main/target/HAKRCH743/config.c | 28 ++++
src/main/target/HAKRCH743/target.c | 51 +++++++
src/main/target/HAKRCH743/target.h | 178 +++++++++++++++++++++++
4 files changed, 258 insertions(+)
create mode 100644 src/main/target/HAKRCH743/CMakeLists.txt
create mode 100644 src/main/target/HAKRCH743/config.c
create mode 100644 src/main/target/HAKRCH743/target.c
create mode 100644 src/main/target/HAKRCH743/target.h
diff --git a/src/main/target/HAKRCH743/CMakeLists.txt b/src/main/target/HAKRCH743/CMakeLists.txt
new file mode 100644
index 00000000000..eb70a0acdca
--- /dev/null
+++ b/src/main/target/HAKRCH743/CMakeLists.txt
@@ -0,0 +1 @@
+target_stm32h743xi(HAKRCH743)
diff --git a/src/main/target/HAKRCH743/config.c b/src/main/target/HAKRCH743/config.c
new file mode 100644
index 00000000000..b963bfbfa59
--- /dev/null
+++ b/src/main/target/HAKRCH743/config.c
@@ -0,0 +1,28 @@
+/*
+ * 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
+
+#include "fc/fc_msp_box.h"
+#include "io/piniobox.h"
+
+void targetConfiguration(void)
+{
+ pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
+ pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
+}
diff --git a/src/main/target/HAKRCH743/target.c b/src/main/target/HAKRCH743/target.c
new file mode 100644
index 00000000000..05c1674f07b
--- /dev/null
+++ b/src/main/target/HAKRCH743/target.c
@@ -0,0 +1,51 @@
+/*
+ * 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
+
+#include "drivers/bus.h"
+#include "drivers/io.h"
+#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
+#include "drivers/pinio.h"
+#include "drivers/sensor.h"
+
+BUSDEV_REGISTER_SPI_TAG(busdev_icm42688_0, DEVHW_ICM42605, ICM42688_0_SPI_BUS, ICM42688_0_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42688_0_ALIGN);
+// BUSDEV_REGISTER_SPI_TAG(busdev_icm42688_1, DEVHW_ICM42605, ICM42688_1_SPI_BUS, ICM42688_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_ICM42688_1_ALIGN);
+
+timerHardware_t timerHardware[] = {
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2
+ DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 2), // S3
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 3), // S4
+
+ DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 4), // S5
+ DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 5), // S6
+ DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S7
+ DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S8
+
+ DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S9
+ DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S10
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S11
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S12
+
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812
+ DEF_TIM(TIM1, CH1, PE9, TIM_USE_BEEPER, 0, 0), // BEEPER
+};
+
+const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
diff --git a/src/main/target/HAKRCH743/target.h b/src/main/target/HAKRCH743/target.h
new file mode 100644
index 00000000000..8f0d69159f6
--- /dev/null
+++ b/src/main/target/HAKRCH743/target.h
@@ -0,0 +1,178 @@
+/*
+ * 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 "HK743"
+#define USBD_PRODUCT_STRING "HAKRCH743"
+
+#define USE_TARGET_CONFIG
+
+/*** Indicators ***/
+#define LED0 PE3
+#define LED1 PE4
+#define BEEPER PE9
+#define BEEPER_INVERTED
+
+/*** SPI/I2C bus ***/
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_NSS1_PIN PC15
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PD7
+
+#define USE_SPI_DEVICE_3
+#define SPI3_NSS_PIN PE2
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
+
+#define USE_SPI_DEVICE_4
+#define SPI4_NSS_PIN PC13
+#define SPI4_SCK_PIN PE12
+#define SPI4_MISO_PIN PE13
+#define SPI4_MOSI_PIN PE14
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
+
+#define USE_I2C_DEVICE_2
+#define I2C2_SCL PB10
+#define I2C2_SDA PB11
+
+/*** IMU sensors ***/
+
+#define USE_DUAL_GYRO
+#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
+#define USE_SPI
+#define USE_IMU_ICM42605
+
+// IMU0 ICM42688P/ICM42605
+#define ICM42688_0_CS_PIN PC15
+#define ICM42688_0_SPI_BUS BUS_SPI1
+#define IMU_ICM42688_0_ALIGN CW0_DEG
+
+
+// IMU1 ICM42688P/ICM42605
+#define ICM42688_1_CS_PIN PC13
+#define ICM42688_1_SPI_BUS BUS_SPI4
+#define IMU_ICM42688_1_ALIGN CW270_DEG
+
+
+/*** OSD ***/
+#define USE_MAX7456
+#define MAX7456_SPI_BUS BUS_SPI3
+#define MAX7456_CS_PIN PE2
+
+
+// *** PINIO ***
+#define USE_PINIO
+#define USE_PINIOBOX
+#define PINIO1_PIN PD10
+#define PINIO2_PIN PD11
+
+/*** Serial ports ***/
+#define USE_VCP
+
+#define USE_UART1
+#define UART1_RX_PIN PA10
+#define UART1_TX_PIN PA9
+
+#define USE_UART2
+#define UART2_RX_PIN PD6
+#define UART2_TX_PIN PD5
+
+#define USE_UART3
+#define UART3_RX_PIN PD9
+#define UART3_TX_PIN PD8
+
+#define USE_UART4
+#define UART4_RX_PIN PB8
+#define UART4_TX_PIN PB9
+
+#define USE_UART5
+#define UART5_RX_PIN PB12
+#define UART5_TX_PIN PB13
+
+#define USE_UART6
+#define UART6_RX_PIN PC7
+#define UART6_TX_PIN PC6
+
+#define USE_UART7
+#define UART7_RX_PIN PE7
+#define UART7_TX_PIN PE8
+
+#define USE_UART8
+#define UART8_RX_PIN PE0
+#define UART8_TX_PIN PE1
+
+#define SERIAL_PORT_COUNT 9 // VCP, UART1, UART2, UART3, UART4, UART5, UART6, UART7, UART8
+#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
+#define SERIALRX_PROVIDER SERIALRX_SBUS
+#define SERIALRX_UART SERIAL_PORT_USART7
+
+/*** BARO & MAG ***/
+#define USE_BARO
+#define BARO_I2C_BUS BUS_I2C1
+#define USE_BARO_BMP280
+#define USE_BARO_SPL06
+#define USE_BARO_DPS310
+
+#define USE_MAG
+#define MAG_I2C_BUS BUS_I2C2
+#define USE_MAG_ALL
+
+/*** ADC ***/
+#define USE_ADC
+#define ADC_INSTANCE ADC1
+#define ADC_CHANNEL_1_PIN PC0
+#define ADC_CHANNEL_2_PIN PC1
+#define ADC_CHANNEL_3_PIN PC5
+
+#define VBAT_ADC_CHANNEL ADC_CHN_1
+#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
+#define RSSI_ADC_CHANNEL ADC_CHN_3
+
+/*** LED STRIP ***/
+#define USE_LED_STRIP
+#define WS2811_PIN PA8
+
+// *************** SDIO SD BLACKBOX*******************
+#define USE_SDCARD
+#define USE_SDCARD_SDIO
+#define SDCARD_SDIO_DEVICE SDIODEV_1
+#define SDCARD_SDIO_4BIT
+#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
+
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
+
+/*** Timer/PWM output ***/
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+#define MAX_PWM_OUTPUT_PORTS 12
+#define USE_DSHOT
+#define USE_ESC_SENSOR
+
+/*** Used pins ***/
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+#define TARGET_IO_PORTE 0xffff
\ No newline at end of file
From aba749b2f4e6987bcd7f5a3e406fbb93467c5038 Mon Sep 17 00:00:00 2001
From: HAKRC8899 <18948734563@163.com>
Date: Tue, 16 Dec 2025 08:32:24 +0800
Subject: [PATCH 03/55] Update src/main/target/HAKRCH743/target.c
Co-authored-by: qodo-code-review[bot] <151058649+qodo-code-review[bot]@users.noreply.github.com>
---
src/main/target/HAKRCH743/target.c | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/target/HAKRCH743/target.c b/src/main/target/HAKRCH743/target.c
index 05c1674f07b..c1a72d29fbc 100644
--- a/src/main/target/HAKRCH743/target.c
+++ b/src/main/target/HAKRCH743/target.c
@@ -26,7 +26,7 @@
#include "drivers/sensor.h"
BUSDEV_REGISTER_SPI_TAG(busdev_icm42688_0, DEVHW_ICM42605, ICM42688_0_SPI_BUS, ICM42688_0_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42688_0_ALIGN);
-// BUSDEV_REGISTER_SPI_TAG(busdev_icm42688_1, DEVHW_ICM42605, ICM42688_1_SPI_BUS, ICM42688_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_ICM42688_1_ALIGN);
+BUSDEV_REGISTER_SPI_TAG(busdev_icm42688_1, DEVHW_ICM42605, ICM42688_1_SPI_BUS, ICM42688_1_CS_PIN, NONE, 1, DEVFLAGS_NONE, IMU_ICM42688_1_ALIGN);
timerHardware_t timerHardware[] = {
DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
From 77aac46f3513e0171bb3c955385e2102ec7d3538 Mon Sep 17 00:00:00 2001
From: HAKRC8899 <18948734563@163.com>
Date: Tue, 16 Dec 2025 10:18:20 +0800
Subject: [PATCH 04/55] Update target.c
---
src/main/target/HAKRCH743/target.c | 5 ++---
1 file changed, 2 insertions(+), 3 deletions(-)
diff --git a/src/main/target/HAKRCH743/target.c b/src/main/target/HAKRCH743/target.c
index c1a72d29fbc..047eeeebd70 100644
--- a/src/main/target/HAKRCH743/target.c
+++ b/src/main/target/HAKRCH743/target.c
@@ -36,8 +36,8 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 4), // S5
DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 5), // S6
- DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S7
- DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S8
+ DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 6), // S7
+ DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 7), // S8
DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S9
DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S10
@@ -45,7 +45,6 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S12
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812
- DEF_TIM(TIM1, CH1, PE9, TIM_USE_BEEPER, 0, 0), // BEEPER
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
From fb9a0f88d982370ab161ed0c3eaeb38e025f00b2 Mon Sep 17 00:00:00 2001
From: Darren Lines
Date: Fri, 30 Jan 2026 12:08:44 +0000
Subject: [PATCH 05/55] Rename profile commands to control_profile
---
docs/Cli.md | 14 +++++++-------
1 file changed, 7 insertions(+), 7 deletions(-)
diff --git a/docs/Cli.md b/docs/Cli.md
index e5fc9dc1541..966c5ec23ea 100644
--- a/docs/Cli.md
+++ b/docs/Cli.md
@@ -27,17 +27,17 @@ Disconnect main power, connect to cli via USB/FTDI.
dump using cli
```
-profile 0
+control_profile 0
dump
```
-dump profiles using cli if you use them
+dump control_profiles using cli if you use them
```
-profile 1
-dump profile
-profile 2
-dump profile
+control_profile 1
+dump control_profile
+control_profile 2
+dump control_profile
```
copy screen output to a file and save it.
@@ -100,7 +100,7 @@ While connected to the CLI, all Logical Switches are temporarily disabled (5.1.0
| `osd_layout` | Get or set the layout of OSD items |
| `pid` | Configurable PID controllers |
| `play_sound` | ``, or none for next item |
-| `profile` | Change profile |
+| `control_profile` | Change profile |
| `resource` | View currently used resources |
| `rxrange` | Configure rx channel ranges |
| `safehome` | Define safe home locations. See the [safehome documentation](Safehomes.md) for usage information. |
From b1cbc45f6ec95e408bd9cc11677ede90209b3fc9 Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Mon, 2 Feb 2026 23:17:57 +0000
Subject: [PATCH 06/55] add vbatt warning to multifunction
---
docs/Settings.md | 10 ++++++++++
src/main/fc/settings.yaml | 7 +++++++
src/main/io/osd.c | 16 ++++++++++++----
src/main/io/osd.h | 1 +
4 files changed, 30 insertions(+), 4 deletions(-)
diff --git a/docs/Settings.md b/docs/Settings.md
index 4e577bbedd5..14859d65cbc 100644
--- a/docs/Settings.md
+++ b/docs/Settings.md
@@ -3092,6 +3092,16 @@ Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this r
---
+### multifunction_warning_cycle_time
+
+Cycle time for display of full multifunction warning messages [s]. Full warnings will be displayed for 5s on a rolling cycle using this setting with only the total number of warnings indicated otherwise. Warnings will always be displayed in full if set to 0.
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 30 | 0 | 60 |
+
+---
+
### name
Craft name
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index 1e1932531e5..ff66b57df26 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -3904,6 +3904,13 @@ groups:
field: osd_switch_indicators_align_left
type: bool
default_value: ON
+ - name: multifunction_warning_cycle_time
+ description: "Cycle time for display of full multifunction warning messages [s]. Full warnings will be displayed for 5s on a rolling cycle using this setting with only the total number of warnings indicated otherwise. Warnings will always be displayed in full if set to 0."
+ field: multifunction_warning_cycle_time
+ min: 0
+ max: 60
+ default_value: 30
+
- name: PG_OSD_COMMON_CONFIG
type: osdCommonConfig_t
headers: ["io/osd_common.h"]
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index 6ad55632c17..b7ecbb96bc7 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -4355,6 +4355,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
.use_pilot_logo = SETTING_OSD_USE_PILOT_LOGO_DEFAULT,
.inav_to_pilot_logo_spacing = SETTING_OSD_INAV_TO_PILOT_LOGO_SPACING_DEFAULT,
.arm_screen_display_time = SETTING_OSD_ARM_SCREEN_DISPLAY_TIME_DEFAULT,
+ .multifunction_warning_cycle_time = SETTING_MULTIFUNCTION_WARNING_CYCLE_TIME_DEFAULT,
#ifdef USE_WIND_ESTIMATOR
.estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT,
@@ -6432,12 +6433,12 @@ static bool osdCheckWarning(bool condition, uint8_t warningFlag, uint8_t *warnin
}
#endif
/* Warnings displayed in full for set time before shrinking down to alert symbol with warning count only.
- * All current warnings then redisplayed for 5s on 30s rolling cycle.
+ * All current warnings are redisplayed in full for 5s on a rolling cycle with time set by multifunction_warning_cycle_time.
* New warnings dislayed individually for 10s */
if (currentTimeMs > redisplayStartTimeMs) {
warningDisplayStartTime = currentTimeMs;
osdWarningTimerDuration = newWarningFlags ? 10000 : WARNING_REDISPLAY_DURATION;
- redisplayStartTimeMs = currentTimeMs + osdWarningTimerDuration + 30000;
+ redisplayStartTimeMs = currentTimeMs + osdWarningTimerDuration + S2MS(osdConfig()->multifunction_warning_cycle_time);
}
if (currentTimeMs - warningDisplayStartTime < osdWarningTimerDuration) {
@@ -6524,13 +6525,20 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
#endif // MULTIFUNCTION - functions only, warnings always defined
/* --- WARNINGS --- */
- const char *messages[7];
+ const char *messages[8];
uint8_t messageCount = 0;
bool warningCondition = false;
warningsCount = 0;
uint8_t warningFlagID = 1;
- // Low Battery
+ // Low Battery Voltage
+ const batteryState_e batteryVoltageState = checkBatteryVoltageState();
+ warningCondition = batteryVoltageState == BATTERY_CRITICAL || batteryVoltageState == BATTERY_WARNING;
+ if (osdCheckWarning(warningCondition, warningFlagID, &warningsCount)) {
+ messages[messageCount++] = batteryVoltageState == BATTERY_CRITICAL ? "VBATT CRIT" : "VBATT LOW ";
+ }
+
+ // Low Battery Capacity
const batteryState_e batteryState = getBatteryState();
warningCondition = batteryState == BATTERY_CRITICAL || batteryState == BATTERY_WARNING;
if (osdCheckWarning(warningCondition, warningFlagID, &warningsCount)) {
diff --git a/src/main/io/osd.h b/src/main/io/osd.h
index bbaa68f862d..e066c9194b4 100644
--- a/src/main/io/osd.h
+++ b/src/main/io/osd.h
@@ -525,6 +525,7 @@ typedef struct osdConfig_s {
bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo.
uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width.
uint16_t arm_screen_display_time; // Length of time the arm screen is displayed
+ uint8_t multifunction_warning_cycle_time; // Cycle time for display of full multifunction warning messages (s)
#ifndef DISABLE_MSP_DJI_COMPAT
bool highlight_djis_missing_characters; // If enabled, show question marks where there is no character in DJI's font to represent an OSD element symbol
#endif
From ecfd1a9374ec5d26f80584a2786e1ac66524193d Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Tue, 3 Feb 2026 10:39:57 +0000
Subject: [PATCH 07/55] Update osd.c
---
src/main/io/osd.c | 13 +++++++------
1 file changed, 7 insertions(+), 6 deletions(-)
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index b7ecbb96bc7..0833631ecda 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -6535,16 +6535,17 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
const batteryState_e batteryVoltageState = checkBatteryVoltageState();
warningCondition = batteryVoltageState == BATTERY_CRITICAL || batteryVoltageState == BATTERY_WARNING;
if (osdCheckWarning(warningCondition, warningFlagID, &warningsCount)) {
- messages[messageCount++] = batteryVoltageState == BATTERY_CRITICAL ? "VBATT CRIT" : "VBATT LOW ";
+ messages[messageCount++] = batteryVoltageState == BATTERY_CRITICAL ? "VBATT LAND" : "VBATT LOW ";
}
// Low Battery Capacity
- const batteryState_e batteryState = getBatteryState();
- warningCondition = batteryState == BATTERY_CRITICAL || batteryState == BATTERY_WARNING;
- if (osdCheckWarning(warningCondition, warningFlagID, &warningsCount)) {
- messages[messageCount++] = batteryState == BATTERY_CRITICAL ? "BATT EMPTY" : "BATT LOW !";
+ if (batteryUsesCapacityThresholds()) {
+ const batteryState_e batteryState = getBatteryState();
+ warningCondition = batteryState == BATTERY_CRITICAL || batteryState == BATTERY_WARNING;
+ if (osdCheckWarning(warningCondition, warningFlagID <<= 1, &warningsCount)) {
+ messages[messageCount++] = batteryState == BATTERY_CRITICAL ? "BATT EMPTY" : "BATT LOW ";
+ }
}
-
#if defined(USE_GPS)
// GPS Fix and Failure
if (feature(FEATURE_GPS)) {
From 1cfcbb17dd6a5445d42525fd1964991d31ddc759 Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Tue, 3 Feb 2026 10:56:31 +0000
Subject: [PATCH 08/55] Update osd.c
---
src/main/io/osd.c | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index 0833631ecda..f83ba9ac346 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -6543,7 +6543,7 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
const batteryState_e batteryState = getBatteryState();
warningCondition = batteryState == BATTERY_CRITICAL || batteryState == BATTERY_WARNING;
if (osdCheckWarning(warningCondition, warningFlagID <<= 1, &warningsCount)) {
- messages[messageCount++] = batteryState == BATTERY_CRITICAL ? "BATT EMPTY" : "BATT LOW ";
+ messages[messageCount++] = batteryState == BATTERY_CRITICAL ? "BATT EMPTY" : "BATT DYING";
}
}
#if defined(USE_GPS)
From c53fb5df13070628932a571d580b42874e7af393 Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Tue, 3 Feb 2026 17:48:34 +0000
Subject: [PATCH 09/55] fix batt voltage state inconsistency
---
src/main/sensors/battery.c | 16 +++++++++-------
1 file changed, 9 insertions(+), 7 deletions(-)
diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c
index 38d410610e1..79706c8dba7 100644
--- a/src/main/sensors/battery.c
+++ b/src/main/sensors/battery.c
@@ -288,7 +288,7 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected)
}
break;
#endif
-
+
#if defined(USE_FAKE_BATT_SENSOR)
case VOLTAGE_SENSOR_FAKE:
vbat = fakeBattSensorGetVBat();
@@ -328,30 +328,32 @@ static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected)
batteryState_e checkBatteryVoltageState(void)
{
uint16_t stateVoltage = getBatteryVoltage();
- switch (batteryState)
+ static batteryState_e currentBatteryVoltageState = BATTERY_OK;
+
+ switch (currentBatteryVoltageState)
{
case BATTERY_OK:
if (stateVoltage <= (batteryWarningVoltage - VBATT_HYSTERESIS)) {
- return BATTERY_WARNING;
+ currentBatteryVoltageState = BATTERY_WARNING;
}
break;
case BATTERY_WARNING:
if (stateVoltage <= (batteryCriticalVoltage - VBATT_HYSTERESIS)) {
- return BATTERY_CRITICAL;
+ currentBatteryVoltageState = BATTERY_CRITICAL;
} else if (stateVoltage > (batteryWarningVoltage + VBATT_HYSTERESIS)){
- return BATTERY_OK;
+ currentBatteryVoltageState = BATTERY_OK;
}
break;
case BATTERY_CRITICAL:
if (stateVoltage > (batteryCriticalVoltage + VBATT_HYSTERESIS)) {
- return BATTERY_WARNING;
+ currentBatteryVoltageState = BATTERY_WARNING;
}
break;
default:
break;
}
- return batteryState;
+ return currentBatteryVoltageState;
}
static void checkBatteryCapacityState(void)
From 342eeeeff532eb182bcdc7e83e8ee2cda5db24f3 Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Tue, 3 Feb 2026 22:50:52 +0000
Subject: [PATCH 10/55] remove blinking
---
src/main/io/osd.c | 1 -
1 file changed, 1 deletion(-)
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index f83ba9ac346..8401bdeaf3a 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -6603,7 +6603,6 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
if (messageCount) {
message = messages[OSD_ALTERNATING_CHOICES(1000, messageCount)]; // display each warning on 1s cycle
strcpy(buff, message);
- TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
} else if (warningsCount) {
buff[0] = SYM_ALERT;
tfp_sprintf(buff + 1, "%u ", warningsCount);
From 497cb3addc552c8c17a42609098cdb5c833b06ed Mon Sep 17 00:00:00 2001
From: KeithCoreDumped
Date: Wed, 21 Jan 2026 00:25:56 +0800
Subject: [PATCH 11/55] fix: flght controller hard fault caused by insufficient
CRSF rx buffer size when connected via TCP
---
src/main/telemetry/crsf.h | 4 ++--
src/main/telemetry/msp_shared.c | 4 ++--
2 files changed, 4 insertions(+), 4 deletions(-)
diff --git a/src/main/telemetry/crsf.h b/src/main/telemetry/crsf.h
index bfe9b9e4f3c..65565888486 100644
--- a/src/main/telemetry/crsf.h
+++ b/src/main/telemetry/crsf.h
@@ -20,8 +20,8 @@
#include "common/time.h"
#include "rx/crsf.h"
-#define CRSF_MSP_RX_BUF_SIZE 128
-#define CRSF_MSP_TX_BUF_SIZE 128
+#define CRSF_MSP_RX_BUF_SIZE 512
+#define CRSF_MSP_TX_BUF_SIZE 512
void initCrsfTelemetry(void);
bool checkCrsfTelemetryState(void);
diff --git a/src/main/telemetry/msp_shared.c b/src/main/telemetry/msp_shared.c
index 4c60a90e707..986c0c3e1aa 100644
--- a/src/main/telemetry/msp_shared.c
+++ b/src/main/telemetry/msp_shared.c
@@ -68,12 +68,12 @@ void initSharedMsp(void)
mspPackage.requestBuffer = (uint8_t *)&mspRxBuffer;
mspPackage.requestPacket = &mspRxPacket;
mspPackage.requestPacket->buf.ptr = mspPackage.requestBuffer;
- mspPackage.requestPacket->buf.end = mspPackage.requestBuffer;
+ mspPackage.requestPacket->buf.end = mspPackage.requestBuffer + sizeof(mspRxBuffer);
mspPackage.responseBuffer = (uint8_t *)&mspTxBuffer;
mspPackage.responsePacket = &mspTxPacket;
mspPackage.responsePacket->buf.ptr = mspPackage.responseBuffer;
- mspPackage.responsePacket->buf.end = mspPackage.responseBuffer;
+ mspPackage.responsePacket->buf.end = mspPackage.responseBuffer + sizeof(mspTxBuffer);
}
static void processMspPacket(void)
From 4c4430ef90f89653c2115074c8c5737a28a1da74 Mon Sep 17 00:00:00 2001
From: KeithCoreDumped
Date: Wed, 4 Feb 2026 17:49:20 +0800
Subject: [PATCH 12/55] fix data length overflow
---
src/main/telemetry/msp_shared.c | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/telemetry/msp_shared.c b/src/main/telemetry/msp_shared.c
index 986c0c3e1aa..5897b1ce557 100644
--- a/src/main/telemetry/msp_shared.c
+++ b/src/main/telemetry/msp_shared.c
@@ -217,7 +217,7 @@ bool sendMspReply(uint8_t payloadSize, mspResponseFnPtr responseFn)
}
sbufWriteU8(payloadBuf, status);
- const uint8_t size = sbufBytesRemaining(txBuf);
+ const uint16_t size = sbufBytesRemaining(txBuf);
if (lastRequestVersion == 1) { // MSPv1
sbufWriteU8(payloadBuf, size);
sbufWriteU8(payloadBuf, mspPackage.responsePacket->cmd);
From 922536955546e0a9ddcbbd868e11e54a516eba25 Mon Sep 17 00:00:00 2001
From: KeithCoreDumped
Date: Wed, 4 Feb 2026 17:49:52 +0800
Subject: [PATCH 13/55] fix: resolve MSP connection hangs due to packet
truncation and buffer initialization when connected via TCP
---
src/main/telemetry/msp_shared.c | 5 +++--
1 file changed, 3 insertions(+), 2 deletions(-)
diff --git a/src/main/telemetry/msp_shared.c b/src/main/telemetry/msp_shared.c
index 5897b1ce557..1589a513596 100644
--- a/src/main/telemetry/msp_shared.c
+++ b/src/main/telemetry/msp_shared.c
@@ -80,7 +80,8 @@ static void processMspPacket(void)
{
mspPackage.responsePacket->cmd = 0;
mspPackage.responsePacket->result = 0;
- mspPackage.responsePacket->buf.end = mspPackage.responseBuffer;
+ mspPackage.responsePacket->buf.ptr = mspPackage.responseBuffer;
+ mspPackage.responsePacket->buf.end = mspPackage.responseBuffer + sizeof(mspTxBuffer);
mspPostProcessFnPtr mspPostProcessFn = NULL;
if (mspFcProcessCommand(mspPackage.requestPacket, mspPackage.responsePacket, &mspPostProcessFn) == MSP_RESULT_ERROR) {
@@ -231,7 +232,7 @@ bool sendMspReply(uint8_t payloadSize, mspResponseFnPtr responseFn)
sbufWriteU8(payloadBuf, (seq++ & TELEMETRY_MSP_SEQ_MASK) | (lastRequestVersion << TELEMETRY_MSP_VER_SHIFT)); // header without 'start' flag
}
- const uint8_t bufferBytesRemaining = sbufBytesRemaining(txBuf);
+ const uint16_t bufferBytesRemaining = sbufBytesRemaining(txBuf);
const uint8_t payloadBytesRemaining = sbufBytesRemaining(payloadBuf);
uint8_t frame[payloadBytesRemaining];
From 24275c03ecb881a28ad030359fcfbf3cf664a903 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sat, 7 Feb 2026 19:53:59 -0600
Subject: [PATCH 14/55] Mark 16 legacy MSP commands as deprecated for removal
in INAV 10.0
Deprecate the following MSP commands with replacement info:
- MSP_ANALOG (110) -> MSP2_INAV_ANALOG
- MSP_MISC (114) / MSP_SET_MISC (207) -> MSP2_INAV_MISC / MSP2_INAV_SET_MISC
- MSP_PIDNAMES (117) -> no replacement needed
- MSP_FILTER_CONFIG (92) / MSP_SET_FILTER_CONFIG (93) -> MSP2_COMMON_SETTING
- MSP_PID_ADVANCED (94) / MSP_SET_PID_ADVANCED (95) -> MSP_INAV_PID
- MSP_OSD_CONFIG (84) / MSP_SET_OSD_CONFIG (85) -> MSP2_INAV_OSD_*
- MSP_POSITION_ESTIMATION_CONFIG (16) / MSP_SET_POSITION_ESTIMATION_CONFIG (17) -> MSP2_COMMON_SETTING
- MSP_SERVO_MIX_RULES (241) / MSP_SET_SERVO_MIX_RULE (242) -> MSP2_INAV_SERVO_MIXER
Commands remain fully functional. This gives third-party developers
a full major release cycle of notice before removal.
Also adds "replaced_by" field to the MSP message JSON schema
(docs/development/msp/format.md) and populates it for all 14 entries.
---
docs/development/msp/format.md | 1 +
docs/development/msp/msp_messages.json | 14 +++++++++++++
src/main/msp/msp_protocol.h | 28 +++++++++++++-------------
3 files changed, 29 insertions(+), 14 deletions(-)
diff --git a/docs/development/msp/format.md b/docs/development/msp/format.md
index e8c6a348c07..bbe7c1fc6fa 100644
--- a/docs/development/msp/format.md
+++ b/docs/development/msp/format.md
@@ -40,6 +40,7 @@
**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 (never or deprecated)\
+**replaced_by**: Optional array of MSP message names that replace this command. Present when a command is deprecated and scheduled for removal. Empty array if no replacement is needed\
**notes**: String with details of message
## Data dict fields:
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index e4c2a39993f..78d3c2f99e2 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -673,6 +673,7 @@
"MSP_POSITION_ESTIMATION_CONFIG": {
"code": 16,
"mspv": 1,
+ "replaced_by": ["MSP2_COMMON_SETTING"],
"request": null,
"reply": {
"payload": [
@@ -727,6 +728,7 @@
"MSP_SET_POSITION_ESTIMATION_CONFIG": {
"code": 17,
"mspv": 1,
+ "replaced_by": ["MSP2_COMMON_SET_SETTING"],
"request": {
"payload": [
{
@@ -2426,6 +2428,7 @@
"MSP_OSD_CONFIG": {
"code": 84,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_OSD_LAYOUTS", "MSP2_INAV_OSD_ALARMS", "MSP2_INAV_OSD_PREFERENCES"],
"request": null,
"reply": {
"payload": [
@@ -2504,6 +2507,7 @@
"MSP_SET_OSD_CONFIG": {
"code": 85,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_OSD_SET_LAYOUT_ITEM", "MSP2_INAV_OSD_SET_ALARMS", "MSP2_INAV_OSD_SET_PREFERENCES"],
"request": null,
"reply": null,
"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.",
@@ -3134,6 +3138,7 @@
"MSP_FILTER_CONFIG": {
"code": 92,
"mspv": 1,
+ "replaced_by": ["MSP2_COMMON_SETTING"],
"request": null,
"reply": {
"payload": [
@@ -3217,6 +3222,7 @@
"MSP_SET_FILTER_CONFIG": {
"code": 93,
"mspv": 1,
+ "replaced_by": ["MSP2_COMMON_SET_SETTING"],
"request": {
"payload": [
{
@@ -3293,6 +3299,7 @@
"MSP_PID_ADVANCED": {
"code": 94,
"mspv": 1,
+ "replaced_by": ["MSP_INAV_PID"],
"request": null,
"reply": {
"payload": [
@@ -3370,6 +3377,7 @@
"MSP_SET_PID_ADVANCED": {
"code": 95,
"mspv": 1,
+ "replaced_by": ["MSP_SET_INAV_PID"],
"request": {
"payload": [
{
@@ -3914,6 +3922,7 @@
"MSP_ANALOG": {
"code": 110,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_ANALOG"],
"request": null,
"reply": {
"payload": [
@@ -4039,6 +4048,7 @@
"MSP_MISC": {
"code": 114,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_MISC"],
"request": null,
"reply": {
"payload": [
@@ -4168,6 +4178,7 @@
"MSP_PIDNAMES": {
"code": 117,
"mspv": 1,
+ "replaced_by": [],
"request": null,
"reply": {
"payload": [
@@ -5135,6 +5146,7 @@
"MSP_SET_MISC": {
"code": 207,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_SET_MISC"],
"request": {
"payload": [
{
@@ -5588,6 +5600,7 @@
"MSP_SERVO_MIX_RULES": {
"code": 241,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_SERVO_MIXER"],
"request": null,
"reply": {
"payload": [
@@ -5644,6 +5657,7 @@
"MSP_SET_SERVO_MIX_RULE": {
"code": 242,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_SET_SERVO_MIXER"],
"request": {
"payload": [
{
diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h
index 5a3af115f9c..fa385fc4f75 100644
--- a/src/main/msp/msp_protocol.h
+++ b/src/main/msp/msp_protocol.h
@@ -110,8 +110,8 @@
#define MSP_CALIBRATION_DATA 14
#define MSP_SET_CALIBRATION_DATA 15
-#define MSP_POSITION_ESTIMATION_CONFIG 16
-#define MSP_SET_POSITION_ESTIMATION_CONFIG 17
+#define MSP_POSITION_ESTIMATION_CONFIG 16 //DEPRECATED in INAV 9.1 - use settings system instead. Will be removed in INAV 10.0
+#define MSP_SET_POSITION_ESTIMATION_CONFIG 17 //DEPRECATED in INAV 9.1 - use settings system instead. Will be removed in INAV 10.0
#define MSP_WP_MISSION_LOAD 18 // Load mission from NVRAM
#define MSP_WP_MISSION_SAVE 19 // Save mission to NVRAM
@@ -189,8 +189,8 @@
#define MSP_TRANSPONDER_CONFIG 82 //out message Get transponder settings
#define MSP_SET_TRANSPONDER_CONFIG 83 //in message Set transponder settings
-#define MSP_OSD_CONFIG 84 //out message Get osd settings - betaflight
-#define MSP_SET_OSD_CONFIG 85 //in message Set osd settings - betaflight
+#define MSP_OSD_CONFIG 84 //DEPRECATED in INAV 9.1 - use MSP2_INAV_OSD_* instead. Will be removed in INAV 10.0
+#define MSP_SET_OSD_CONFIG 85 //DEPRECATED in INAV 9.1 - use MSP2_INAV_OSD_* instead. Will be removed in INAV 10.0
#define MSP_OSD_CHAR_READ 86 //out message Get osd settings - betaflight
#define MSP_OSD_CHAR_WRITE 87 //in message Set osd settings - betaflight
@@ -202,10 +202,10 @@
#define MSP_ADVANCED_CONFIG 90
#define MSP_SET_ADVANCED_CONFIG 91
-#define MSP_FILTER_CONFIG 92
-#define MSP_SET_FILTER_CONFIG 93
-#define MSP_PID_ADVANCED 94
-#define MSP_SET_PID_ADVANCED 95
+#define MSP_FILTER_CONFIG 92 //DEPRECATED in INAV 9.1 - use settings system instead. Will be removed in INAV 10.0
+#define MSP_SET_FILTER_CONFIG 93 //DEPRECATED in INAV 9.1 - use settings system instead. Will be removed in INAV 10.0
+#define MSP_PID_ADVANCED 94 //DEPRECATED in INAV 9.1 - use MSP_INAV_PID/MSP_SET_INAV_PID instead. Will be removed in INAV 10.0
+#define MSP_SET_PID_ADVANCED 95 //DEPRECATED in INAV 9.1 - use MSP_INAV_PID/MSP_SET_INAV_PID instead. Will be removed in INAV 10.0
#define MSP_SENSOR_CONFIG 96
#define MSP_SET_SENSOR_CONFIG 97
@@ -240,12 +240,12 @@
#define MSP_COMP_GPS 107 //out message distance home, direction home
#define MSP_ATTITUDE 108 //out message 2 angles 1 heading
#define MSP_ALTITUDE 109 //out message altitude, variometer
-#define MSP_ANALOG 110 //out message vbat, powermetersum, rssi if available on RX
+#define MSP_ANALOG 110 //DEPRECATED in INAV 9.1 - use MSP2_INAV_ANALOG instead. Will be removed in INAV 10.0
#define MSP_RC_TUNING 111 //out message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
#define MSP_ACTIVEBOXES 113 //out message Active box flags (full width, more than 32 bits)
-#define MSP_MISC 114 //out message powermeter trig
+#define MSP_MISC 114 //DEPRECATED in INAV 9.1 - use MSP2_INAV_MISC instead. Will be removed in INAV 10.0
#define MSP_BOXNAMES 116 //out message the aux switch names
-#define MSP_PIDNAMES 117 //out message the PID names
+#define MSP_PIDNAMES 117 //DEPRECATED in INAV 9.1 - no replacement needed (static data). Will be removed in INAV 10.0
#define MSP_WP 118 //out message get a WP, WP# is in the payload, returns (WP#, lat, lon, alt, flags) WP#0-home, WP#16-poshold
#define MSP_BOXIDS 119 //out message get the permanent IDs associated to BOXes
#define MSP_SERVO_CONFIGURATIONS 120 //out message All servo configurations.
@@ -263,7 +263,7 @@
#define MSP_SET_RC_TUNING 204 //in message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID, yaw expo
#define MSP_ACC_CALIBRATION 205 //in message no param
#define MSP_MAG_CALIBRATION 206 //in message no param
-#define MSP_SET_MISC 207 //in message powermeter trig + 8 free for future use
+#define MSP_SET_MISC 207 //DEPRECATED in INAV 9.1 - use MSP2_INAV_SET_MISC instead. Will be removed in INAV 10.0
#define MSP_RESET_CONF 208 //in message no param
#define MSP_SET_WP 209 //in message sets a given WP (WP#,lat, lon, alt, flags)
#define MSP_SELECT_SETTING 210 //in message Select Setting Number (0-2)
@@ -295,8 +295,8 @@
#define MSP_GPSSTATISTICS 166 //out message get GPS debugging data
#define MSP_ACC_TRIM 240 //out message get acc angle trim values
#define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values
-#define MSP_SERVO_MIX_RULES 241 //out message Returns servo mixer configuration
-#define MSP_SET_SERVO_MIX_RULE 242 //in message Sets servo mixer configuration
+#define MSP_SERVO_MIX_RULES 241 //DEPRECATED in INAV 9.1 - use MSP2_INAV_SERVO_MIXER instead. Will be removed in INAV 10.0
+#define MSP_SET_SERVO_MIX_RULE 242 //DEPRECATED in INAV 9.1 - use MSP2_INAV_SET_SERVO_MIXER instead. Will be removed in INAV 10.0
#define MSP_SET_PASSTHROUGH 245 //in message Sets up passthrough to different peripherals (4way interface, uart, etc...)
#define MSP_RTC 246 //out message Gets the RTC clock (returns: secs(i32) millis(u16) - (0,0) if time is not known)
#define MSP_SET_RTC 247 //in message Sets the RTC clock (args: secs(i32) millis(u16))
From 435e489959b985f9174c8bfad7ab088e7ee760b6 Mon Sep 17 00:00:00 2001
From: Sensei
Date: Sat, 7 Feb 2026 20:32:06 -0600
Subject: [PATCH 15/55] msp_protocol.h change depreciation comment format
Co-authored-by: qodo-code-review[bot] <151058649+qodo-code-review[bot]@users.noreply.github.com>
---
src/main/msp/msp_protocol.h | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h
index fa385fc4f75..e1cbd028293 100644
--- a/src/main/msp/msp_protocol.h
+++ b/src/main/msp/msp_protocol.h
@@ -204,8 +204,8 @@
#define MSP_FILTER_CONFIG 92 //DEPRECATED in INAV 9.1 - use settings system instead. Will be removed in INAV 10.0
#define MSP_SET_FILTER_CONFIG 93 //DEPRECATED in INAV 9.1 - use settings system instead. Will be removed in INAV 10.0
-#define MSP_PID_ADVANCED 94 //DEPRECATED in INAV 9.1 - use MSP_INAV_PID/MSP_SET_INAV_PID instead. Will be removed in INAV 10.0
-#define MSP_SET_PID_ADVANCED 95 //DEPRECATED in INAV 9.1 - use MSP_INAV_PID/MSP_SET_INAV_PID instead. Will be removed in INAV 10.0
+#define MSP_PID_ADVANCED 94 //DEPRECATED in INAV 9.1 - use MSP_INAV_PID instead. Will be removed in INAV 10.0
+#define MSP_SET_PID_ADVANCED 95 //DEPRECATED in INAV 9.1 - use MSP_SET_INAV_PID instead. Will be removed in INAV 10.0
#define MSP_SENSOR_CONFIG 96
#define MSP_SET_SENSOR_CONFIG 97
From b4ca845cde05f7b2b9522e099d2d844efaa4e1a3 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sun, 8 Feb 2026 23:06:27 -0600
Subject: [PATCH 16/55] Fix servo throttle mix outputting wrong position when
disarmed
When disarmed, the servo mixer was unconditionally setting servo outputs
to motorConfig()->mincommand for any servo with a throttle mixer rule.
This ignored servo reversal (negative servoParams rate) and negative
mixer weights, causing reversed throttle servos to go to full output
instead of minimum on disarm - a safety hazard.
Fix by forcing throttle inputs to minimum (-500) before the mixer loop
so the normal pipeline correctly computes safe positions accounting for
reversal and negative weights. Remove the broken post-hoc override.
---
src/main/flight/servos.c | 23 ++++++++++-------------
1 file changed, 10 insertions(+), 13 deletions(-)
diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c
index 9d2720bec09..b56d97eec87 100755
--- a/src/main/flight/servos.c
+++ b/src/main/flight/servos.c
@@ -425,6 +425,16 @@ void servoMixer(float dT)
simulatorData.input[INPUT_STABILIZED_THROTTLE] = input[INPUT_STABILIZED_THROTTLE];
#endif
+ /*
+ * When disarmed, force throttle inputs to minimum so the mixer pipeline
+ * computes the correct safe servo position accounting for servo reversal
+ * and negative mixer weights.
+ */
+ if (!ARMING_FLAG(ARMED)) {
+ input[INPUT_STABILIZED_THROTTLE] = -500;
+ input[INPUT_RC_THROTTLE] = -500;
+ }
+
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
servo[i] = 0;
}
@@ -487,19 +497,6 @@ void servoMixer(float dT)
servo[i] = constrain(servo[i], servoParams(i)->min, servoParams(i)->max);
}
- /*
- * When not armed, apply servo low position to all outputs that include a throttle or stabilizet throttle in the mix
- */
- if (!ARMING_FLAG(ARMED)) {
- for (int i = 0; i < servoRuleCount; i++) {
- const uint8_t target = currentServoMixer[i].targetChannel;
- const uint8_t from = currentServoMixer[i].inputSource;
-
- if (from == INPUT_STABILIZED_THROTTLE || from == INPUT_RC_THROTTLE) {
- servo[target] = motorConfig()->mincommand;
- }
- }
- }
}
#define SERVO_AUTOTRIM_TIMER_MS 2000
From 31bb99e809d774fdcfacdfda204147165c9d01f3 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Mon, 9 Feb 2026 12:09:03 -0600
Subject: [PATCH 17/55] Fix SD card busy-wait loops that can lock up flight
controller
Add timeout guards to unbounded busy-wait loops in the SD card drivers.
A problematic SD card could cause sdcardSpi_deselect() to spin forever
on busIsBusy(), freezing the entire FC since blackbox runs inline with
the PID loop.
- sdcard_spi.c: Add 100K-iteration timeout to sdcardSpi_deselect(),
matching the existing pattern in sdcardSpi_init(). On timeout,
increment failureCount and disable card at threshold.
- sdmmc_sdio_f4xx.c: Add 10K-iteration timeout to DMA disable loop.
Add SD_DATATIMEOUT software backstop to three FIFO read loops
(SD_HighSpeed, SD_GetCardStatus, SD_FindSCR) as defense-in-depth
behind the hardware SDIO_STA_DTIMEOUT.
---
src/main/drivers/sdcard/sdcard_spi.c | 12 +++++++++++-
src/main/drivers/sdcard/sdmmc_sdio_f4xx.c | 15 ++++++++++++++-
2 files changed, 25 insertions(+), 2 deletions(-)
diff --git a/src/main/drivers/sdcard/sdcard_spi.c b/src/main/drivers/sdcard/sdcard_spi.c
index 214f1fd8105..6446ec09164 100644
--- a/src/main/drivers/sdcard/sdcard_spi.c
+++ b/src/main/drivers/sdcard/sdcard_spi.c
@@ -62,7 +62,17 @@ static void sdcardSpi_deselect(void)
// As per the SD-card spec, give the card 8 dummy clocks so it can finish its operation
//spiTransferByte(SDCARD_SPI_INSTANCE, 0xFF);
- while (busIsBusy(sdcard.dev)) { __NOP(); }
+ int timeout = 100000;
+ while (busIsBusy(sdcard.dev)) {
+ if (timeout-- == 0) {
+ sdcard.failureCount++;
+ if (sdcard.failureCount >= SDCARD_MAX_CONSECUTIVE_FAILURES) {
+ sdcard.state = SDCARD_STATE_NOT_PRESENT;
+ }
+ break;
+ }
+ __NOP();
+ }
busDeselectDevice(sdcard.dev);
}
diff --git a/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c b/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
index 8999cdd7197..917574871f9 100644
--- a/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
+++ b/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
@@ -549,7 +549,8 @@ static void SD_StartBlockTransfert(uint32_t* pBuffer, uint32_t BlockSize, uint32
}
pDMA->CR &= ~DMA_SxCR_EN; // Disable the Peripheral
- while (pDMA->CR & DMA_SxCR_EN);
+ int dmaTimeout = 10000;
+ while ((pDMA->CR & DMA_SxCR_EN) && dmaTimeout-- > 0);
pDMA->NDTR = (uint32_t) (BlockSize * NumberOfBlocks) / 4; // Configure DMA Stream data length
pDMA->M0AR = (uint32_t) pBuffer; // Configure DMA Stream memory address
@@ -1014,7 +1015,11 @@ SD_Error_t SD_HighSpeed(void)
return ErrorState;
}
+ uint32_t swTimeout = SD_DATATIMEOUT;
while ((SDIO->STA & (SDIO_STA_RXOVERR | SDIO_STA_DCRCFAIL | SDIO_STA_DTIMEOUT | SDIO_STA_DBCKEND)) == 0) {
+ if (swTimeout-- == 0) {
+ break;
+ }
if ((SDIO->STA & SDIO_STA_RXFIFOHF) != 0) {
for(Count = 0; Count < 8; Count++) {
*(Buffer + Count) = SDIO->FIFO;
@@ -1124,7 +1129,11 @@ SD_Error_t SD_GetCardStatus(SD_CardStatus_t* pCardStatus)
}
// Get status data
+ uint32_t statTimeout = SD_DATATIMEOUT;
while ((SDIO->STA & (SDIO_STA_RXOVERR | SDIO_STA_DCRCFAIL | SDIO_STA_DTIMEOUT | SDIO_STA_DBCKEND)) == 0) {
+ if (statTimeout-- == 0) {
+ break;
+ }
if ((SDIO->STA & SDIO_STA_RXFIFOHF) != 0) {
for(Count = 0; Count < 8; Count++) {
Status[Count] = SDIO->FIFO;
@@ -1318,7 +1327,11 @@ static SD_Error_t SD_FindSCR(uint32_t *pSCR)
// Send ACMD51 SD_APP_SEND_SCR with argument as 0
if ((ErrorState = SD_TransmitCommand((SD_CMD_SD_APP_SEND_SCR | SD_CMD_RESPONSE_SHORT), 0, 1)) == SD_OK) {
+ uint32_t scrTimeout = SD_DATATIMEOUT;
while ((SDIO->STA & (SDIO_STA_RXOVERR | SDIO_STA_DCRCFAIL | SDIO_STA_DTIMEOUT | SDIO_STA_DBCKEND)) == 0) {
+ if (scrTimeout-- == 0) {
+ break;
+ }
if ((SDIO->STA & SDIO_STA_RXDAVL) != 0) {
*(tempscr + Index) = SDIO->FIFO;
Index++;
From 321e8e653a25425e869dbcac41b25707a10dc1e9 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Mon, 9 Feb 2026 13:10:44 -0600
Subject: [PATCH 18/55] Add error handling when SDIO DMA fails to disable
If the DMA stream remains enabled after the timeout, set
TransferError and return early to avoid configuring a
still-active DMA stream.
---
src/main/drivers/sdcard/sdmmc_sdio_f4xx.c | 5 +++++
1 file changed, 5 insertions(+)
diff --git a/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c b/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
index 917574871f9..aa534799002 100644
--- a/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
+++ b/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
@@ -552,6 +552,11 @@ static void SD_StartBlockTransfert(uint32_t* pBuffer, uint32_t BlockSize, uint32
int dmaTimeout = 10000;
while ((pDMA->CR & DMA_SxCR_EN) && dmaTimeout-- > 0);
+ if (pDMA->CR & DMA_SxCR_EN) {
+ SD_Handle.TransferError = SD_DATA_TIMEOUT;
+ return;
+ }
+
pDMA->NDTR = (uint32_t) (BlockSize * NumberOfBlocks) / 4; // Configure DMA Stream data length
pDMA->M0AR = (uint32_t) pBuffer; // Configure DMA Stream memory address
From 3529fcdda70681696caee39a7f7a0ebccb41193b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Pawe=C5=82=20Spychalski?=
Date: Thu, 12 Feb 2026 12:18:06 +0100
Subject: [PATCH 19/55] Brahma H7 target files
---
src/main/target/BRAHMA_H7/CMakeLists.txt | 1 +
src/main/target/BRAHMA_H7/config.c | 32 ++++
src/main/target/BRAHMA_H7/target.c | 53 +++++++
src/main/target/BRAHMA_H7/target.h | 185 +++++++++++++++++++++++
4 files changed, 271 insertions(+)
create mode 100644 src/main/target/BRAHMA_H7/CMakeLists.txt
create mode 100644 src/main/target/BRAHMA_H7/config.c
create mode 100644 src/main/target/BRAHMA_H7/target.c
create mode 100644 src/main/target/BRAHMA_H7/target.h
diff --git a/src/main/target/BRAHMA_H7/CMakeLists.txt b/src/main/target/BRAHMA_H7/CMakeLists.txt
new file mode 100644
index 00000000000..afb710016ad
--- /dev/null
+++ b/src/main/target/BRAHMA_H7/CMakeLists.txt
@@ -0,0 +1 @@
+target_stm32h743xi(BRAHMA_H7)
diff --git a/src/main/target/BRAHMA_H7/config.c b/src/main/target/BRAHMA_H7/config.c
new file mode 100644
index 00000000000..1065971614a
--- /dev/null
+++ b/src/main/target/BRAHMA_H7/config.c
@@ -0,0 +1,32 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight 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.
+ *
+ * Cleanflight 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 Cleanflight. If not, see .
+ */
+
+#include
+
+#include "platform.h"
+
+#include "fc/fc_msp_box.h"
+#include "fc/config.h"
+
+#include "io/piniobox.h"
+
+void targetConfiguration(void)
+{
+ pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
+ pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
+ beeperConfigMutable()->pwmMode = true;
+}
diff --git a/src/main/target/BRAHMA_H7/target.c b/src/main/target/BRAHMA_H7/target.c
new file mode 100644
index 00000000000..3ffd307d90e
--- /dev/null
+++ b/src/main/target/BRAHMA_H7/target.c
@@ -0,0 +1,53 @@
+/*
+ * 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/bus.h"
+#include "drivers/io.h"
+#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
+#include "drivers/pinio.h"
+#include "drivers/sensor.h"
+
+BUSDEV_REGISTER_SPI_TAG(busdev_icm42605, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
+BUSDEV_REGISTER_SPI_TAG(busdev_icm42605_2, DEVHW_ICM42605, ICM42605_SPI_BUS_2, ICM42605_CS_PIN_2, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN_2);
+
+timerHardware_t timerHardware[] = {
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 1), // S2
+
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 2), // S3
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 3), // S4
+ DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 4), // S5
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 5), // S6
+
+ DEF_TIM(TIM4, CH1, PD12, TIM_USE_OUTPUT_AUTO, 0, 6), // S7
+ DEF_TIM(TIM4, CH2, PD13, TIM_USE_OUTPUT_AUTO, 0, 7), // S8
+ DEF_TIM(TIM4, CH3, PD14, TIM_USE_OUTPUT_AUTO, 0, 0), // S9
+ DEF_TIM(TIM4, CH4, PD15, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 DMA_NONE
+
+ DEF_TIM(TIM15, CH1, PE5, TIM_USE_OUTPUT_AUTO, 0, 0), // S11
+ DEF_TIM(TIM15, CH2, PE6, TIM_USE_OUTPUT_AUTO, 0, 0), // S12 DMA_NONE
+
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812
+ // DEF_TIM(TIM2, CH1, PA15, TIM_USE_BEEPER, 0, 0), // BEEPER PWM
+};
+
+const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
diff --git a/src/main/target/BRAHMA_H7/target.h b/src/main/target/BRAHMA_H7/target.h
new file mode 100644
index 00000000000..175d01a1376
--- /dev/null
+++ b/src/main/target/BRAHMA_H7/target.h
@@ -0,0 +1,185 @@
+/*
+ * 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/.
+ */
+
+#pragma once
+
+#define TARGET_BOARD_IDENTIFIER "DMH7"
+#define USBD_PRODUCT_STRING "BRAHMA_H7"
+
+#define USE_TARGET_CONFIG
+
+#define LED0 PE3
+#define LED1 PA4
+
+#define BEEPER PA15
+#define BEEPER_INVERTED
+// #define BEEPER_PWM_FREQUENCY 2000
+
+// *************** IMU generic ***********************
+#define USE_DUAL_GYRO
+#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS
+
+// *************** SPI1 IMU0 ICM42605 ****************
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PD7
+
+#define USE_IMU_ICM42605
+
+#define IMU_ICM42605_ALIGN CW180_DEG
+#define ICM42605_SPI_BUS BUS_SPI1
+#define ICM42605_CS_PIN PC15
+
+// *************** SPI4 IMU1 ICM42605 **************
+#define USE_SPI_DEVICE_4
+#define SPI4_SCK_PIN PE12
+#define SPI4_MISO_PIN PE13
+#define SPI4_MOSI_PIN PE14
+
+#define IMU_ICM42605_ALIGN_2 CW180_DEG
+#define ICM42605_SPI_BUS_2 BUS_SPI4
+#define ICM42605_CS_PIN_2 PE11
+
+// *************** SPI2 OSD ***********************
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_MAX7456
+#define MAX7456_SPI_BUS BUS_SPI2
+#define MAX7456_CS_PIN PB12
+
+// *************** SPI3 ************************
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
+
+// *************** I2C /Baro/Mag *********************
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
+
+#define USE_I2C_DEVICE_2
+#define I2C2_SCL PB10
+#define I2C2_SDA PB11
+
+#define USE_BARO
+#define BARO_I2C_BUS BUS_I2C2
+#define USE_BARO_ALL
+
+#define USE_MAG
+#define MAG_I2C_BUS BUS_I2C1
+#define USE_MAG_ALL
+
+#define TEMPERATURE_I2C_BUS BUS_I2C1
+#define PITOT_I2C_BUS BUS_I2C1
+
+#define USE_RANGEFINDER
+#define RANGEFINDER_I2C_BUS BUS_I2C1
+// *************** UART *****************************
+#define USE_VCP
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+
+#define USE_UART2
+#define UART2_TX_PIN PD5
+#define UART2_RX_PIN PD6
+
+#define USE_UART3
+#define UART3_TX_PIN PD8
+#define UART3_RX_PIN PD9
+
+#define USE_UART4
+#define UART4_TX_PIN PB9
+#define UART4_RX_PIN PB8
+
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+
+#define USE_UART7
+#define UART7_TX_PIN PE8
+#define UART7_RX_PIN PE7
+
+#define USE_UART8
+#define UART8_TX_PIN PE1
+#define UART8_RX_PIN PE0
+
+#define SERIAL_PORT_COUNT 8
+
+#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
+#define SERIALRX_PROVIDER SERIALRX_CRSF
+#define SERIALRX_UART SERIAL_PORT_USART2
+
+// *************** SDIO SD BLACKBOX*******************
+#define USE_SDCARD
+#define USE_SDCARD_SDIO
+#define SDCARD_SDIO_DEVICE SDIODEV_1
+#define SDCARD_SDIO_4BIT
+
+#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
+
+// *************** ADC *****************************
+#define USE_ADC
+#define ADC_INSTANCE ADC1
+
+#define ADC_CHANNEL_1_PIN PC0 //ADC123 VBAT1
+#define ADC_CHANNEL_2_PIN PC1 //ADC123 CURR1
+#define ADC_CHANNEL_3_PIN PC5 //ADC12 RSSI
+
+#define VBAT_ADC_CHANNEL ADC_CHN_1
+#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
+#define RSSI_ADC_CHANNEL ADC_CHN_3
+
+// *************** PINIO ***************************
+#define USE_PINIO
+#define USE_PINIOBOX
+#define PINIO1_PIN PD10
+#define PINIO2_PIN PD11
+
+// *************** LEDSTRIP ************************
+#define USE_LED_STRIP
+#define WS2811_PIN PA8
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
+#define CURRENT_METER_SCALE 250
+
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+#define TARGET_IO_PORTA (0xffff & ~(BIT(14) | BIT(13)))
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+#define TARGET_IO_PORTE 0xffff
+
+#define MAX_PWM_OUTPUT_PORTS 13
+#define USE_DSHOT
+#define USE_ESC_SENSOR
From cb834eb616593cb03487b06eb218118b1a9efd43 Mon Sep 17 00:00:00 2001
From: Sensei
Date: Sat, 14 Feb 2026 22:45:45 -0600
Subject: [PATCH 20/55] NEW_HARDWARE_POLICY.md: Use Discord rather than email
Updated contact method for hardware feature requests.
---
docs/policies/NEW_HARDWARE_POLICY.md | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/docs/policies/NEW_HARDWARE_POLICY.md b/docs/policies/NEW_HARDWARE_POLICY.md
index bd4bddedf05..10767524700 100644
--- a/docs/policies/NEW_HARDWARE_POLICY.md
+++ b/docs/policies/NEW_HARDWARE_POLICY.md
@@ -67,7 +67,7 @@ If one of the core developers has the hardware in possession they may opt in and
1. Requester is advised to open a feature request to add support for certain hardware to INAV by following [this link](https://github.com/iNavFlight/inav/issues/new/choose)
-2. After opening a feature request, Requester is advised to contact the core development team by [email](mailto:coredev@inavflight.com) mentioning the open feature request and communicate with developer team via email to arrange hardware and specifications delivery.
+2. After opening a feature request, Requester is advised to contact the core development team via [Discord](https://discord.gg/peg2hhbYwN) mentioning the open feature request and communicate with developer team via email to arrange hardware and specifications delivery.
## See also
From 3dd3fc7bbf585a2e58f2028c62eb182a8ac75c90 Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Mon, 16 Feb 2026 12:56:24 +0000
Subject: [PATCH 21/55] change default cycle time
---
docs/Settings.md | 2 +-
src/main/fc/settings.yaml | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/docs/Settings.md b/docs/Settings.md
index 14859d65cbc..ef2429733d0 100644
--- a/docs/Settings.md
+++ b/docs/Settings.md
@@ -3098,7 +3098,7 @@ Cycle time for display of full multifunction warning messages [s]. Full warnings
| Default | Min | Max |
| --- | --- | --- |
-| 30 | 0 | 60 |
+| 5 | 0 | 60 |
---
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index ff66b57df26..62ba8089b4e 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -3909,7 +3909,7 @@ groups:
field: multifunction_warning_cycle_time
min: 0
max: 60
- default_value: 30
+ default_value: 5
- name: PG_OSD_COMMON_CONFIG
type: osdCommonConfig_t
From 1d370a6d68df8e71e3d037081d284f7937f6a50c Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Mon, 16 Feb 2026 23:12:08 -0600
Subject: [PATCH 22/55] Add SDMODELH7V2 target (STM32H743)
SDMODEL SDH7 V2 flight controller with MPU6000 on SPI4 (CW270),
MAX7456 OSD on SPI2, SD card blackbox on SPI1, BMP280/MS5611 baro
and IST8310 mag on I2C1, 8 motor outputs across TIM2/3/5/8,
VCP + 6 UARTs (UART7 RX-only for ESC sensor).
---
src/main/target/SDMODELH7V2/CMakeLists.txt | 1 +
src/main/target/SDMODELH7V2/target.c | 46 ++++++
src/main/target/SDMODELH7V2/target.h | 178 +++++++++++++++++++++
3 files changed, 225 insertions(+)
create mode 100644 src/main/target/SDMODELH7V2/CMakeLists.txt
create mode 100644 src/main/target/SDMODELH7V2/target.c
create mode 100644 src/main/target/SDMODELH7V2/target.h
diff --git a/src/main/target/SDMODELH7V2/CMakeLists.txt b/src/main/target/SDMODELH7V2/CMakeLists.txt
new file mode 100644
index 00000000000..ac26094e636
--- /dev/null
+++ b/src/main/target/SDMODELH7V2/CMakeLists.txt
@@ -0,0 +1 @@
+target_stm32h743xi(SDMODELH7V2)
diff --git a/src/main/target/SDMODELH7V2/target.c b/src/main/target/SDMODELH7V2/target.c
new file mode 100644
index 00000000000..ee01b45327f
--- /dev/null
+++ b/src/main/target/SDMODELH7V2/target.c
@@ -0,0 +1,46 @@
+/*
+ * 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/bus.h"
+#include "drivers/io.h"
+#include "drivers/pwm_mapping.h"
+#include "drivers/timer.h"
+#include "drivers/pinio.h"
+#include "drivers/sensor.h"
+
+timerHardware_t timerHardware[] = {
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // M1
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 1), // M2
+
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_OUTPUT_AUTO, 0, 2), // M3
+ DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 3), // M4
+
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_OUTPUT_AUTO, 0, 4), // M5
+ DEF_TIM(TIM5, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 5), // M6
+
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 6), // M7
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 7), // M8
+
+ DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 14), // LED strip
+ DEF_TIM(TIM1, CH1, PE9, TIM_USE_ANY, 0, 12), // Camera control
+};
+
+const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
diff --git a/src/main/target/SDMODELH7V2/target.h b/src/main/target/SDMODELH7V2/target.h
new file mode 100644
index 00000000000..b49697cd80f
--- /dev/null
+++ b/src/main/target/SDMODELH7V2/target.h
@@ -0,0 +1,178 @@
+/*
+ * 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 "SDH7V2"
+#define USBD_PRODUCT_STRING "SDMODELH7V2"
+
+#define USE_TARGET_CONFIG
+
+// *************** LED / BEEPER **********************
+#define LED0 PC2
+
+#define BEEPER PC13
+#define BEEPER_INVERTED
+
+// *************** SPI1 - SD Card ********************
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+
+// *************** SPI2 - OSD (MAX7456) **************
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_MAX7456
+#define MAX7456_SPI_BUS BUS_SPI2
+#define MAX7456_CS_PIN PB12
+
+// *************** SPI4 - IMU (MPU6000) **************
+#define USE_SPI_DEVICE_4
+#define SPI4_SCK_PIN PE2
+#define SPI4_MISO_PIN PE5
+#define SPI4_MOSI_PIN PE6
+
+#define USE_IMU_MPU6000
+#define IMU_MPU6000_ALIGN CW270_DEG
+#define MPU6000_SPI_BUS BUS_SPI4
+#define MPU6000_CS_PIN PE4
+#define MPU6000_EXTI_PIN PE1
+
+// *************** I2C1 - Baro / Mag *****************
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
+
+#define USE_BARO
+#define BARO_I2C_BUS BUS_I2C1
+#define USE_BARO_BMP280
+#define USE_BARO_MS5611
+
+#define USE_MAG
+#define MAG_I2C_BUS BUS_I2C1
+#define USE_MAG_IST8310
+#define USE_MAG_ALL
+
+#define TEMPERATURE_I2C_BUS BUS_I2C1
+#define PITOT_I2C_BUS BUS_I2C1
+
+#define USE_RANGEFINDER
+#define RANGEFINDER_I2C_BUS BUS_I2C1
+
+// *************** SD Card (SPI) *********************
+#define USE_SDCARD
+#define USE_SDCARD_SPI
+#define SDCARD_SPI_BUS BUS_SPI1
+#define SDCARD_CS_PIN PA4
+#define SDCARD_DETECT_PIN PA3
+#define SDCARD_DETECT_INVERTED
+
+#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
+
+// *************** UART ******************************
+#define USE_VCP
+
+#define USE_UART1
+#define UART1_TX_PIN PA9
+#define UART1_RX_PIN PA10
+
+#define USE_UART2
+#define UART2_TX_PIN PD5
+#define UART2_RX_PIN PD6
+
+#define USE_UART3
+#define UART3_TX_PIN PD8
+#define UART3_RX_PIN PD9
+
+#define USE_UART4
+#define UART4_TX_PIN PD1
+#define UART4_RX_PIN PD0
+
+#define USE_UART6
+#define UART6_TX_PIN PC6
+#define UART6_RX_PIN PC7
+
+// UART7 RX-only (ESC sensor); TX pin not routed but AF mapping requires a valid pin
+#define USE_UART7
+#define UART7_TX_PIN PE8
+#define UART7_RX_PIN PE7
+
+#define SERIAL_PORT_COUNT 7 // VCP, UART1-4, UART6, UART7
+
+#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
+#define SERIALRX_PROVIDER SERIALRX_CRSF
+#define SERIALRX_UART SERIAL_PORT_USART6
+
+// *************** ADC *******************************
+#define USE_ADC
+#define ADC_INSTANCE ADC1
+
+#define ADC_CHANNEL_1_PIN PC0
+#define ADC_CHANNEL_2_PIN PC1
+#define ADC_CHANNEL_3_PIN PC5
+
+#define VBAT_ADC_CHANNEL ADC_CHN_1
+#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
+#define RSSI_ADC_CHANNEL ADC_CHN_3
+
+// BF DEFAULT_VOLTAGE_METER_SCALE=109, BF DEFAULT_CURRENT_METER_SCALE=168
+// INAV uses a different scaling formula; these values approximate the same
+// physical measurement. Users should calibrate via the configurator.
+#define VBAT_SCALE_DEFAULT 1090
+#define CURRENT_METER_SCALE 168
+
+// *************** USB detect ************************
+#define USB_DETECT_PIN PA8
+
+// *************** PINIO *****************************
+#define USE_PINIO
+#define USE_PINIOBOX
+#define PINIO1_PIN PE13
+#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
+#define PINIO2_PIN PB11
+#define PINIO2_FLAGS PINIO_FLAGS_INVERTED
+
+// *************** LED STRIP *************************
+#define USE_LED_STRIP
+#define WS2811_PIN PD12
+
+// *************** DEFAULT FEATURES ******************
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX)
+
+// *************** SERIAL 4WAY ***********************
+#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+
+// *************** ESC SENSOR ************************
+#define USE_ESC_SENSOR
+
+// *************** DSHOT *****************************
+#define USE_DSHOT
+
+// *************** IO PORT MASK **********************
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+#define TARGET_IO_PORTE 0xffff
+
+#define MAX_PWM_OUTPUT_PORTS 8
From 3a93f2402b6148c7e55c2de4b5a1a50bf068b5d8 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Tue, 17 Feb 2026 00:15:50 -0600
Subject: [PATCH 23/55] SDMODELH7V2: replace camera control with USER1/USER2
PINIO, preset UART2 for onboard Bluetooth MSP
Remove the camera control timer output on PE9. Add config.c to wire
PINIO1/PINIO2 to USER1/USER2 mode boxes and preset UART2 for MSP at
115200 baud since it is connected to an onboard Bluetooth module.
---
src/main/target/SDMODELH7V2/config.c | 37 ++++++++++++++++++++++++++++
src/main/target/SDMODELH7V2/target.c | 1 -
2 files changed, 37 insertions(+), 1 deletion(-)
create mode 100644 src/main/target/SDMODELH7V2/config.c
diff --git a/src/main/target/SDMODELH7V2/config.c b/src/main/target/SDMODELH7V2/config.c
new file mode 100644
index 00000000000..54ecc6f7627
--- /dev/null
+++ b/src/main/target/SDMODELH7V2/config.c
@@ -0,0 +1,37 @@
+/*
+ * 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 "fc/fc_msp_box.h"
+#include "fc/config.h"
+
+#include "io/piniobox.h"
+#include "drivers/serial.h"
+#include "io/serial.h"
+
+void targetConfiguration(void)
+{
+ pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
+ pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
+
+ // UART2 is connected to an onboard Bluetooth module (not user-accessible)
+ serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_MSP;
+ serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].msp_baudrateIndex = BAUD_115200;
+}
diff --git a/src/main/target/SDMODELH7V2/target.c b/src/main/target/SDMODELH7V2/target.c
index ee01b45327f..b3da3c075b1 100644
--- a/src/main/target/SDMODELH7V2/target.c
+++ b/src/main/target/SDMODELH7V2/target.c
@@ -40,7 +40,6 @@ timerHardware_t timerHardware[] = {
DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 7), // M8
DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 14), // LED strip
- DEF_TIM(TIM1, CH1, PE9, TIM_USE_ANY, 0, 12), // Camera control
};
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
From 1a1b420f3efab58f0487fd054dae62d5da11f269 Mon Sep 17 00:00:00 2001
From: cluez0r
Date: Fri, 20 Feb 2026 08:45:06 +0100
Subject: [PATCH 24/55] Bugfix: SDIO capacity shows incorrectly on F4 devices
---
src/main/drivers/sdcard/sdmmc_sdio_f4xx.c | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c b/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
index 8999cdd7197..c0076a5682d 100644
--- a/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
+++ b/src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
@@ -772,7 +772,7 @@ SD_Error_t SD_GetCardInfo(void)
SD_CardInfo.CardCapacity = (SD_CardInfo.SD_csd.DeviceSize + 1) ;
SD_CardInfo.CardCapacity *= (1 << (SD_CardInfo.SD_csd.DeviceSizeMul + 2));
SD_CardInfo.CardBlockSize = 1 << (SD_CardInfo.SD_csd.RdBlockLen);
- SD_CardInfo.CardCapacity *= SD_CardInfo.CardBlockSize;
+ SD_CardInfo.CardCapacity = SD_CardInfo.CardCapacity * SD_CardInfo.CardBlockSize / 512; // In 512 byte blocks
}
else if (SD_CardType == SD_HIGH_CAPACITY) {
// Byte 7
From 3a3709d765dc7bbacd87e56b9b32623084da3334 Mon Sep 17 00:00:00 2001
From: daijoubu
Date: Fri, 20 Feb 2026 21:45:14 -0800
Subject: [PATCH 25/55] Fix USB VCP lockup on disconnect (STM32F4)
Two issues fixed:
1. serial.c: serialIsConnected() was not returning the result from
the vtable isConnected call, always returning true regardless of
actual connection state.
2. vcpf4/usbd_cdc_vcp.c: VCP_DataTx() had infinite loops waiting for
TX state and buffer space. If USB was disconnected, these loops
would never exit, locking up the flight controller.
Added 50ms timeout to both blocking loops. On timeout, returns
USBD_FAIL and CDC_Send_DATA returns 0 to indicate failure.
Tested on SPEEDYBEEF405WING - FC continues operating normally after
USB disconnect instead of locking up.
Co-Authored-By: Claude Opus 4.6
---
src/main/drivers/serial.c | 2 +-
src/main/vcpf4/usbd_cdc_vcp.c | 17 +++++++++++++++--
2 files changed, 16 insertions(+), 3 deletions(-)
diff --git a/src/main/drivers/serial.c b/src/main/drivers/serial.c
index dc625aaa354..590a36002b2 100644
--- a/src/main/drivers/serial.c
+++ b/src/main/drivers/serial.c
@@ -111,7 +111,7 @@ void serialEndWrite(serialPort_t *instance)
bool serialIsConnected(const serialPort_t *instance)
{
if (instance->vTable->isConnected)
- instance->vTable->isConnected(instance);
+ return(instance->vTable->isConnected(instance));
// If API is not defined - assume connected
return true;
diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c
index 15c1f7e39d9..a29eb70f4c4 100644
--- a/src/main/vcpf4/usbd_cdc_vcp.c
+++ b/src/main/vcpf4/usbd_cdc_vcp.c
@@ -178,7 +178,9 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
*******************************************************************************/
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
{
- VCP_DataTx(ptrBuffer, sendLength);
+ if (VCP_DataTx(ptrBuffer, sendLength) != USBD_OK) {
+ return 0;
+ }
return sendLength;
}
@@ -194,18 +196,29 @@ uint32_t CDC_Send_FreeBytes(void)
* @param Len: Number of data to be sent (in bytes)
* @retval Result of the operation: USBD_OK if all operations are OK else VCP_FAIL
*/
+#define VCP_WRITE_TIMEOUT_MS 50
+
static uint16_t VCP_DataTx(const uint8_t* Buf, uint32_t Len)
{
+ uint32_t start = millis();
+
/*
make sure that any paragraph end frame is not in play
could just check for: USB_CDC_ZLP, but better to be safe
and wait for any existing transmission to complete.
*/
- while (USB_Tx_State != 0);
+ while (USB_Tx_State != 0) {
+ if (millis() - start > VCP_WRITE_TIMEOUT_MS) {
+ return USBD_FAIL;
+ }
+ }
for (uint32_t i = 0; i < Len; i++) {
// Stall if the ring buffer is full
while (((APP_Rx_ptr_in + 1) % APP_RX_DATA_SIZE) == APP_Rx_ptr_out) {
+ if (millis() - start > VCP_WRITE_TIMEOUT_MS) {
+ return USBD_FAIL;
+ }
delay(1);
}
From 692d6400f73efd1c21e9340c7967ddfbd60fb722 Mon Sep 17 00:00:00 2001
From: daijoubu
Date: Fri, 20 Feb 2026 21:49:34 -0800
Subject: [PATCH 26/55] Fix USB VCP lockup on disconnect (STM32F7/H7)
Same fix as STM32F4: added 50ms timeout to blocking loops in
CDC_Send_DATA() that wait for TX state and buffer space.
On timeout, returns partial byte count (or 0) instead of blocking
forever when USB is disconnected.
Co-Authored-By: Claude Opus 4.6
---
src/main/vcp_hal/usbd_cdc_interface.c | 13 ++++++++++++-
1 file changed, 12 insertions(+), 1 deletion(-)
diff --git a/src/main/vcp_hal/usbd_cdc_interface.c b/src/main/vcp_hal/usbd_cdc_interface.c
index dbc093fb641..7ad16084ad9 100644
--- a/src/main/vcp_hal/usbd_cdc_interface.c
+++ b/src/main/vcp_hal/usbd_cdc_interface.c
@@ -415,6 +415,8 @@ uint32_t CDC_Send_FreeBytes(void)
* @param sendLength: Number of data to be sent (in bytes)
* @retval Bytes sent
*/
+#define VCP_WRITE_TIMEOUT_MS 50
+
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
{
#if defined(STM32H7)
@@ -423,13 +425,22 @@ uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pCDC_ClassData;
#endif
- while (hcdc->TxState != 0);
+ uint32_t start = millis();
+
+ while (hcdc->TxState != 0) {
+ if (millis() - start > VCP_WRITE_TIMEOUT_MS) {
+ return 0;
+ }
+ }
for (uint32_t i = 0; i < sendLength; i++)
{
UserTxBuffer[UserTxBufPtrIn] = ptrBuffer[i];
UserTxBufPtrIn = (UserTxBufPtrIn + 1) % APP_TX_DATA_SIZE;
while (CDC_Send_FreeBytes() == 0) {
+ if (millis() - start > VCP_WRITE_TIMEOUT_MS) {
+ return i; // Return partial count
+ }
delay(1);
}
}
From 502095ada9ab8a2656b2230a231ca93f2cfada11 Mon Sep 17 00:00:00 2001
From: daijoubu
Date: Fri, 20 Feb 2026 21:54:54 -0800
Subject: [PATCH 27/55] Fix CDC_Send_FreeBytes buffer calculation (STM32F4)
The previous implementation incorrectly subtracted RX buffer usage
from TX buffer size. Fixed to properly calculate free space in the
outbound (APP_Rx) circular buffer using the correct pointer math.
Co-Authored-By: Claude Opus 4.6
---
src/main/vcpf4/usbd_cdc_vcp.c | 11 ++++++++++-
1 file changed, 10 insertions(+), 1 deletion(-)
diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c
index a29eb70f4c4..7511f617eb4 100644
--- a/src/main/vcpf4/usbd_cdc_vcp.c
+++ b/src/main/vcpf4/usbd_cdc_vcp.c
@@ -186,7 +186,16 @@ uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
uint32_t CDC_Send_FreeBytes(void)
{
- return APP_RX_DATA_SIZE - CDC_Receive_BytesAvailable();
+ // Calculate free space in APP_Rx_Buffer (outbound to host)
+ // Using correct circular buffer math with volatile pointers
+ uint32_t ptr_in = APP_Rx_ptr_in;
+ uint32_t ptr_out = APP_Rx_ptr_out;
+
+ if (ptr_out > ptr_in) {
+ return ptr_out - ptr_in - 1;
+ } else {
+ return APP_RX_DATA_SIZE + ptr_out - ptr_in - 1;
+ }
}
/**
From bc913862a3054b26c6ad6782a6b6ab100d92f7de Mon Sep 17 00:00:00 2001
From: daijoubu
Date: Fri, 20 Feb 2026 21:55:01 -0800
Subject: [PATCH 28/55] Add DTR tracking for USB VCP connection detection
Register callback for CDC control line state changes to track when
the host has actually opened the COM port (DTR signal). This provides
more reliable connection detection than just checking USB enumeration
state.
usbVcpIsConnected() now returns true only when:
- USB is connected (hardware)
- USB is configured (enumerated)
- Host has opened COM port (DTR high)
This helps prevent writes to USB when no host application is listening,
which can cause buffer buildup and delays.
Co-Authored-By: Claude Opus 4.6
---
src/main/drivers/serial_usb_vcp.c | 21 +++++++++++++++++++--
1 file changed, 19 insertions(+), 2 deletions(-)
diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c
index 7fdbad2a114..9a98e86854d 100644
--- a/src/main/drivers/serial_usb_vcp.c
+++ b/src/main/drivers/serial_usb_vcp.c
@@ -51,6 +51,16 @@ USBD_HandleTypeDef USBD_Device;
static vcpPort_t vcpPort;
+// Track DTR (Data Terminal Ready) state - indicates if host has COM port open
+static volatile bool cdcPortOpened = false;
+
+static void cdcCtrlLineStateCallback(void *context, uint16_t ctrlLineState)
+{
+ UNUSED(context);
+ // DTR is bit 0 of control line state
+ cdcPortOpened = (ctrlLineState & 0x01) != 0;
+}
+
static void usbVcpSetBaudRate(serialPort_t *instance, uint32_t baudRate)
{
UNUSED(instance);
@@ -103,7 +113,8 @@ static uint8_t usbVcpRead(serialPort_t *instance)
static bool usbVcpIsConnected(const serialPort_t *instance)
{
(void)instance;
- return usbIsConnected() && usbIsConfigured();
+ // Check USB hardware state AND whether host has opened the COM port (DTR)
+ return usbIsConnected() && usbIsConfigured() && cdcPortOpened;
}
static void usbVcpWriteBuf(serialPort_t *instance, const void *data, int count)
@@ -209,6 +220,9 @@ void usbVcpInitHardware(void)
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_INPUT, 0);
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_OUTPUT, 0);
USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb);
+
+ // Register callback for DTR state changes
+ CDC_SetCtrlLineStateCb(cdcCtrlLineStateCallback, NULL);
#elif defined(STM32F7) || defined(STM32H7)
usbGenerateDisconnectPulse();
@@ -225,7 +239,10 @@ void usbVcpInitHardware(void)
/* Start Device Process */
USBD_Start(&USBD_Device);
-
+
+ // Register callback for DTR state changes
+ CDC_SetCtrlLineStateCb(cdcCtrlLineStateCallback, NULL);
+
#ifdef STM32H7
HAL_PWREx_EnableUSBVoltageDetector();
delay(100); // Cold boot failures observed without this, even when USB cable is not connected
From 5a81c9bdbca2b52254f3e145db91d99c154913ed Mon Sep 17 00:00:00 2001
From: daijoubu
Date: Fri, 20 Feb 2026 21:57:54 -0800
Subject: [PATCH 29/55] Add suspend detection as disconnect fallback (STM32F4)
On boards without VBUS sensing, USB hardware disconnect may not be
detected. Treat USB suspend event as a disconnect to prevent blocking
on writes when cable is unplugged.
When suspend occurs, set bDeviceState = UNCONNECTED so that
usbIsConnected() returns false and writes are skipped.
Co-Authored-By: Claude Opus 4.6
---
src/main/vcpf4/usbd_usr.c | 9 +++++++--
1 file changed, 7 insertions(+), 2 deletions(-)
diff --git a/src/main/vcpf4/usbd_usr.c b/src/main/vcpf4/usbd_usr.c
index 24c5f17c206..15aa47fb257 100644
--- a/src/main/vcpf4/usbd_usr.c
+++ b/src/main/vcpf4/usbd_usr.c
@@ -21,6 +21,7 @@
#include "usbd_usr.h"
#include "usbd_ioreq.h"
+#include "usbd_cdc_vcp.h"
USBD_Usr_cb_TypeDef USR_cb =
{
@@ -102,13 +103,17 @@ void USBD_USR_DeviceDisconnected (void)
/**
* @brief USBD_USR_DeviceSuspended
-* Displays the message on LCD on device suspend Event
+* Handle device suspend event - treat as disconnect for safety.
+* This helps on boards without VBUS sensing where hardware
+* disconnect detection may not work.
* @param None
* @retval None
*/
void USBD_USR_DeviceSuspended(void)
{
- /* Users can do their application actions here for the USB-Reset */
+ // Treat suspend as disconnect - prevents blocking on USB writes
+ // when cable is unplugged on boards without VBUS sensing
+ bDeviceState = UNCONNECTED;
}
From bf81e90a3dcbe08bc7010357cf83088768404c49 Mon Sep 17 00:00:00 2001
From: daijoubu
Date: Fri, 20 Feb 2026 22:15:37 -0800
Subject: [PATCH 30/55] Fix DTR tracking default - assume connected initially
Default cdcPortOpened to true so MSP works immediately on connection.
DTR state will be updated when host explicitly sets/clears it.
Previous default of false broke MSP on tools that don't assert DTR.
Co-Authored-By: Claude Opus 4.6
---
src/main/drivers/serial_usb_vcp.c | 3 ++-
1 file changed, 2 insertions(+), 1 deletion(-)
diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c
index 9a98e86854d..f076e0bfee2 100644
--- a/src/main/drivers/serial_usb_vcp.c
+++ b/src/main/drivers/serial_usb_vcp.c
@@ -52,7 +52,8 @@ USBD_HandleTypeDef USBD_Device;
static vcpPort_t vcpPort;
// Track DTR (Data Terminal Ready) state - indicates if host has COM port open
-static volatile bool cdcPortOpened = false;
+// Default to true - assume connected until host explicitly clears DTR
+static volatile bool cdcPortOpened = true;
static void cdcCtrlLineStateCallback(void *context, uint16_t ctrlLineState)
{
From e17b50b3dfbb73d72baed7e6114e2158a8b4ccee Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sun, 22 Feb 2026 15:08:25 -0600
Subject: [PATCH 31/55] SDMODELH7V2: COnfigure PINIO and Bluetooth arming
control
---
src/main/target/SDMODELH7V2/config.c | 1 +
src/main/target/SDMODELH7V2/target.h | 15 ++++++++++-----
2 files changed, 11 insertions(+), 5 deletions(-)
diff --git a/src/main/target/SDMODELH7V2/config.c b/src/main/target/SDMODELH7V2/config.c
index 54ecc6f7627..47f9da30bc5 100644
--- a/src/main/target/SDMODELH7V2/config.c
+++ b/src/main/target/SDMODELH7V2/config.c
@@ -30,6 +30,7 @@ void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
+ pinioBoxConfigMutable()->permanentId[2] = findBoxByActiveBoxId(BOXARM)->permanentId;
// UART2 is connected to an onboard Bluetooth module (not user-accessible)
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_MSP;
diff --git a/src/main/target/SDMODELH7V2/target.h b/src/main/target/SDMODELH7V2/target.h
index b49697cd80f..fcdc0898f18 100644
--- a/src/main/target/SDMODELH7V2/target.h
+++ b/src/main/target/SDMODELH7V2/target.h
@@ -135,9 +135,6 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
-// BF DEFAULT_VOLTAGE_METER_SCALE=109, BF DEFAULT_CURRENT_METER_SCALE=168
-// INAV uses a different scaling formula; these values approximate the same
-// physical measurement. Users should calibrate via the configurator.
#define VBAT_SCALE_DEFAULT 1090
#define CURRENT_METER_SCALE 168
@@ -147,11 +144,19 @@
// *************** PINIO *****************************
#define USE_PINIO
#define USE_PINIOBOX
-#define PINIO1_PIN PE13
+
+// VTX power
+#define PINIO1_PIN PB11
#define PINIO1_FLAGS PINIO_FLAGS_INVERTED
-#define PINIO2_PIN PB11
+
+// Cam pin
+#define PINIO2_PIN PE9
#define PINIO2_FLAGS PINIO_FLAGS_INVERTED
+// Bluetooth (off on arm)
+#define PINIO3_PIN PE13
+#define PINIO3_FLAGS PINIO_FLAGS_INVERTED
+
// *************** LED STRIP *************************
#define USE_LED_STRIP
#define WS2811_PIN PD12
From 1fca72e253aed825871279def721a5612b8c12d8 Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Sun, 22 Feb 2026 21:20:41 +0000
Subject: [PATCH 32/55] Update navigation_multicopter.c
---
src/main/navigation/navigation_multicopter.c | 10 +++++-----
1 file changed, 5 insertions(+), 5 deletions(-)
diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c
index bb8f15dc8ba..7da742829c5 100644
--- a/src/main/navigation/navigation_multicopter.c
+++ b/src/main/navigation/navigation_multicopter.c
@@ -137,17 +137,17 @@ bool adjustMulticopterAltitudeFromRCInput(void)
return true;
}
else {
- const int16_t rcThrottleAdjustment = applyDeadbandRescaled(rcCommand[THROTTLE] - altHoldThrottleRCZero, rcControlsConfig()->alt_hold_deadband, -500, 500);
+ const uint8_t deadband = rcControlsConfig()->alt_hold_deadband;
+ const int16_t rcThrottleAdjustment = applyDeadband(rcCommand[THROTTLE] - altHoldThrottleRCZero, deadband);
if (rcThrottleAdjustment) {
/* Set velocity proportional to stick movement
* Scale from altHoldThrottleRCZero to maxthrottle or minthrottle to altHoldThrottleRCZero */
- // Calculate max up or min down limit value scaled for deadband
- int16_t limitValue = rcThrottleAdjustment > 0 ? getMaxThrottle() : getThrottleIdleValue();
- limitValue = applyDeadbandRescaled(limitValue - altHoldThrottleRCZero, rcControlsConfig()->alt_hold_deadband, -500, 500);
+ int16_t controlRange = -deadband;
+ controlRange += rcThrottleAdjustment > 0 ? getMaxThrottle() - altHoldThrottleRCZero : altHoldThrottleRCZero - getThrottleIdleValue();
- int16_t rcClimbRate = ABS(rcThrottleAdjustment) * navConfig()->mc.max_manual_climb_rate / limitValue;
+ const int16_t rcClimbRate = rcThrottleAdjustment * navConfig()->mc.max_manual_climb_rate / controlRange;
updateClimbRateToAltitudeController(rcClimbRate, 0, ROC_TO_ALT_CONSTANT);
return true;
From edf04d2d7549ef14d7669b830b2999a7cf0bf67b Mon Sep 17 00:00:00 2001
From: John-Henrique
Date: Sat, 28 Feb 2026 07:12:00 -0300
Subject: [PATCH 33/55] Add Loiter to LED control on mode flight
---
src/main/io/ledstrip.c | 2 ++
src/main/io/ledstrip.h | 3 ++-
2 files changed, 4 insertions(+), 1 deletion(-)
diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c
index 62c41683f02..8e8e5771450 100644
--- a/src/main/io/ledstrip.c
+++ b/src/main/io/ledstrip.c
@@ -127,6 +127,7 @@ static const modeColorIndexes_t defaultModeColors[] = {
[LED_MODE_ANGLE] = {{ COLOR_CYAN, COLOR_DARK_VIOLET, COLOR_YELLOW, COLOR_DEEP_PINK, COLOR_BLUE, COLOR_ORANGE }},
[LED_MODE_MAG] = {{ COLOR_MINT_GREEN, COLOR_DARK_VIOLET, COLOR_ORANGE, COLOR_DEEP_PINK, COLOR_BLUE, COLOR_ORANGE }},
[LED_MODE_BARO] = {{ COLOR_LIGHT_BLUE, COLOR_DARK_VIOLET, COLOR_RED, COLOR_DEEP_PINK, COLOR_BLUE, COLOR_ORANGE }},
+ [LED_MODE_LOITER] = {{ COLOR_YELLOW, COLOR_DARK_VIOLET, COLOR_RED, COLOR_DEEP_PINK, COLOR_BLUE, COLOR_ORANGE }},
};
static const specialColorIndexes_t defaultSpecialColors[] = {
@@ -423,6 +424,7 @@ static const struct {
uint8_t ledMode;
} flightModeToLed[] = {
{HEADFREE_MODE, LED_MODE_HEADFREE},
+ {NAV_POSHOLD_MODE, LED_MODE_LOITER},
{HEADING_MODE, LED_MODE_MAG},
#ifdef USE_BARO
{NAV_ALTHOLD_MODE, LED_MODE_BARO},
diff --git a/src/main/io/ledstrip.h b/src/main/io/ledstrip.h
index 204a4661d17..2aea06cde73 100644
--- a/src/main/io/ledstrip.h
+++ b/src/main/io/ledstrip.h
@@ -23,7 +23,7 @@
#define LED_MAX_STRIP_LENGTH 128
#define LED_CONFIGURABLE_COLOR_COUNT 16
-#define LED_MODE_COUNT 6
+#define LED_MODE_COUNT 7
#define LED_DIRECTION_COUNT 6
#define LED_BASEFUNCTION_COUNT 8
#define LED_OVERLAY_COUNT 7
@@ -79,6 +79,7 @@ typedef enum {
LED_MODE_ANGLE,
LED_MODE_MAG,
LED_MODE_BARO,
+ LED_MODE_LOITER,
LED_SPECIAL
} ledModeIndex_e;
From 7ec7f0d190807ddabea5513025143e23516df6ac Mon Sep 17 00:00:00 2001
From: Sensei
Date: Sun, 1 Mar 2026 09:01:02 -0600
Subject: [PATCH 34/55] Remove HD_3016 from resolutionType_e enum
Removed HD_3016 resolution type from the enum.
---
src/main/io/displayport_msp_osd.c | 1 -
1 file changed, 1 deletion(-)
diff --git a/src/main/io/displayport_msp_osd.c b/src/main/io/displayport_msp_osd.c
index a39f123cdde..f193913916f 100644
--- a/src/main/io/displayport_msp_osd.c
+++ b/src/main/io/displayport_msp_osd.c
@@ -58,7 +58,6 @@
typedef enum { // defines are from hdzero code
SD_3016,
HD_5018,
- HD_3016, // Special HDZERO mode that just sends the centre 30x16 of the 50x18 canvas to the VRX
HD_6022, // added to support DJI wtfos 60x22 grid
HD_5320 // added to support Avatar and BetaflightHD
} resolutionType_e;
From b52c6f783473a157b652a026b66d75bc1646651a Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sun, 1 Mar 2026 12:31:43 -0600
Subject: [PATCH 35/55] CI: publish PR test builds to iNavFlight/pr-test-builds
Add a workflow_run-triggered job that uploads each PR's firmware as
individually named release assets on iNavFlight/pr-test-builds, then
posts (or updates) a PR comment with a direct download link.
This avoids two limitations of GitHub Actions artifacts: the opaque
single-zip bundle, and the requirement for a GitHub login to download.
Requires a PR_BUILDS_TOKEN secret with Contents:write access to
iNavFlight/pr-test-builds.
---
.github/workflows/ci.yml | 10 ++
.github/workflows/pr-test-builds.yml | 151 +++++++++++++++++++++++++++
2 files changed, 161 insertions(+)
create mode 100644 .github/workflows/pr-test-builds.yml
diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml
index bf911321f14..f3a856bc7f6 100644
--- a/.github/workflows/ci.yml
+++ b/.github/workflows/ci.yml
@@ -107,6 +107,16 @@ jobs:
with:
name: targets
path: targets.txt
+ - name: Save PR number
+ if: github.event_name == 'pull_request'
+ run: echo "${{ github.event.pull_request.number }}" > pr_number.txt
+ - name: Upload PR number
+ if: github.event_name == 'pull_request'
+ uses: actions/upload-artifact@v4
+ with:
+ name: pr-number
+ path: pr_number.txt
+ retention-days: 1
build-SITL-Linux-arm64:
runs-on: ubuntu-22.04-arm
diff --git a/.github/workflows/pr-test-builds.yml b/.github/workflows/pr-test-builds.yml
new file mode 100644
index 00000000000..8a217d7fe32
--- /dev/null
+++ b/.github/workflows/pr-test-builds.yml
@@ -0,0 +1,151 @@
+name: PR Test Builds
+
+# Runs after "Build firmware" completes. Uses workflow_run (rather than
+# pull_request directly) so that secrets are available even for PRs from forks.
+#
+# Requires a repository secret PR_BUILDS_TOKEN with Contents: write access
+# to iNavFlight/pr-test-builds (fine-grained PAT or classic PAT with repo scope).
+on:
+ workflow_run:
+ workflows: ["Build firmware"]
+ types: [completed]
+
+jobs:
+ publish:
+ runs-on: ubuntu-latest
+ # Only act on pull_request-triggered runs that succeeded.
+ if: >
+ github.event.workflow_run.event == 'pull_request' &&
+ github.event.workflow_run.conclusion == 'success'
+ # Prevent concurrent runs for the same PR branch racing on the
+ # release delete/create cycle.
+ concurrency:
+ group: pr-test-build-${{ github.event.workflow_run.head_branch }}
+ cancel-in-progress: true
+ permissions:
+ actions: read # to download artifacts from the triggering workflow run
+ pull-requests: write # to post the PR comment
+
+ steps:
+ - name: Download PR number
+ uses: actions/download-artifact@v4
+ with:
+ name: pr-number
+ run-id: ${{ github.event.workflow_run.id }}
+ github-token: ${{ secrets.GITHUB_TOKEN }}
+
+ - name: Read PR number
+ id: pr
+ run: |
+ PR_NUM=$(tr -dc '0-9' < pr_number.txt)
+ if [ -z "$PR_NUM" ]; then
+ echo "::error::Invalid PR number in artifact"
+ exit 1
+ fi
+ echo "number=${PR_NUM}" >> $GITHUB_OUTPUT
+
+ - name: Download firmware artifacts
+ uses: actions/download-artifact@v4
+ with:
+ pattern: matrix-inav-*
+ merge-multiple: true
+ path: hexes
+ run-id: ${{ github.event.workflow_run.id }}
+ github-token: ${{ secrets.GITHUB_TOKEN }}
+
+ - name: Get build info
+ id: info
+ run: |
+ COUNT=$(find hexes -name '*.hex' -type f | wc -l)
+ if [ "$COUNT" -eq 0 ]; then
+ echo "::error::No .hex files found in downloaded artifacts"
+ exit 1
+ fi
+ echo "count=${COUNT}" >> $GITHUB_OUTPUT
+ echo "short_sha=$(echo '${{ github.event.workflow_run.head_sha }}' | cut -c1-7)" >> $GITHUB_OUTPUT
+
+ # Delete the previous release for this PR (if any) so assets are replaced
+ # cleanly on each new commit. --cleanup-tag removes the old tag so it is
+ # recreated fresh pointing to the new commit.
+ - name: Delete existing PR release
+ env:
+ GH_TOKEN: ${{ secrets.PR_BUILDS_TOKEN }}
+ run: |
+ gh release delete "pr-${{ steps.pr.outputs.number }}" \
+ --repo iNavFlight/pr-test-builds --cleanup-tag --yes 2>/dev/null || true
+
+ - name: Create PR release
+ env:
+ GH_TOKEN: ${{ secrets.PR_BUILDS_TOKEN }}
+ run: |
+ PR_NUMBER="${{ steps.pr.outputs.number }}"
+ SHORT_SHA="${{ steps.info.outputs.short_sha }}"
+ COUNT="${{ steps.info.outputs.count }}"
+ PR_URL="https://github.com/${{ github.repository }}/pull/${PR_NUMBER}"
+
+ NOTES="Test build for [PR #${PR_NUMBER}](${PR_URL}) — commit \`${SHORT_SHA}\`
+
+**${COUNT} targets built.** Find your board's \`.hex\` file by name (e.g. \`MATEKF405SE.hex\`).
+
+> Development build for testing only. Use Full Chip Erase when flashing."
+
+ cd hexes
+ gh release create "pr-${PR_NUMBER}" *.hex \
+ --repo iNavFlight/pr-test-builds \
+ --prerelease \
+ --title "PR #${PR_NUMBER} (${SHORT_SHA})" \
+ --notes "${NOTES}"
+
+ - name: Post or update PR comment
+ uses: actions/github-script@v7
+ env:
+ PR_NUMBER: ${{ steps.pr.outputs.number }}
+ SHORT_SHA: ${{ steps.info.outputs.short_sha }}
+ HEX_COUNT: ${{ steps.info.outputs.count }}
+ with:
+ script: |
+ const prNumber = parseInt(process.env.PR_NUMBER);
+ const shortSha = process.env.SHORT_SHA;
+ const count = process.env.HEX_COUNT;
+ const releaseUrl = `https://github.com/iNavFlight/pr-test-builds/releases/tag/pr-${prNumber}`;
+
+ const body = [
+ '',
+ '**Test firmware build ready** — commit `' + shortSha + '`',
+ '',
+ `[Download firmware for PR #${prNumber}](${releaseUrl})`,
+ '',
+ `${count} targets built. Find your board's \`.hex\` file by name on that page ` +
+ '(e.g. `MATEKF405SE.hex`). Files are individually downloadable — no GitHub login required.',
+ '',
+ '> Development build for testing only. Use Full Chip Erase when flashing.',
+ ].join('\n');
+
+ const comments = await github.paginate(
+ github.rest.issues.listComments,
+ {
+ owner: context.repo.owner,
+ repo: context.repo.repo,
+ issue_number: prNumber,
+ }
+ );
+
+ const existing = comments.find(c =>
+ c.user.type === 'Bot' && c.body.includes('')
+ );
+
+ if (existing) {
+ await github.rest.issues.updateComment({
+ owner: context.repo.owner,
+ repo: context.repo.repo,
+ comment_id: existing.id,
+ body,
+ });
+ } else {
+ await github.rest.issues.createComment({
+ owner: context.repo.owner,
+ repo: context.repo.repo,
+ issue_number: prNumber,
+ body,
+ });
+ }
From 37e02bd1c050e7a49c71834f3edd98460b11ae09 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sun, 1 Mar 2026 12:44:29 -0600
Subject: [PATCH 36/55] CI: address code review findings in pr-test-builds
workflow
- Add issues: write permission (required for github.rest.issues.* endpoints)
- Include fork repo name in concurrency key to prevent cross-fork cancellation
- Pin release tag to head_sha via --target flag
- Add parseInt radix and NaN validation for PR number
---
.github/workflows/pr-test-builds.yml | 7 +++++--
1 file changed, 5 insertions(+), 2 deletions(-)
diff --git a/.github/workflows/pr-test-builds.yml b/.github/workflows/pr-test-builds.yml
index 8a217d7fe32..a297bd3671b 100644
--- a/.github/workflows/pr-test-builds.yml
+++ b/.github/workflows/pr-test-builds.yml
@@ -20,10 +20,11 @@ jobs:
# Prevent concurrent runs for the same PR branch racing on the
# release delete/create cycle.
concurrency:
- group: pr-test-build-${{ github.event.workflow_run.head_branch }}
+ group: pr-test-build-${{ github.event.workflow_run.head_repository.full_name }}-${{ github.event.workflow_run.head_branch }}
cancel-in-progress: true
permissions:
actions: read # to download artifacts from the triggering workflow run
+ issues: write # github.rest.issues.* endpoints used to post PR comments
pull-requests: write # to post the PR comment
steps:
@@ -93,6 +94,7 @@ jobs:
gh release create "pr-${PR_NUMBER}" *.hex \
--repo iNavFlight/pr-test-builds \
--prerelease \
+ --target "${{ github.event.workflow_run.head_sha }}" \
--title "PR #${PR_NUMBER} (${SHORT_SHA})" \
--notes "${NOTES}"
@@ -104,7 +106,8 @@ jobs:
HEX_COUNT: ${{ steps.info.outputs.count }}
with:
script: |
- const prNumber = parseInt(process.env.PR_NUMBER);
+ const prNumber = parseInt(process.env.PR_NUMBER, 10);
+ if (isNaN(prNumber)) throw new Error(`Invalid PR number: ${process.env.PR_NUMBER}`);
const shortSha = process.env.SHORT_SHA;
const count = process.env.HEX_COUNT;
const releaseUrl = `https://github.com/iNavFlight/pr-test-builds/releases/tag/pr-${prNumber}`;
From e5bcf839535de1e7567d611ce01c25fc1adf67ff Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sun, 1 Mar 2026 14:10:29 -0600
Subject: [PATCH 37/55] Mark MSP_STATUS, MSP_DEBUG, and blackbox config
commands as deprecated
Add replaced_by fields to msp_messages.json and deprecation comments
to msp_protocol.h for MSP_BLACKBOX_CONFIG, MSP_SET_BLACKBOX_CONFIG,
MSP_STATUS, and MSP_DEBUG. MSP_STATUS_EX not marked deprecated because
its accCalibAxisFlags field is absent from MSP2_INAV_STATUS.
---
docs/development/msp/msp_messages.json | 4 ++++
src/main/msp/msp_protocol.h | 8 ++++----
2 files changed, 8 insertions(+), 4 deletions(-)
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index 78d3c2f99e2..db4e7ebf2b1 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -2362,6 +2362,7 @@
"MSP_BLACKBOX_CONFIG": {
"code": 80,
"mspv": 1,
+ "replaced_by": ["MSP2_BLACKBOX_CONFIG"],
"request": null,
"reply": {
"payload": [
@@ -2401,6 +2402,7 @@
"MSP_SET_BLACKBOX_CONFIG": {
"code": 81,
"mspv": 1,
+ "replaced_by": ["MSP2_SET_BLACKBOX_CONFIG"],
"not_implemented": true,
"request": null,
"reply": null,
@@ -3607,6 +3609,7 @@
"MSP_STATUS": {
"code": 101,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_STATUS"],
"request": null,
"reply": {
"payload": [
@@ -5817,6 +5820,7 @@
"MSP_DEBUG": {
"code": 254,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_DEBUG"],
"request": null,
"reply": {
"payload": [
diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h
index e1cbd028293..4a6cb877237 100644
--- a/src/main/msp/msp_protocol.h
+++ b/src/main/msp/msp_protocol.h
@@ -183,8 +183,8 @@
#define MSP_SDCARD_SUMMARY 79 //out message Get the state of the SD card
-#define MSP_BLACKBOX_CONFIG 80 //out message Get blackbox settings
-#define MSP_SET_BLACKBOX_CONFIG 81 //in message Set blackbox settings
+#define MSP_BLACKBOX_CONFIG 80 //DEPRECATED in INAV 9.1, use MSP2_BLACKBOX_CONFIG. Will be removed in INAV 10.0
+#define MSP_SET_BLACKBOX_CONFIG 81 //DEPRECATED in INAV 9.1, use MSP2_SET_BLACKBOX_CONFIG. Will be removed in INAV 10.0
#define MSP_TRANSPONDER_CONFIG 82 //out message Get transponder settings
#define MSP_SET_TRANSPONDER_CONFIG 83 //in message Set transponder settings
@@ -231,7 +231,7 @@
// Multwii original MSP commands
//
-#define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation & current setting number
+#define MSP_STATUS 101 //DEPRECATED in INAV 9.1, use MSP2_INAV_STATUS. Will be removed in INAV 10.0
#define MSP_RAW_IMU 102 //out message 9 DOF
#define MSP_SERVO 103 //out message servos
#define MSP_MOTOR 104 //out message motors
@@ -284,7 +284,7 @@
#define MSP_RESERVE_1 251 //reserved for system usage
#define MSP_RESERVE_2 252 //reserved for system usage
#define MSP_DEBUGMSG 253 //out message debug string buffer
-#define MSP_DEBUG 254 //out message debug1,debug2,debug3,debug4
+#define MSP_DEBUG 254 //DEPRECATED in INAV 9.1, use MSP2_INAV_DEBUG. Will be removed in INAV 10.0
#define MSP_V2_FRAME 255 //MSPv2 payload indicator
// Additional commands that are not compatible with MultiWii
From 1aec36a770a8036b45a7dfdefa54c3c915b59a83 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sun, 1 Mar 2026 14:14:57 -0600
Subject: [PATCH 38/55] Mark MSP_STATUS_EX as deprecated; accCalibAxisFlags in
MSP_CALIBRATION_DATA
MSP2_INAV_STATUS supersedes MSP_STATUS_EX for all status fields.
The accCalibAxisFlags field absent from MSP2_INAV_STATUS is available
via MSP_CALIBRATION_DATA.
---
docs/development/msp/msp_messages.json | 3 ++-
src/main/msp/msp_protocol.h | 2 +-
2 files changed, 3 insertions(+), 2 deletions(-)
diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json
index db4e7ebf2b1..84d603de8e1 100644
--- a/docs/development/msp/msp_messages.json
+++ b/docs/development/msp/msp_messages.json
@@ -4658,6 +4658,7 @@
"MSP_STATUS_EX": {
"code": 150,
"mspv": 1,
+ "replaced_by": ["MSP2_INAV_STATUS"],
"request": null,
"reply": {
"payload": [
@@ -4715,7 +4716,7 @@
}
]
},
- "notes": "Superseded by `MSP2_INAV_STATUS` which provides the full 32-bit `armingFlags` and other enhancements.",
+ "notes": "Superseded by `MSP2_INAV_STATUS` which provides the full 32-bit `armingFlags` and other enhancements. The `accCalibAxisFlags` field is not present in `MSP2_INAV_STATUS` but is available via `MSP_CALIBRATION_DATA`.",
"description": "Provides extended flight controller status, including CPU load, arming flags, and calibration status, in addition to `MSP_STATUS` fields."
},
"MSP_SENSOR_STATUS": {
diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h
index 4a6cb877237..406cfe28ddf 100644
--- a/src/main/msp/msp_protocol.h
+++ b/src/main/msp/msp_protocol.h
@@ -288,7 +288,7 @@
#define MSP_V2_FRAME 255 //MSPv2 payload indicator
// Additional commands that are not compatible with MultiWii
-#define MSP_STATUS_EX 150 //out message cycletime, errors_count, CPU load, sensor present etc
+#define MSP_STATUS_EX 150 //DEPRECATED in INAV 9.1, use MSP2_INAV_STATUS (accCalibAxisFlags available via MSP_CALIBRATION_DATA). Will be removed in INAV 10.0
#define MSP_SENSOR_STATUS 151 //out message Hardware sensor status
#define MSP_UID 160 //out message Unique device ID
#define MSP_GPSSVINFO 164 //out message get Signal Strength (only U-Blox)
From aa2fefcdb8dacf7bad5c2780ff8c55cb0d50b981 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sun, 1 Mar 2026 14:31:23 -0600
Subject: [PATCH 39/55] cmake/sitl: use CheckLinkerFlag instead of GCC version
check for --no-warn-rwx-segments
Replace the fragile CMAKE_COMPILER_IS_GNUCC + version threshold heuristic
with a proper check_linker_flag() probe (available since CMake 3.18; SITL
already requires 3.22+). The probe directly tests whether the linker
accepts the flag rather than guessing based on compiler version.
---
cmake/sitl.cmake | 4 +++-
1 file changed, 3 insertions(+), 1 deletion(-)
diff --git a/cmake/sitl.cmake b/cmake/sitl.cmake
index 39e6456830a..a5a98a779b6 100644
--- a/cmake/sitl.cmake
+++ b/cmake/sitl.cmake
@@ -64,7 +64,9 @@ if(NOT MACOSX)
-Wno-error=maybe-uninitialized
-fsingle-precision-constant
)
- if (CMAKE_COMPILER_IS_GNUCC AND NOT CMAKE_C_COMPILER_VERSION VERSION_LESS 12.0)
+ include(CheckLinkerFlag)
+ check_linker_flag(C "-Wl,--no-warn-rwx-segments" LINKER_SUPPORTS_NO_RWX_WARNING)
+ if(LINKER_SUPPORTS_NO_RWX_WARNING)
set(SITL_LINK_OPTIONS ${SITL_LINK_OPTIONS} "-Wl,--no-warn-rwx-segments")
endif()
else()
From 767333fdd6a3eb61b1f45d332bb9dc45de8e4f7d Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sun, 1 Mar 2026 16:07:02 -0600
Subject: [PATCH 40/55] CI: fix YAML syntax error in pr-test-builds workflow
Multi-line shell string in the NOTES variable had unindented continuation
lines (**..., >...) that were less indented than the YAML block scalar
body, causing a parse error on every run.
Replace with printf + --notes-file to avoid multi-line strings in the
YAML block scalar entirely. Also moves ${{ }} expressions into env vars
rather than inline in the shell script.
---
.github/workflows/pr-test-builds.yml | 29 ++++++++++++++--------------
1 file changed, 14 insertions(+), 15 deletions(-)
diff --git a/.github/workflows/pr-test-builds.yml b/.github/workflows/pr-test-builds.yml
index a297bd3671b..cf4a32b7b57 100644
--- a/.github/workflows/pr-test-builds.yml
+++ b/.github/workflows/pr-test-builds.yml
@@ -78,25 +78,24 @@ jobs:
- name: Create PR release
env:
GH_TOKEN: ${{ secrets.PR_BUILDS_TOKEN }}
+ PR_NUMBER: ${{ steps.pr.outputs.number }}
+ SHORT_SHA: ${{ steps.info.outputs.short_sha }}
+ HEX_COUNT: ${{ steps.info.outputs.count }}
+ HEAD_SHA: ${{ github.event.workflow_run.head_sha }}
+ REPO: ${{ github.repository }}
run: |
- PR_NUMBER="${{ steps.pr.outputs.number }}"
- SHORT_SHA="${{ steps.info.outputs.short_sha }}"
- COUNT="${{ steps.info.outputs.count }}"
- PR_URL="https://github.com/${{ github.repository }}/pull/${PR_NUMBER}"
-
- NOTES="Test build for [PR #${PR_NUMBER}](${PR_URL}) — commit \`${SHORT_SHA}\`
-
-**${COUNT} targets built.** Find your board's \`.hex\` file by name (e.g. \`MATEKF405SE.hex\`).
-
-> Development build for testing only. Use Full Chip Erase when flashing."
-
- cd hexes
- gh release create "pr-${PR_NUMBER}" *.hex \
+ PR_URL="https://github.com/${REPO}/pull/${PR_NUMBER}"
+ printf '%s\n\n%s\n\n%s\n' \
+ "Test build for [PR #${PR_NUMBER}](${PR_URL}) — commit \`${SHORT_SHA}\`" \
+ "**${HEX_COUNT} targets built.** Find your board's \`.hex\` file by name (e.g. \`MATEKF405SE.hex\`)." \
+ "> Development build for testing only. Use Full Chip Erase when flashing." \
+ > release-notes.md
+ gh release create "pr-${PR_NUMBER}" hexes/*.hex \
--repo iNavFlight/pr-test-builds \
--prerelease \
- --target "${{ github.event.workflow_run.head_sha }}" \
+ --target "${HEAD_SHA}" \
--title "PR #${PR_NUMBER} (${SHORT_SHA})" \
- --notes "${NOTES}"
+ --notes-file release-notes.md
- name: Post or update PR comment
uses: actions/github-script@v7
From c7edbc33a09da687781f730600041c1e8347eeb1 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Sun, 1 Mar 2026 16:07:02 -0600
Subject: [PATCH 41/55] CI: fix YAML syntax error in pr-test-builds workflow
Multi-line shell string in the NOTES variable had unindented continuation
lines (**..., >...) that were less indented than the YAML block scalar
body, causing a parse error on every run.
Replace with printf + --notes-file to avoid multi-line strings in the
YAML block scalar entirely. Also moves ${{ }} expressions into env vars
rather than inline in the shell script.
---
.github/workflows/pr-test-builds.yml | 29 ++++++++++++++--------------
1 file changed, 14 insertions(+), 15 deletions(-)
diff --git a/.github/workflows/pr-test-builds.yml b/.github/workflows/pr-test-builds.yml
index a297bd3671b..cf4a32b7b57 100644
--- a/.github/workflows/pr-test-builds.yml
+++ b/.github/workflows/pr-test-builds.yml
@@ -78,25 +78,24 @@ jobs:
- name: Create PR release
env:
GH_TOKEN: ${{ secrets.PR_BUILDS_TOKEN }}
+ PR_NUMBER: ${{ steps.pr.outputs.number }}
+ SHORT_SHA: ${{ steps.info.outputs.short_sha }}
+ HEX_COUNT: ${{ steps.info.outputs.count }}
+ HEAD_SHA: ${{ github.event.workflow_run.head_sha }}
+ REPO: ${{ github.repository }}
run: |
- PR_NUMBER="${{ steps.pr.outputs.number }}"
- SHORT_SHA="${{ steps.info.outputs.short_sha }}"
- COUNT="${{ steps.info.outputs.count }}"
- PR_URL="https://github.com/${{ github.repository }}/pull/${PR_NUMBER}"
-
- NOTES="Test build for [PR #${PR_NUMBER}](${PR_URL}) — commit \`${SHORT_SHA}\`
-
-**${COUNT} targets built.** Find your board's \`.hex\` file by name (e.g. \`MATEKF405SE.hex\`).
-
-> Development build for testing only. Use Full Chip Erase when flashing."
-
- cd hexes
- gh release create "pr-${PR_NUMBER}" *.hex \
+ PR_URL="https://github.com/${REPO}/pull/${PR_NUMBER}"
+ printf '%s\n\n%s\n\n%s\n' \
+ "Test build for [PR #${PR_NUMBER}](${PR_URL}) — commit \`${SHORT_SHA}\`" \
+ "**${HEX_COUNT} targets built.** Find your board's \`.hex\` file by name (e.g. \`MATEKF405SE.hex\`)." \
+ "> Development build for testing only. Use Full Chip Erase when flashing." \
+ > release-notes.md
+ gh release create "pr-${PR_NUMBER}" hexes/*.hex \
--repo iNavFlight/pr-test-builds \
--prerelease \
- --target "${{ github.event.workflow_run.head_sha }}" \
+ --target "${HEAD_SHA}" \
--title "PR #${PR_NUMBER} (${SHORT_SHA})" \
- --notes "${NOTES}"
+ --notes-file release-notes.md
- name: Post or update PR comment
uses: actions/github-script@v7
From 4e07d5c918ca5917b0adf6ea03350d8478d9b695 Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Sun, 1 Mar 2026 23:17:30 +0000
Subject: [PATCH 42/55] remove setting and change warning logic
---
docs/Settings.md | 10 -----
src/main/fc/multifunction.c | 13 +++---
src/main/fc/multifunction.h | 8 +++-
src/main/fc/settings.yaml | 6 ---
src/main/io/osd.c | 83 ++++++++++++++-----------------------
src/main/io/osd.h | 3 --
6 files changed, 44 insertions(+), 79 deletions(-)
diff --git a/docs/Settings.md b/docs/Settings.md
index ef2429733d0..4e577bbedd5 100644
--- a/docs/Settings.md
+++ b/docs/Settings.md
@@ -3092,16 +3092,6 @@ Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this r
---
-### multifunction_warning_cycle_time
-
-Cycle time for display of full multifunction warning messages [s]. Full warnings will be displayed for 5s on a rolling cycle using this setting with only the total number of warnings indicated otherwise. Warnings will always be displayed in full if set to 0.
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 5 | 0 | 60 |
-
----
-
### name
Craft name
diff --git a/src/main/fc/multifunction.c b/src/main/fc/multifunction.c
index c217110842d..2ac3a558278 100644
--- a/src/main/fc/multifunction.c
+++ b/src/main/fc/multifunction.c
@@ -45,32 +45,29 @@ static void multiFunctionApply(multi_function_e selectedItem)
switch (selectedItem) {
case MULTI_FUNC_NONE:
break;
- case MULTI_FUNC_1: // redisplay current warnings
- osdResetWarningFlags();
- break;
- case MULTI_FUNC_2: // control manual emergency landing
+ case MULTI_FUNC_1: // control manual emergency landing
checkManualEmergencyLandingControl(ARMING_FLAG(ARMED));
break;
- case MULTI_FUNC_3: // toggle Safehome suspend
+ case MULTI_FUNC_2: // toggle Safehome suspend
#if defined(USE_SAFE_HOME)
if (navConfig()->general.flags.safehome_usage_mode != SAFEHOME_USAGE_OFF) {
MULTI_FUNC_FLAG(MF_SUSPEND_SAFEHOMES) ? MULTI_FUNC_FLAG_DISABLE(MF_SUSPEND_SAFEHOMES) : MULTI_FUNC_FLAG_ENABLE(MF_SUSPEND_SAFEHOMES);
}
#endif
break;
- case MULTI_FUNC_4: // toggle RTH Trackback suspend
+ case MULTI_FUNC_3: // toggle RTH Trackback suspend
if (navConfig()->general.flags.rth_trackback_mode != RTH_TRACKBACK_OFF) {
MULTI_FUNC_FLAG(MF_SUSPEND_TRACKBACK) ? MULTI_FUNC_FLAG_DISABLE(MF_SUSPEND_TRACKBACK) : MULTI_FUNC_FLAG_ENABLE(MF_SUSPEND_TRACKBACK);
}
break;
- case MULTI_FUNC_5:
+ case MULTI_FUNC_4:
#ifdef USE_DSHOT
if (STATE(MULTIROTOR)) { // toggle Turtle mode
MULTI_FUNC_FLAG(MF_TURTLE_MODE) ? MULTI_FUNC_FLAG_DISABLE(MF_TURTLE_MODE) : MULTI_FUNC_FLAG_ENABLE(MF_TURTLE_MODE);
}
#endif
break;
- case MULTI_FUNC_6: // emergency ARM
+ case MULTI_FUNC_5: // emergency ARM
if (!ARMING_FLAG(ARMED)) {
emergencyArmingUpdate(true, true);
}
diff --git a/src/main/fc/multifunction.h b/src/main/fc/multifunction.h
index 93265ba1200..6e60da2bdd8 100644
--- a/src/main/fc/multifunction.h
+++ b/src/main/fc/multifunction.h
@@ -26,6 +26,13 @@
#include
+typedef struct multiFunctionWarning_s {
+ uint8_t osdWarningsFlags; // bitfield
+ bool newWarningActive;
+} multiFunctionWarning_t;
+
+extern multiFunctionWarning_t multiFunctionWarning;
+
#ifdef USE_MULTI_FUNCTIONS
extern uint8_t multiFunctionFlags;
@@ -47,7 +54,6 @@ typedef enum {
MULTI_FUNC_3,
MULTI_FUNC_4,
MULTI_FUNC_5,
- MULTI_FUNC_6,
MULTI_FUNC_END,
} multi_function_e;
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index 62ba8089b4e..476dfe09ff7 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -3904,12 +3904,6 @@ groups:
field: osd_switch_indicators_align_left
type: bool
default_value: ON
- - name: multifunction_warning_cycle_time
- description: "Cycle time for display of full multifunction warning messages [s]. Full warnings will be displayed for 5s on a rolling cycle using this setting with only the total number of warnings indicated otherwise. Warnings will always be displayed in full if set to 0."
- field: multifunction_warning_cycle_time
- min: 0
- max: 60
- default_value: 5
- name: PG_OSD_COMMON_CONFIG
type: osdCommonConfig_t
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index 8401bdeaf3a..f4fe19a4040 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -203,8 +203,9 @@ static bool fullRedraw = false;
static uint8_t armState;
+// Multifunction
static textAttributes_t osdGetMultiFunctionMessage(char *buff);
-static uint8_t osdWarningsFlags = 0;
+multiFunctionWarning_t multiFunctionWarning;
typedef struct osdMapData_s {
uint32_t scale;
@@ -4355,7 +4356,6 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
.use_pilot_logo = SETTING_OSD_USE_PILOT_LOGO_DEFAULT,
.inav_to_pilot_logo_spacing = SETTING_OSD_INAV_TO_PILOT_LOGO_SPACING_DEFAULT,
.arm_screen_display_time = SETTING_OSD_ARM_SCREEN_DISPLAY_TIME_DEFAULT,
- .multifunction_warning_cycle_time = SETTING_MULTIFUNCTION_WARNING_CYCLE_TIME_DEFAULT,
#ifdef USE_WIND_ESTIMATOR
.estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT,
@@ -6406,49 +6406,35 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter
return elemAttr;
}
-void osdResetWarningFlags(void)
+static bool osdCheckWarning(bool condition, uint8_t warningFlag)
{
- osdWarningsFlags = 0;
-}
-
-static bool osdCheckWarning(bool condition, uint8_t warningFlag, uint8_t *warningsCount)
-{
-#define WARNING_REDISPLAY_DURATION 5000; // milliseconds
-
+ static timeMs_t newWarningEndTime = 0;
+ static uint8_t newWarningFlags = 0; // bitfield
const timeMs_t currentTimeMs = millis();
- static timeMs_t warningDisplayStartTime = 0;
- static timeMs_t redisplayStartTimeMs = 0;
- static uint16_t osdWarningTimerDuration;
- static uint8_t newWarningFlags;
+ /* New warnings dislayed individually for 10s with blinking after which
+ * all current warnings displayed without blinking on 1 second cycle */
if (condition) { // condition required to trigger warning
- if (!(osdWarningsFlags & warningFlag)) {
- osdWarningsFlags |= warningFlag;
+ if (!(multiFunctionWarning.osdWarningsFlags & warningFlag)) { // check for new warnings
+ multiFunctionWarning.osdWarningsFlags |= warningFlag;
newWarningFlags |= warningFlag;
- redisplayStartTimeMs = 0;
+ newWarningEndTime = currentTimeMs + 10000;
+ multiFunctionWarning.newWarningActive = true;
}
#ifdef USE_DEV_TOOLS
if (systemConfig()->groundTestMode) {
return true;
}
#endif
- /* Warnings displayed in full for set time before shrinking down to alert symbol with warning count only.
- * All current warnings are redisplayed in full for 5s on a rolling cycle with time set by multifunction_warning_cycle_time.
- * New warnings dislayed individually for 10s */
- if (currentTimeMs > redisplayStartTimeMs) {
- warningDisplayStartTime = currentTimeMs;
- osdWarningTimerDuration = newWarningFlags ? 10000 : WARNING_REDISPLAY_DURATION;
- redisplayStartTimeMs = currentTimeMs + osdWarningTimerDuration + S2MS(osdConfig()->multifunction_warning_cycle_time);
- }
-
- if (currentTimeMs - warningDisplayStartTime < osdWarningTimerDuration) {
- return (newWarningFlags & warningFlag) || osdWarningTimerDuration == WARNING_REDISPLAY_DURATION;
+ if (currentTimeMs < newWarningEndTime) {
+ return (newWarningFlags & warningFlag); // filter out new warnings excluding older warnings
} else {
newWarningFlags = 0;
+ multiFunctionWarning.newWarningActive = false;
}
- *warningsCount += 1;
- } else if (osdWarningsFlags & warningFlag) {
- osdWarningsFlags &= ~warningFlag;
+ return true;
+ } else if (multiFunctionWarning.osdWarningsFlags & warningFlag) {
+ multiFunctionWarning.osdWarningsFlags &= ~warningFlag;
}
return false;
@@ -6459,7 +6445,6 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
/* Message length limit 10 char max */
textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE;
- static uint8_t warningsCount;
const char *message = NULL;
#ifdef USE_MULTI_FUNCTIONS
@@ -6472,12 +6457,9 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
switch (selectedFunction) {
case MULTI_FUNC_NONE:
case MULTI_FUNC_1:
- message = warningsCount ? "WARNINGS !" : "0 WARNINGS";
- break;
- case MULTI_FUNC_2:
message = posControl.flags.manualEmergLandActive ? "ABORT LAND" : "EMERG LAND";
break;
- case MULTI_FUNC_3:
+ case MULTI_FUNC_2:
#if defined(USE_SAFE_HOME)
if (navConfig()->general.flags.safehome_usage_mode != SAFEHOME_USAGE_OFF) {
message = MULTI_FUNC_FLAG(MF_SUSPEND_SAFEHOMES) ? "USE SFHOME" : "SUS SFHOME";
@@ -6486,14 +6468,14 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
#endif
activeFunction++;
FALLTHROUGH;
- case MULTI_FUNC_4:
+ case MULTI_FUNC_3:
if (navConfig()->general.flags.rth_trackback_mode != RTH_TRACKBACK_OFF) {
message = MULTI_FUNC_FLAG(MF_SUSPEND_TRACKBACK) ? "USE TKBACK" : "SUS TKBACK";
break;
}
activeFunction++;
FALLTHROUGH;
- case MULTI_FUNC_5:
+ case MULTI_FUNC_4:
#ifdef USE_DSHOT
if (STATE(MULTIROTOR)) {
message = MULTI_FUNC_FLAG(MF_TURTLE_MODE) ? "END TURTLE" : "USE TURTLE";
@@ -6502,7 +6484,7 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
#endif
activeFunction++;
FALLTHROUGH;
- case MULTI_FUNC_6:
+ case MULTI_FUNC_5:
message = ARMING_FLAG(ARMED) ? "NOW ARMED " : "EMERG ARM ";
break;
case MULTI_FUNC_END:
@@ -6528,13 +6510,12 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
const char *messages[8];
uint8_t messageCount = 0;
bool warningCondition = false;
- warningsCount = 0;
uint8_t warningFlagID = 1;
// Low Battery Voltage
const batteryState_e batteryVoltageState = checkBatteryVoltageState();
warningCondition = batteryVoltageState == BATTERY_CRITICAL || batteryVoltageState == BATTERY_WARNING;
- if (osdCheckWarning(warningCondition, warningFlagID, &warningsCount)) {
+ if (osdCheckWarning(warningCondition, warningFlagID)) {
messages[messageCount++] = batteryVoltageState == BATTERY_CRITICAL ? "VBATT LAND" : "VBATT LOW ";
}
@@ -6542,14 +6523,14 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
if (batteryUsesCapacityThresholds()) {
const batteryState_e batteryState = getBatteryState();
warningCondition = batteryState == BATTERY_CRITICAL || batteryState == BATTERY_WARNING;
- if (osdCheckWarning(warningCondition, warningFlagID <<= 1, &warningsCount)) {
+ if (osdCheckWarning(warningCondition, warningFlagID <<= 1)) {
messages[messageCount++] = batteryState == BATTERY_CRITICAL ? "BATT EMPTY" : "BATT DYING";
}
}
#if defined(USE_GPS)
// GPS Fix and Failure
if (feature(FEATURE_GPS)) {
- if (osdCheckWarning(!STATE(GPS_FIX), warningFlagID <<= 1, &warningsCount)) {
+ if (osdCheckWarning(!STATE(GPS_FIX), warningFlagID <<= 1)) {
bool gpsFailed = getHwGPSStatus() == HW_SENSOR_UNAVAILABLE;
messages[messageCount++] = gpsFailed ? "GPS FAILED" : "NO GPS FIX";
}
@@ -6558,12 +6539,12 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
// RTH sanity (warning if RTH heads 200m further away from home than closest point)
warningCondition = NAV_Status.state == MW_NAV_STATE_RTH_ENROUTE && !posControl.flags.rthTrackbackActive &&
(posControl.homeDistance - posControl.rthSanityChecker.minimalDistanceToHome) > 20000;
- if (osdCheckWarning(warningCondition, warningFlagID <<= 1, &warningsCount)) {
+ if (osdCheckWarning(warningCondition, warningFlagID <<= 1)) {
messages[messageCount++] = "RTH SANITY";
}
// Altitude sanity (warning if significant mismatch between estimated and GPS altitude)
- if (osdCheckWarning(posControl.flags.gpsCfEstimatedAltitudeMismatch, warningFlagID <<= 1, &warningsCount)) {
+ if (osdCheckWarning(posControl.flags.gpsCfEstimatedAltitudeMismatch, warningFlagID <<= 1)) {
messages[messageCount++] = "ALT SANITY";
}
#endif
@@ -6572,7 +6553,7 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
// Magnetometer failure
if (requestedSensors[SENSOR_INDEX_MAG] != MAG_NONE) {
hardwareSensorStatus_e magStatus = getHwCompassStatus();
- if (osdCheckWarning(magStatus == HW_SENSOR_UNAVAILABLE || magStatus == HW_SENSOR_UNHEALTHY, warningFlagID <<= 1, &warningsCount)) {
+ if (osdCheckWarning(magStatus == HW_SENSOR_UNAVAILABLE || magStatus == HW_SENSOR_UNHEALTHY, warningFlagID <<= 1)) {
messages[messageCount++] = "MAG FAILED";
}
}
@@ -6581,7 +6562,7 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
#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)) {
+ if (osdCheckWarning(pitotHasFailed(), warningFlagID <<= 1)) {
messages[messageCount++] = "PITOT FAIL";
}
}
@@ -6595,7 +6576,7 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
// }
#ifdef USE_DEV_TOOLS
- if (osdCheckWarning(systemConfig()->groundTestMode, warningFlagID <<= 1, &warningsCount)) {
+ if (osdCheckWarning(systemConfig()->groundTestMode, warningFlagID <<= 1)) {
messages[messageCount++] = "GRD TEST !";
}
#endif
@@ -6603,9 +6584,9 @@ static textAttributes_t osdGetMultiFunctionMessage(char *buff)
if (messageCount) {
message = messages[OSD_ALTERNATING_CHOICES(1000, messageCount)]; // display each warning on 1s cycle
strcpy(buff, message);
- } else if (warningsCount) {
- buff[0] = SYM_ALERT;
- tfp_sprintf(buff + 1, "%u ", warningsCount);
+ if (multiFunctionWarning.newWarningActive) {
+ TEXT_ATTRIBUTES_ADD_BLINK(elemAttr);
+ }
}
return elemAttr;
diff --git a/src/main/io/osd.h b/src/main/io/osd.h
index e066c9194b4..88240ff84c0 100644
--- a/src/main/io/osd.h
+++ b/src/main/io/osd.h
@@ -525,7 +525,6 @@ typedef struct osdConfig_s {
bool use_pilot_logo; // If enabled, the pilot logo (last 40 characters of page 2 font) will be used with the INAV logo.
uint8_t inav_to_pilot_logo_spacing; // The space between the INAV and pilot logos, if pilot logo is used. This number may be adjusted so that it fits the odd/even col width.
uint16_t arm_screen_display_time; // Length of time the arm screen is displayed
- uint8_t multifunction_warning_cycle_time; // Cycle time for display of full multifunction warning messages (s)
#ifndef DISABLE_MSP_DJI_COMPAT
bool highlight_djis_missing_characters; // If enabled, show question marks where there is no character in DJI's font to represent an OSD element symbol
#endif
@@ -586,8 +585,6 @@ int osdFormatVelocityStr(char* buff, int32_t vel, osd_SpeedTypes_e speedType, bo
// Returns a heading angle in degrees normalized to [0, 360).
int osdGetHeadingAngle(int angle);
-void osdResetWarningFlags(void);
-
int16_t osdGetPanServoOffset(void);
/**
From 7ff2464135fbf69aa264d243447d24c1ac3238b3 Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Sun, 1 Mar 2026 23:44:01 +0000
Subject: [PATCH 43/55] pos est corr improvements + vel filtering
---
src/main/common/time.h | 2 +-
.../navigation/navigation_pos_estimator.c | 89 ++++++++++++-------
.../navigation_pos_estimator_flow.c | 2 +-
.../navigation_pos_estimator_private.h | 5 +-
4 files changed, 62 insertions(+), 36 deletions(-)
diff --git a/src/main/common/time.h b/src/main/common/time.h
index 82f29860777..15fc5e2ce08 100644
--- a/src/main/common/time.h
+++ b/src/main/common/time.h
@@ -58,7 +58,7 @@ typedef uint32_t timeUs_t;
#define MS2S(ms) ((ms) * 1e-3f)
#define S2MS(s) ((s) * MILLISECS_PER_SEC)
#define DS2MS(ds) ((ds) * 100)
-#define HZ2S(hz) US2S(HZ2US(hz))
+#define HZ2S(hz) (1.0f / (hz))
// Use this function only to get small deltas (difference overflows at ~35 minutes)
static inline timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b) { return (timeDelta_t)(a - b); }
diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c
index 4252b952c27..8add9c8a2ab 100644
--- a/src/main/navigation/navigation_pos_estimator.c
+++ b/src/main/navigation/navigation_pos_estimator.c
@@ -581,7 +581,7 @@ static bool estimationCalculateCorrection_Z(estimationContext_t * ctx)
if (ctx->newFlags & EST_BARO_VALID && wBaro) {
if (posEstimator.baro.updateDt) { // only update corrections once every sensor update
- ctx->applyCorrections = true;
+ ctx->applyCorrectionsZ = true;
const float dT = posEstimator.baro.updateDt;
bool isAirCushionEffectDetected = false;
@@ -641,7 +641,7 @@ static bool estimationCalculateCorrection_Z(estimationContext_t * ctx)
ctx->newEPV = posEstimator.gps.epv;
}
else {
- ctx->applyCorrections = true;
+ ctx->applyCorrectionsZ = true;
const float dT = posEstimator.gps.updateDt;
// Altitude
@@ -686,7 +686,7 @@ static bool estimationCalculateCorrection_XY_GPS(estimationContext_t * ctx)
ctx->newEPH = posEstimator.gps.eph;
}
else {
- ctx->applyCorrections = true;
+ ctx->applyCorrectionsXY = true;
const float dT = posEstimator.gps.updateDt;
const float gpsPosXResidual = posEstimator.gps.pos.x - posEstimator.est.pos.x;
@@ -743,6 +743,8 @@ static void estimationCalculateGroundCourse(timeUs_t currentTimeUs)
static void updateEstimatedTopic(timeUs_t currentTimeUs)
{
estimationContext_t ctx;
+ static timeMs_t lastXYSensorUpdateMs = 0;
+ static timeMs_t lastZSensorUpdateMs = 0;
const float max_eph_epv = positionEstimationConfig()->max_eph_epv;
@@ -759,13 +761,17 @@ static void updateEstimatedTopic(timeUs_t currentTimeUs)
}
/* Calculate new degraded EPH and EPV for the case we didn't update estimation from sensors - linear degradation in max 10s */
- ctx.newEPH = posEstimator.est.eph + ((posEstimator.est.eph <= max_eph_epv) ? 100.0f * ctx.dt : 0.0f);
- ctx.newEPV = posEstimator.est.epv + ((posEstimator.est.epv <= max_eph_epv) ? 100.0f * ctx.dt : 0.0f);
+ bool XYPosUpdateTimeout = US2MS(currentTimeUs) - lastXYSensorUpdateMs > 200;
+ ctx.newEPH = posEstimator.est.eph + ((posEstimator.est.eph <= max_eph_epv && XYPosUpdateTimeout) ? 100.0f * ctx.dt : 0.0f);
+ bool ZPosUpdateTimeout = US2MS(currentTimeUs) - lastZSensorUpdateMs > 200;
+ ctx.newEPV = posEstimator.est.epv + ((posEstimator.est.epv <= max_eph_epv && ZPosUpdateTimeout) ? 100.0f * ctx.dt : 0.0f);
ctx.newFlags = calculateCurrentValidityFlags(currentTimeUs);
vectorZero(&ctx.estPosCorr);
vectorZero(&ctx.estVelCorr);
vectorZero(&ctx.accBiasCorr);
+ ctx.applyCorrectionsXY = false;
+ ctx.applyCorrectionsZ = false;
/* AGL estimation - separate process, decouples from Z coordinate */
estimationCalculateAGL(&ctx);
@@ -792,43 +798,52 @@ static void updateEstimatedTopic(timeUs_t currentTimeUs)
}
// Only apply corrections if new sensor update available
- if (ctx.applyCorrections) {
- ctx.applyCorrections = false;
-
- // Boost the corrections based on accWeight
- vectorScale(&ctx.estPosCorr, &ctx.estPosCorr, 1.0f / posEstimator.imu.accWeightFactor);
- vectorScale(&ctx.estVelCorr, &ctx.estVelCorr, 1.0f / posEstimator.imu.accWeightFactor);
-
- // Constrain corrections to prevent instability
+ if (ctx.applyCorrectionsXY || ctx.applyCorrectionsZ) {
float maxUpdateDt = MAX(posEstimator.gps.updateDt, posEstimator.baro.updateDt);
maxUpdateDt = MAX(maxUpdateDt, posEstimator.flow.updateDt);
- const float correctionLimit = INAV_EST_CORR_LIMIT_VALUE * maxUpdateDt;
- for (uint8_t axis = 0; axis < 3; axis++) {
+ float correctionLimit = INAV_EST_CORR_LIMIT_VALUE * maxUpdateDt;
+
+ uint8_t axisStart = 0;
+ uint8_t axisEnd = 2;
+ if (!ctx.applyCorrectionsXY) {
+ axisStart = 2;
+ } else if (!ctx.applyCorrectionsZ) {
+ axisEnd = 1;
+ }
+
+ for (uint8_t axis = axisStart; axis <= axisEnd; axis++) {
+ // Boost the corrections based on accWeight
+ ctx.estPosCorr.v[axis] *= 1.0f / posEstimator.imu.accWeightFactor;
+ ctx.estVelCorr.v[axis] *= 1.0f / posEstimator.imu.accWeightFactor;
+
+ // Constrain corrections to prevent instability
ctx.estPosCorr.v[axis] = constrainf(ctx.estPosCorr.v[axis], -correctionLimit, correctionLimit);
ctx.estVelCorr.v[axis] = constrainf(ctx.estVelCorr.v[axis], -correctionLimit, correctionLimit);
- }
- // Apply corrections
- vectorAdd(&posEstimator.est.pos, &posEstimator.est.pos, &ctx.estPosCorr);
- vectorAdd(&posEstimator.est.vel, &posEstimator.est.vel, &ctx.estVelCorr);
-
- /* Correct accelerometer bias */
- const float w_acc_bias = positionEstimationConfig()->w_acc_bias;
- if (w_acc_bias > 0.0f) {
- /* Correct accel bias */
- posEstimator.imu.accelBias.x += ctx.accBiasCorr.x * w_acc_bias;
- posEstimator.imu.accelBias.y += ctx.accBiasCorr.y * w_acc_bias;
- posEstimator.imu.accelBias.z += ctx.accBiasCorr.z * w_acc_bias;
-
- posEstimator.imu.accelBias.x = constrainf(posEstimator.imu.accelBias.x, -INAV_ACC_BIAS_ACCEPTANCE_VALUE, INAV_ACC_BIAS_ACCEPTANCE_VALUE);
- posEstimator.imu.accelBias.y = constrainf(posEstimator.imu.accelBias.y, -INAV_ACC_BIAS_ACCEPTANCE_VALUE, INAV_ACC_BIAS_ACCEPTANCE_VALUE);
- posEstimator.imu.accelBias.z = constrainf(posEstimator.imu.accelBias.z, -INAV_ACC_BIAS_ACCEPTANCE_VALUE, INAV_ACC_BIAS_ACCEPTANCE_VALUE);
+ // Apply corrections
+ posEstimator.est.pos.v[axis] += ctx.estPosCorr.v[axis];
+ posEstimator.est.vel.v[axis] += ctx.estVelCorr.v[axis];
+
+ /* Correct accelerometer bias */
+ const float w_acc_bias = positionEstimationConfig()->w_acc_bias;
+ if (w_acc_bias > 0.0f) {
+ /* Correct accel bias */
+ posEstimator.imu.accelBias.v[axis] += ctx.accBiasCorr.v[axis] * w_acc_bias;
+ posEstimator.imu.accelBias.v[axis] = constrainf(posEstimator.imu.accelBias.v[axis], -INAV_ACC_BIAS_ACCEPTANCE_VALUE, INAV_ACC_BIAS_ACCEPTANCE_VALUE);
+ }
}
// Reset sensor update time deltas once sensor corrections applied after sensor update
posEstimator.gps.updateDt = 0.0f;
posEstimator.baro.updateDt = 0.0f;
posEstimator.flow.updateDt = 0.0f;
+
+ if (ctx.applyCorrectionsXY) {
+ lastXYSensorUpdateMs = US2MS(currentTimeUs);
+ }
+ if (ctx.applyCorrectionsZ) {
+ lastZSensorUpdateMs = US2MS(currentTimeUs);
+ }
}
/* Update ground course */
@@ -860,8 +875,13 @@ static void publishEstimatedTopic(timeUs_t currentTimeUs)
/* Publish position update */
if (posEstimator.est.eph < positionEstimationConfig()->max_eph_epv) {
+ static pt1Filter_t estVelFilterState_X;
+ static pt1Filter_t estVelFilterState_Y;
+ float filteredVelX = pt1FilterApply4(&estVelFilterState_X, posEstimator.est.vel.x, INAV_EST_VEL_F_CUT_HZ, HZ2S(INAV_POSITION_PUBLISH_RATE_HZ));
+ float filteredVelY = pt1FilterApply4(&estVelFilterState_Y, posEstimator.est.vel.y, INAV_EST_VEL_F_CUT_HZ, HZ2S(INAV_POSITION_PUBLISH_RATE_HZ));
+
// FIXME!!!!!
- updateActualHorizontalPositionAndVelocity(true, true, posEstimator.est.pos.x, posEstimator.est.pos.y, posEstimator.est.vel.x, posEstimator.est.vel.y);
+ updateActualHorizontalPositionAndVelocity(true, true, posEstimator.est.pos.x, posEstimator.est.pos.y, filteredVelX, filteredVelY);
}
else {
updateActualHorizontalPositionAndVelocity(false, false, posEstimator.est.pos.x, posEstimator.est.pos.y, 0, 0);
@@ -869,9 +889,12 @@ static void publishEstimatedTopic(timeUs_t currentTimeUs)
/* Publish altitude update and set altitude validity */
if (posEstimator.est.epv < positionEstimationConfig()->max_eph_epv) {
+ static pt1Filter_t estVelFilterState_Z;
+ float filteredVelZ = pt1FilterApply4(&estVelFilterState_Z, posEstimator.est.vel.z, INAV_EST_VEL_F_CUT_HZ, HZ2S(INAV_POSITION_PUBLISH_RATE_HZ));
+
const float gpsCfEstimatedAltitudeError = STATE(GPS_FIX) ? posEstimator.gps.pos.z - posEstimator.est.pos.z : 0;
navigationEstimateStatus_e aglStatus = (posEstimator.est.aglQual == SURFACE_QUAL_LOW) ? EST_USABLE : EST_TRUSTED;
- updateActualAltitudeAndClimbRate(true, posEstimator.est.pos.z, posEstimator.est.vel.z, posEstimator.est.aglAlt, posEstimator.est.aglVel, aglStatus, gpsCfEstimatedAltitudeError);
+ updateActualAltitudeAndClimbRate(true, posEstimator.est.pos.z, filteredVelZ, posEstimator.est.aglAlt, posEstimator.est.aglVel, aglStatus, gpsCfEstimatedAltitudeError);
}
else {
updateActualAltitudeAndClimbRate(false, posEstimator.est.pos.z, 0, posEstimator.est.aglAlt, 0, EST_NONE, 0);
diff --git a/src/main/navigation/navigation_pos_estimator_flow.c b/src/main/navigation/navigation_pos_estimator_flow.c
index 36325f5dc1a..5fc41f8eb78 100644
--- a/src/main/navigation/navigation_pos_estimator_flow.c
+++ b/src/main/navigation/navigation_pos_estimator_flow.c
@@ -124,7 +124,7 @@ bool estimationCalculateCorrection_XY_FLOW(estimationContext_t * ctx)
DEBUG_SET(DEBUG_FLOW, 2, posEstimator.est.flowCoordinates[X]);
DEBUG_SET(DEBUG_FLOW, 3, posEstimator.est.flowCoordinates[Y]);
- return ctx->applyCorrections = true;
+ return ctx->applyCorrectionsXY = true;
#else
UNUSED(ctx);
return false;
diff --git a/src/main/navigation/navigation_pos_estimator_private.h b/src/main/navigation/navigation_pos_estimator_private.h
index 8a91afe268b..2a38155dddb 100644
--- a/src/main/navigation/navigation_pos_estimator_private.h
+++ b/src/main/navigation/navigation_pos_estimator_private.h
@@ -60,6 +60,8 @@
#define RANGEFINDER_RELIABILITY_LOW_THRESHOLD (0.33f)
#define RANGEFINDER_RELIABILITY_HIGH_THRESHOLD (0.75f)
+#define INAV_EST_VEL_F_CUT_HZ 3.0f
+
typedef struct {
timeUs_t lastTriggeredTime;
timeUs_t deltaTime;
@@ -183,7 +185,8 @@ typedef struct {
fpVector3_t estPosCorr;
fpVector3_t estVelCorr;
fpVector3_t accBiasCorr;
- bool applyCorrections;
+ bool applyCorrectionsXY;
+ bool applyCorrectionsZ;
} estimationContext_t;
extern navigationPosEstimator_t posEstimator;
From a539ce17c65630a12f016eb8ea5bcdab6733f9a3 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Mon, 2 Mar 2026 01:38:41 -0600
Subject: [PATCH 44/55] HAKRCH743: Add DMAR for Dshot on all outputs, fix typo
---
src/main/target/HAKRCH743/target.h | 6 ++++--
1 file changed, 4 insertions(+), 2 deletions(-)
diff --git a/src/main/target/HAKRCH743/target.h b/src/main/target/HAKRCH743/target.h
index 8f0d69159f6..e227fc1fa0b 100644
--- a/src/main/target/HAKRCH743/target.h
+++ b/src/main/target/HAKRCH743/target.h
@@ -22,6 +22,8 @@
#define USE_TARGET_CONFIG
+#define USE_DSHOT_DMAR
+
/*** Indicators ***/
#define LED0 PE3
#define LED1 PE4
@@ -31,7 +33,7 @@
/*** SPI/I2C bus ***/
#define USE_SPI
#define USE_SPI_DEVICE_1
-#define SPI1_NSS1_PIN PC15
+#define SPI1_NSS_PIN PC15
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PD7
@@ -175,4 +177,4 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
-#define TARGET_IO_PORTE 0xffff
\ No newline at end of file
+#define TARGET_IO_PORTE 0xffff
From ed37ed2928485d5ce79b6202722be6e70dfa8efb Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Mon, 2 Mar 2026 12:43:35 +0000
Subject: [PATCH 45/55] Update navigation_pos_estimator.c
---
src/main/navigation/navigation_pos_estimator.c | 10 +++++-----
1 file changed, 5 insertions(+), 5 deletions(-)
diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c
index 8add9c8a2ab..41d1c4862ea 100644
--- a/src/main/navigation/navigation_pos_estimator.c
+++ b/src/main/navigation/navigation_pos_estimator.c
@@ -760,11 +760,11 @@ static void updateEstimatedTopic(timeUs_t currentTimeUs)
return;
}
- /* Calculate new degraded EPH and EPV for the case we didn't update estimation from sensors - linear degradation in max 10s */
- bool XYPosUpdateTimeout = US2MS(currentTimeUs) - lastXYSensorUpdateMs > 200;
- ctx.newEPH = posEstimator.est.eph + ((posEstimator.est.eph <= max_eph_epv && XYPosUpdateTimeout) ? 100.0f * ctx.dt : 0.0f);
- bool ZPosUpdateTimeout = US2MS(currentTimeUs) - lastZSensorUpdateMs > 200;
- ctx.newEPV = posEstimator.est.epv + ((posEstimator.est.epv <= max_eph_epv && ZPosUpdateTimeout) ? 100.0f * ctx.dt : 0.0f);
+ /* Calculate new degraded EPH and EPV for the case we didn't update estimation from sensors for > 200ms - linear degradation in max 10s */
+ const bool XYPSensorUpdateTimeout = US2MS(currentTimeUs) - lastXYSensorUpdateMs > 200;
+ ctx.newEPH = posEstimator.est.eph + ((posEstimator.est.eph <= max_eph_epv && XYPSensorUpdateTimeout) ? 100.0f * ctx.dt : 0.0f);
+ const bool ZSensorUpdateTimeout = US2MS(currentTimeUs) - lastZSensorUpdateMs > 200;
+ ctx.newEPV = posEstimator.est.epv + ((posEstimator.est.epv <= max_eph_epv && ZSensorUpdateTimeout) ? 100.0f * ctx.dt : 0.0f);
ctx.newFlags = calculateCurrentValidityFlags(currentTimeUs);
vectorZero(&ctx.estPosCorr);
From 506ea42c99679d449b864ffd8fe9a8d28a17d91e Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Mon, 2 Mar 2026 12:46:40 +0000
Subject: [PATCH 46/55] Update navigation_pos_estimator.c
---
src/main/navigation/navigation_pos_estimator.c | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c
index 41d1c4862ea..51ca98ccb97 100644
--- a/src/main/navigation/navigation_pos_estimator.c
+++ b/src/main/navigation/navigation_pos_estimator.c
@@ -761,8 +761,8 @@ static void updateEstimatedTopic(timeUs_t currentTimeUs)
}
/* Calculate new degraded EPH and EPV for the case we didn't update estimation from sensors for > 200ms - linear degradation in max 10s */
- const bool XYPSensorUpdateTimeout = US2MS(currentTimeUs) - lastXYSensorUpdateMs > 200;
- ctx.newEPH = posEstimator.est.eph + ((posEstimator.est.eph <= max_eph_epv && XYPSensorUpdateTimeout) ? 100.0f * ctx.dt : 0.0f);
+ const bool XYSensorUpdateTimeout = US2MS(currentTimeUs) - lastXYSensorUpdateMs > 200;
+ ctx.newEPH = posEstimator.est.eph + ((posEstimator.est.eph <= max_eph_epv && XYSensorUpdateTimeout) ? 100.0f * ctx.dt : 0.0f);
const bool ZSensorUpdateTimeout = US2MS(currentTimeUs) - lastZSensorUpdateMs > 200;
ctx.newEPV = posEstimator.est.epv + ((posEstimator.est.epv <= max_eph_epv && ZSensorUpdateTimeout) ? 100.0f * ctx.dt : 0.0f);
From 63c255c3cbbe010e754bb77e753423f26d7aa46e Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Mon, 2 Mar 2026 13:37:28 -0600
Subject: [PATCH 47/55] CI: fix pr-test-builds release creation failing with
target_commitish error
The --target flag was passing the inav commit SHA to gh release create
in iNavFlight/pr-test-builds. That SHA does not exist in that repo so
GitHub rejected it with HTTP 422 "Release.target_commitish is invalid".
Remove --target so the release is anchored to the default branch (main)
of pr-test-builds, which is the correct behaviour for a binary hosting
repo.
Co-Authored-By: Claude Sonnet 4.6
---
.github/workflows/pr-test-builds.yml | 2 --
1 file changed, 2 deletions(-)
diff --git a/.github/workflows/pr-test-builds.yml b/.github/workflows/pr-test-builds.yml
index cf4a32b7b57..f969f40218c 100644
--- a/.github/workflows/pr-test-builds.yml
+++ b/.github/workflows/pr-test-builds.yml
@@ -81,7 +81,6 @@ jobs:
PR_NUMBER: ${{ steps.pr.outputs.number }}
SHORT_SHA: ${{ steps.info.outputs.short_sha }}
HEX_COUNT: ${{ steps.info.outputs.count }}
- HEAD_SHA: ${{ github.event.workflow_run.head_sha }}
REPO: ${{ github.repository }}
run: |
PR_URL="https://github.com/${REPO}/pull/${PR_NUMBER}"
@@ -93,7 +92,6 @@ jobs:
gh release create "pr-${PR_NUMBER}" hexes/*.hex \
--repo iNavFlight/pr-test-builds \
--prerelease \
- --target "${HEAD_SHA}" \
--title "PR #${PR_NUMBER} (${SHORT_SHA})" \
--notes-file release-notes.md
From c8b2edcf7647ed8b101dc6a8e6d9a2a24ecdec90 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Mon, 2 Mar 2026 14:28:19 -0600
Subject: [PATCH 48/55] Fix SPI GPIO alternate function assignment on
STM32H7/F7
Create per-pin AF lookup tables (bus_spi_stm32h7xx.h and
bus_spi_stm32f7xx.h) and use them in bus_spi_hal_ll.c to
automatically resolve the correct GPIO AF for each SPI pin.
Previously, SPI3 on STM32H743 applied AF6 to all pins. On H743,
AF6 on PB5 is SPI3_MISO - the MOSI function requires AF7. Targets
routing SPI3_MOSI to PB5 (e.g. HAKRCH743 MAX7456 OSD) received no
MOSI signal. Targets may still define SPI*_SCK/MISO/MOSI_AF in
target.h to override the table.
---
src/main/drivers/bus_spi_hal_ll.c | 164 +++++++++++++++++----------
src/main/drivers/bus_spi_stm32f7xx.h | 78 +++++++++++++
src/main/drivers/bus_spi_stm32h7xx.h | 79 +++++++++++++
3 files changed, 264 insertions(+), 57 deletions(-)
create mode 100644 src/main/drivers/bus_spi_stm32f7xx.h
create mode 100644 src/main/drivers/bus_spi_stm32h7xx.h
diff --git a/src/main/drivers/bus_spi_hal_ll.c b/src/main/drivers/bus_spi_hal_ll.c
index fac8a82761a..ce6fbde9595 100644
--- a/src/main/drivers/bus_spi_hal_ll.c
+++ b/src/main/drivers/bus_spi_hal_ll.c
@@ -89,109 +89,159 @@ static const uint32_t spiDivisorMapSlow[] = {
#endif
#if defined(STM32H7)
-static spiDevice_t spiHardwareMap[SPIDEV_COUNT] = {
+#include "bus_spi_stm32h7xx.h"
+
+// Auto-resolve SPI AF per pin from the lookup table in bus_spi_stm32h7xx.h.
+// Targets may still define individual SPI*_SCK/MISO/MOSI_AF values in target.h
+// to override; explicit defines take priority via these #ifndef guards.
#ifdef USE_SPI_DEVICE_1
-#if defined(SPI1_SCK_AF) || defined(SPI1_MISO_AF) || defined(SPI1_MOSI_AF)
-#if !defined(SPI1_SCK_AF) || !defined(SPI1_MISO_AF) || !defined(SPI1_MOSI_AF)
-#error SPI1: SCK, MISO and MOSI AFs should be defined together in target.h!
+#ifndef SPI1_SCK_AF
+#define SPI1_SCK_AF SPI_PIN_AF_HELPER(1, SPI1_SCK_PIN)
#endif
- { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = SPI1_SCK_AF, .misoAF = SPI1_MISO_AF, .mosiAF = SPI1_MOSI_AF, .divisorMap = spiDivisorMapFast },
-#else
- { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = GPIO_AF5_SPI1, .misoAF = GPIO_AF5_SPI1, .mosiAF = GPIO_AF5_SPI1, .divisorMap = spiDivisorMapFast },
+#ifndef SPI1_MISO_AF
+#define SPI1_MISO_AF SPI_PIN_AF_HELPER(1, SPI1_MISO_PIN)
+#endif
+#ifndef SPI1_MOSI_AF
+#define SPI1_MOSI_AF SPI_PIN_AF_HELPER(1, SPI1_MOSI_PIN)
#endif
-#else
- { .dev = NULL }, // No SPI1
#endif
#ifdef USE_SPI_DEVICE_2
-#if defined(SPI2_SCK_AF) || defined(SPI2_MISO_AF) || defined(SPI2_MOSI_AF)
-#if !defined(SPI2_SCK_AF) || !defined(SPI2_MISO_AF) || !defined(SPI2_MOSI_AF)
-#error SPI2: SCK, MISO and MOSI AFs should be defined together in target.h!
+#ifndef SPI2_SCK_AF
+#define SPI2_SCK_AF SPI_PIN_AF_HELPER(2, SPI2_SCK_PIN)
#endif
- { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1L(SPI2), .sckAF = SPI2_SCK_AF, .misoAF = SPI2_MISO_AF, .mosiAF = SPI2_MOSI_AF, .divisorMap = spiDivisorMapSlow },
+#ifndef SPI2_MISO_AF
+#define SPI2_MISO_AF SPI_PIN_AF_HELPER(2, SPI2_MISO_PIN)
+#endif
+#ifndef SPI2_MOSI_AF
+#define SPI2_MOSI_AF SPI_PIN_AF_HELPER(2, SPI2_MOSI_PIN)
+#endif
+#endif
+
+#ifdef USE_SPI_DEVICE_3
+#ifndef SPI3_SCK_AF
+#define SPI3_SCK_AF SPI_PIN_AF_HELPER(3, SPI3_SCK_PIN)
+#endif
+#ifndef SPI3_MISO_AF
+#define SPI3_MISO_AF SPI_PIN_AF_HELPER(3, SPI3_MISO_PIN)
+#endif
+#ifndef SPI3_MOSI_AF
+#define SPI3_MOSI_AF SPI_PIN_AF_HELPER(3, SPI3_MOSI_PIN)
+#endif
+#endif
+
+#ifdef USE_SPI_DEVICE_4
+#ifndef SPI4_SCK_AF
+#define SPI4_SCK_AF SPI_PIN_AF_HELPER(4, SPI4_SCK_PIN)
+#endif
+#ifndef SPI4_MISO_AF
+#define SPI4_MISO_AF SPI_PIN_AF_HELPER(4, SPI4_MISO_PIN)
+#endif
+#ifndef SPI4_MOSI_AF
+#define SPI4_MOSI_AF SPI_PIN_AF_HELPER(4, SPI4_MOSI_PIN)
+#endif
+#endif
+
+static spiDevice_t spiHardwareMap[SPIDEV_COUNT] = {
+#ifdef USE_SPI_DEVICE_1
+ { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = SPI1_SCK_AF, .misoAF = SPI1_MISO_AF, .mosiAF = SPI1_MOSI_AF, .divisorMap = spiDivisorMapFast },
#else
- { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1L(SPI2), .sckAF = GPIO_AF5_SPI2, .misoAF = GPIO_AF5_SPI2, .mosiAF = GPIO_AF5_SPI2, .divisorMap = spiDivisorMapSlow },
+ { .dev = NULL }, // No SPI1
#endif
+
+#ifdef USE_SPI_DEVICE_2
+ { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1L(SPI2), .sckAF = SPI2_SCK_AF, .misoAF = SPI2_MISO_AF, .mosiAF = SPI2_MOSI_AF, .divisorMap = spiDivisorMapSlow },
#else
{ .dev = NULL }, // No SPI2
#endif
#ifdef USE_SPI_DEVICE_3
-#if defined(SPI3_SCK_AF) || defined(SPI3_MISO_AF) || defined(SPI3_MOSI_AF)
-#if !defined(SPI3_SCK_AF) || !defined(SPI3_MISO_AF) || !defined(SPI3_MOSI_AF)
-#error SPI3: SCK, MISO and MOSI AFs should be defined together in target.h!
-#endif
{ .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1L(SPI3), .sckAF = SPI3_SCK_AF, .misoAF = SPI3_MISO_AF, .mosiAF = SPI3_MOSI_AF, .divisorMap = spiDivisorMapSlow },
-#else
- { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1L(SPI3), .sckAF = GPIO_AF6_SPI3, .misoAF = GPIO_AF6_SPI3, .mosiAF = GPIO_AF6_SPI3, .divisorMap = spiDivisorMapSlow },
-#endif
#else
{ .dev = NULL }, // No SPI3
#endif
#ifdef USE_SPI_DEVICE_4
-#if defined(SPI4_SCK_AF) || defined(SPI4_MISO_AF) || defined(SPI4_MOSI_AF)
-#if !defined(SPI4_SCK_AF) || !defined(SPI4_MISO_AF) || !defined(SPI4_MOSI_AF)
-#error SPI4: SCK, MISO and MOSI AFs should be defined together in target.h!
-#endif
{ .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .sckAF = SPI4_SCK_AF, .misoAF = SPI4_MISO_AF, .mosiAF = SPI4_MOSI_AF, .divisorMap = spiDivisorMapSlow }
-#else
- { .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .sckAF = GPIO_AF5_SPI4, .misoAF = GPIO_AF5_SPI4, .mosiAF = GPIO_AF5_SPI4, .divisorMap = spiDivisorMapSlow }
-#endif
#else
{ .dev = NULL } // No SPI4
#endif
};
-#else
-static spiDevice_t spiHardwareMap[] = {
+#elif defined(STM32F7)
+#include "bus_spi_stm32f7xx.h"
+
+// Auto-resolve SPI AF per pin from the lookup table in bus_spi_stm32f7xx.h.
+// Targets may still define individual SPI*_SCK/MISO/MOSI_AF values in target.h
+// to override; explicit defines take priority via these #ifndef guards.
#ifdef USE_SPI_DEVICE_1
-#if defined(SPI1_SCK_AF) || defined(SPI1_MISO_AF) || defined(SPI1_MOSI_AF)
-#if !defined(SPI1_SCK_AF) || !defined(SPI1_MISO_AF) || !defined(SPI1_MOSI_AF)
-#error SPI1: SCK, MISO and MOSI AFs should be defined together in target.h!
+#ifndef SPI1_SCK_AF
+#define SPI1_SCK_AF SPI_PIN_AF_HELPER(1, SPI1_SCK_PIN)
#endif
- { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = SPI1_SCK_AF, .misoAF = SPI1_MISO_AF, .mosiAF = SPI1_MOSI_AF, .divisorMap = spiDivisorMapFast },
-#else
- { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = GPIO_AF5_SPI1, .misoAF = GPIO_AF5_SPI1, .mosiAF = GPIO_AF5_SPI1, .divisorMap = spiDivisorMapFast },
+#ifndef SPI1_MISO_AF
+#define SPI1_MISO_AF SPI_PIN_AF_HELPER(1, SPI1_MISO_PIN)
+#endif
+#ifndef SPI1_MOSI_AF
+#define SPI1_MOSI_AF SPI_PIN_AF_HELPER(1, SPI1_MOSI_PIN)
#endif
-#else
- { .dev = NULL }, // No SPI1
#endif
#ifdef USE_SPI_DEVICE_2
-#if defined(SPI2_SCK_AF) || defined(SPI2_MISO_AF) || defined(SPI2_MOSI_AF)
-#if !defined(SPI2_SCK_AF) || !defined(SPI2_MISO_AF) || !defined(SPI2_MOSI_AF)
-#error SPI2: SCK, MISO and MOSI AFs should be defined together in target.h!
+#ifndef SPI2_SCK_AF
+#define SPI2_SCK_AF SPI_PIN_AF_HELPER(2, SPI2_SCK_PIN)
#endif
- { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .sckAF = SPI2_SCK_AF, .misoAF = SPI2_MISO_AF, .mosiAF = SPI2_MOSI_AF, .divisorMap = spiDivisorMapSlow },
+#ifndef SPI2_MISO_AF
+#define SPI2_MISO_AF SPI_PIN_AF_HELPER(2, SPI2_MISO_PIN)
+#endif
+#ifndef SPI2_MOSI_AF
+#define SPI2_MOSI_AF SPI_PIN_AF_HELPER(2, SPI2_MOSI_PIN)
+#endif
+#endif
+
+#ifdef USE_SPI_DEVICE_3
+#ifndef SPI3_SCK_AF
+#define SPI3_SCK_AF SPI_PIN_AF_HELPER(3, SPI3_SCK_PIN)
+#endif
+#ifndef SPI3_MISO_AF
+#define SPI3_MISO_AF SPI_PIN_AF_HELPER(3, SPI3_MISO_PIN)
+#endif
+#ifndef SPI3_MOSI_AF
+#define SPI3_MOSI_AF SPI_PIN_AF_HELPER(3, SPI3_MOSI_PIN)
+#endif
+#endif
+
+#ifdef USE_SPI_DEVICE_4
+#ifndef SPI4_SCK_AF
+#define SPI4_SCK_AF SPI_PIN_AF_HELPER(4, SPI4_SCK_PIN)
+#endif
+#ifndef SPI4_MISO_AF
+#define SPI4_MISO_AF SPI_PIN_AF_HELPER(4, SPI4_MISO_PIN)
+#endif
+#ifndef SPI4_MOSI_AF
+#define SPI4_MOSI_AF SPI_PIN_AF_HELPER(4, SPI4_MOSI_PIN)
+#endif
+#endif
+
+static spiDevice_t spiHardwareMap[] = {
+#ifdef USE_SPI_DEVICE_1
+ { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = SPI1_SCK_AF, .misoAF = SPI1_MISO_AF, .mosiAF = SPI1_MOSI_AF, .divisorMap = spiDivisorMapFast },
#else
- { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .sckAF = GPIO_AF5_SPI2, .misoAF = GPIO_AF5_SPI2, .mosiAF = GPIO_AF5_SPI2, .divisorMap = spiDivisorMapSlow },
+ { .dev = NULL }, // No SPI1
#endif
+
+#ifdef USE_SPI_DEVICE_2
+ { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .sckAF = SPI2_SCK_AF, .misoAF = SPI2_MISO_AF, .mosiAF = SPI2_MOSI_AF, .divisorMap = spiDivisorMapSlow },
#else
{ .dev = NULL }, // No SPI2
#endif
#ifdef USE_SPI_DEVICE_3
-#if defined(SPI3_SCK_AF) || defined(SPI3_MISO_AF) || defined(SPI3_MOSI_AF)
-#if !defined(SPI3_SCK_AF) || !defined(SPI3_MISO_AF) || !defined(SPI3_MOSI_AF)
-#error SPI3: SCK, MISO and MOSI AFs should be defined together in target.h!
-#endif
{ .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .sckAF = SPI3_SCK_AF, .misoAF = SPI3_MISO_AF, .mosiAF = SPI3_MOSI_AF, .divisorMap = spiDivisorMapSlow },
-#else
- { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .sckAF = GPIO_AF6_SPI3, .misoAF = GPIO_AF6_SPI3, .mosiAF = GPIO_AF6_SPI3, .divisorMap = spiDivisorMapSlow },
-#endif
#else
{ .dev = NULL }, // No SPI3
#endif
#ifdef USE_SPI_DEVICE_4
-#if defined(SPI4_SCK_AF) || defined(SPI4_MISO_AF) || defined(SPI4_MOSI_AF)
-#if !defined(SPI4_SCK_AF) || !defined(SPI4_MISO_AF) || !defined(SPI4_MOSI_AF)
-#error SPI3: SCK, MISO and MOSI AFs should be defined together in target.h!
-#endif
{ .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .sckAF = SPI4_SCK_AF, .misoAF = SPI4_MISO_AF, .mosiAF = SPI4_MOSI_AF, .divisorMap = spiDivisorMapSlow }
-#else
- { .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .sckAF = GPIO_AF5_SPI4, .misoAF = GPIO_AF5_SPI4, .mosiAF = GPIO_AF5_SPI4, .divisorMap = spiDivisorMapSlow }
-#endif
#else
{ .dev = NULL } // No SPI4
#endif
diff --git a/src/main/drivers/bus_spi_stm32f7xx.h b/src/main/drivers/bus_spi_stm32f7xx.h
new file mode 100644
index 00000000000..d8a4d246cf6
--- /dev/null
+++ b/src/main/drivers/bus_spi_stm32f7xx.h
@@ -0,0 +1,78 @@
+/*
+ * 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 .
+ */
+
+/*
+ * STM32F7 SPI pin alternate function lookup table.
+ *
+ * Usage: SPI_PIN_AF_HELPER(3, PB5) expands to SPI_PIN_AF_SPI3_PB5,
+ * which is defined below as GPIO_AF6_SPI3.
+ *
+ * AF assignments from STM32F722 datasheet (DS11853) and STM32F745 datasheet
+ * (DS10916), Table 9.
+ *
+ * NOTE: The F7 AF table differs from the H7 for SPI3/PB5:
+ * On F7, PB5 SPI3_MOSI is AF6 (the default).
+ * On H7, PB5 SPI3_MOSI is AF7 (an exception — see bus_spi_stm32h7xx.h).
+ *
+ * SPI1, SPI2, SPI4 pins are all AF5 with no exceptions.
+ * SPI3 SCK/MISO are AF6. SPI3 MOSI has pin-dependent exceptions:
+ * PB2 uses AF7 (not AF6). PD6 uses AF5 (not AF6). PC12 and PB5 use AF6.
+ */
+
+#pragma once
+
+// Resolves to SPI_PIN_AF_SPIn_Pxy, defined below for each valid pin.
+// If a pin is not in the table the build will fail with "undefined identifier",
+// which is preferable to silently applying the wrong AF.
+#define SPI_PIN_AF_HELPER(spi, pin) CONCAT4(SPI_PIN_AF_SPI, spi, _, pin)
+
+/* SPI1 — all data pins use AF5 */
+#define SPI_PIN_AF_SPI1_PA5 GPIO_AF5_SPI1 // SCK
+#define SPI_PIN_AF_SPI1_PA6 GPIO_AF5_SPI1 // MISO
+#define SPI_PIN_AF_SPI1_PA7 GPIO_AF5_SPI1 // MOSI
+#define SPI_PIN_AF_SPI1_PB3 GPIO_AF5_SPI1 // SCK
+#define SPI_PIN_AF_SPI1_PB4 GPIO_AF5_SPI1 // MISO
+#define SPI_PIN_AF_SPI1_PB5 GPIO_AF5_SPI1 // MOSI
+
+/* SPI2 — all data pins use AF5 */
+#define SPI_PIN_AF_SPI2_PB13 GPIO_AF5_SPI2 // SCK
+#define SPI_PIN_AF_SPI2_PB14 GPIO_AF5_SPI2 // MISO
+#define SPI_PIN_AF_SPI2_PB15 GPIO_AF5_SPI2 // MOSI
+#define SPI_PIN_AF_SPI2_PC1 GPIO_AF5_SPI2 // MOSI
+#define SPI_PIN_AF_SPI2_PC2 GPIO_AF5_SPI2 // MISO
+#define SPI_PIN_AF_SPI2_PC3 GPIO_AF5_SPI2 // MOSI
+
+/*
+ * SPI3 — SCK and MISO use AF6, but MOSI has pin-dependent exceptions.
+ * PB2 carries SPI3_MOSI on AF7 (not AF6). PD6 uses AF5. PB5 and PC12 use AF6.
+ */
+#define SPI_PIN_AF_SPI3_PB2 GPIO_AF7_SPI3 // MOSI — exception: AF7, not AF6
+#define SPI_PIN_AF_SPI3_PB3 GPIO_AF6_SPI3 // SCK
+#define SPI_PIN_AF_SPI3_PB4 GPIO_AF6_SPI3 // MISO
+#define SPI_PIN_AF_SPI3_PB5 GPIO_AF6_SPI3 // MOSI (AF6 on F7; H7 uses AF7 for this pin)
+#define SPI_PIN_AF_SPI3_PC10 GPIO_AF6_SPI3 // SCK
+#define SPI_PIN_AF_SPI3_PC11 GPIO_AF6_SPI3 // MISO
+#define SPI_PIN_AF_SPI3_PC12 GPIO_AF6_SPI3 // MOSI
+#define SPI_PIN_AF_SPI3_PD6 GPIO_AF5_SPI3 // MOSI — exception: AF5, not AF6
+
+/* SPI4 — all data pins use AF5 */
+#define SPI_PIN_AF_SPI4_PE2 GPIO_AF5_SPI4 // SCK
+#define SPI_PIN_AF_SPI4_PE5 GPIO_AF5_SPI4 // MISO
+#define SPI_PIN_AF_SPI4_PE6 GPIO_AF5_SPI4 // MOSI
+#define SPI_PIN_AF_SPI4_PE12 GPIO_AF5_SPI4 // SCK
+#define SPI_PIN_AF_SPI4_PE13 GPIO_AF5_SPI4 // MISO
+#define SPI_PIN_AF_SPI4_PE14 GPIO_AF5_SPI4 // MOSI
diff --git a/src/main/drivers/bus_spi_stm32h7xx.h b/src/main/drivers/bus_spi_stm32h7xx.h
new file mode 100644
index 00000000000..67ff4071d42
--- /dev/null
+++ b/src/main/drivers/bus_spi_stm32h7xx.h
@@ -0,0 +1,79 @@
+/*
+ * 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 .
+ */
+
+/*
+ * STM32H7 SPI pin alternate function lookup table.
+ *
+ * Usage: SPI_PIN_AF_HELPER(3, PB5) expands to SPI_PIN_AF_SPI3_PB5,
+ * which is defined below as GPIO_AF7_SPI3.
+ *
+ * This allows bus_spi_hal_ll.c to resolve the correct AF per pin automatically,
+ * without requiring each target to define SPI*_SCK_AF / SPI*_MISO_AF / SPI*_MOSI_AF
+ * manually in target.h. Targets may still override individual values if needed.
+ *
+ * Alternate function assignments are from the STM32H743 datasheet (DS12110),
+ * Tables 10-14.
+ */
+
+#pragma once
+
+// Resolves to SPI_PIN_AF_SPIn_Pxy, which is defined below for each valid pin.
+// If a pin is not in the table the build will fail with "undefined identifier",
+// which is preferable to silently applying the wrong AF.
+#define SPI_PIN_AF_HELPER(spi, pin) CONCAT4(SPI_PIN_AF_SPI, spi, _, pin)
+
+/* SPI1 — all data pins use AF5 */
+#define SPI_PIN_AF_SPI1_PA5 GPIO_AF5_SPI1 // SCK
+#define SPI_PIN_AF_SPI1_PA6 GPIO_AF5_SPI1 // MISO
+#define SPI_PIN_AF_SPI1_PA7 GPIO_AF5_SPI1 // MOSI
+#define SPI_PIN_AF_SPI1_PB3 GPIO_AF5_SPI1 // SCK
+#define SPI_PIN_AF_SPI1_PB4 GPIO_AF5_SPI1 // MISO
+#define SPI_PIN_AF_SPI1_PB5 GPIO_AF5_SPI1 // MOSI
+#define SPI_PIN_AF_SPI1_PD7 GPIO_AF5_SPI1 // MOSI
+
+/* SPI2 — all data pins use AF5 */
+#define SPI_PIN_AF_SPI2_PA9 GPIO_AF5_SPI2 // SCK
+#define SPI_PIN_AF_SPI2_PB10 GPIO_AF5_SPI2 // SCK
+#define SPI_PIN_AF_SPI2_PB13 GPIO_AF5_SPI2 // SCK
+#define SPI_PIN_AF_SPI2_PB14 GPIO_AF5_SPI2 // MISO
+#define SPI_PIN_AF_SPI2_PB15 GPIO_AF5_SPI2 // MOSI
+#define SPI_PIN_AF_SPI2_PC1 GPIO_AF5_SPI2 // MOSI
+#define SPI_PIN_AF_SPI2_PC2 GPIO_AF5_SPI2 // MISO
+#define SPI_PIN_AF_SPI2_PC3 GPIO_AF5_SPI2 // MOSI
+#define SPI_PIN_AF_SPI2_PD3 GPIO_AF5_SPI2 // SCK
+
+/*
+ * SPI3 — SCK and MISO use AF6, but MOSI has pin-dependent exceptions.
+ * PB2 and PB5 carry SPI3_MOSI on AF7 (not AF6). PD6 uses AF5.
+ * This is the only SPI bus on STM32H743 where a single-AF fallback is wrong.
+ */
+#define SPI_PIN_AF_SPI3_PB2 GPIO_AF7_SPI3 // MOSI — exception: AF7, not AF6
+#define SPI_PIN_AF_SPI3_PB3 GPIO_AF6_SPI3 // SCK
+#define SPI_PIN_AF_SPI3_PB4 GPIO_AF6_SPI3 // MISO
+#define SPI_PIN_AF_SPI3_PB5 GPIO_AF7_SPI3 // MOSI — exception: AF7, not AF6
+#define SPI_PIN_AF_SPI3_PC10 GPIO_AF6_SPI3 // SCK
+#define SPI_PIN_AF_SPI3_PC11 GPIO_AF6_SPI3 // MISO
+#define SPI_PIN_AF_SPI3_PC12 GPIO_AF6_SPI3 // MOSI
+#define SPI_PIN_AF_SPI3_PD6 GPIO_AF5_SPI3 // MOSI — exception: AF5, not AF6
+
+/* SPI4 — all data pins use AF5 */
+#define SPI_PIN_AF_SPI4_PE2 GPIO_AF5_SPI4 // SCK
+#define SPI_PIN_AF_SPI4_PE5 GPIO_AF5_SPI4 // MISO
+#define SPI_PIN_AF_SPI4_PE6 GPIO_AF5_SPI4 // MOSI
+#define SPI_PIN_AF_SPI4_PE12 GPIO_AF5_SPI4 // SCK
+#define SPI_PIN_AF_SPI4_PE13 GPIO_AF5_SPI4 // MISO
+#define SPI_PIN_AF_SPI4_PE14 GPIO_AF5_SPI4 // MOSI
From 6817a6643b32a5338f2f931acf75fb3114ef8f90 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Mon, 2 Mar 2026 16:37:59 -0600
Subject: [PATCH 49/55] drivers: explicitly include common/utils.h in SPI AF
lookup headers
Both bus_spi_stm32h7xx.h and bus_spi_stm32f7xx.h use CONCAT4 but relied
on transitive includes from the including translation unit to provide it.
Add an explicit include to make the dependency self-contained.
---
src/main/drivers/bus_spi_stm32f7xx.h | 2 ++
src/main/drivers/bus_spi_stm32h7xx.h | 2 ++
2 files changed, 4 insertions(+)
diff --git a/src/main/drivers/bus_spi_stm32f7xx.h b/src/main/drivers/bus_spi_stm32f7xx.h
index d8a4d246cf6..a43938e1e45 100644
--- a/src/main/drivers/bus_spi_stm32f7xx.h
+++ b/src/main/drivers/bus_spi_stm32f7xx.h
@@ -35,6 +35,8 @@
#pragma once
+#include "common/utils.h"
+
// Resolves to SPI_PIN_AF_SPIn_Pxy, defined below for each valid pin.
// If a pin is not in the table the build will fail with "undefined identifier",
// which is preferable to silently applying the wrong AF.
diff --git a/src/main/drivers/bus_spi_stm32h7xx.h b/src/main/drivers/bus_spi_stm32h7xx.h
index 67ff4071d42..286e5859816 100644
--- a/src/main/drivers/bus_spi_stm32h7xx.h
+++ b/src/main/drivers/bus_spi_stm32h7xx.h
@@ -31,6 +31,8 @@
#pragma once
+#include "common/utils.h"
+
// Resolves to SPI_PIN_AF_SPIn_Pxy, which is defined below for each valid pin.
// If a pin is not in the table the build will fail with "undefined identifier",
// which is preferable to silently applying the wrong AF.
From 36bb13daabbfd6ce83ae85cad38a21e92bb77d2d Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Mon, 2 Mar 2026 17:49:09 -0600
Subject: [PATCH 50/55] cmake/sitl: guard CheckLinkerFlag for compatibility
with CMake < 3.18
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
check_linker_flag() requires CMake 3.18. Use include(CheckLinkerFlag OPTIONAL)
and if(COMMAND check_linker_flag) to probe for the module's availability rather
than hardcoding a version number. On CMake < 3.18 the include silently does
nothing, the guard skips the call, and LINKER_SUPPORTS_NO_RWX_WARNING is left
unset — the flag is simply not added, which is safe because linkers old enough
to ship with CMake < 3.18 do not produce the RWX warning anyway.
---
cmake/sitl.cmake | 6 ++++--
1 file changed, 4 insertions(+), 2 deletions(-)
diff --git a/cmake/sitl.cmake b/cmake/sitl.cmake
index a5a98a779b6..c94fca21209 100644
--- a/cmake/sitl.cmake
+++ b/cmake/sitl.cmake
@@ -64,8 +64,10 @@ if(NOT MACOSX)
-Wno-error=maybe-uninitialized
-fsingle-precision-constant
)
- include(CheckLinkerFlag)
- check_linker_flag(C "-Wl,--no-warn-rwx-segments" LINKER_SUPPORTS_NO_RWX_WARNING)
+ include(CheckLinkerFlag OPTIONAL)
+ if(COMMAND check_linker_flag)
+ check_linker_flag(C "-Wl,--no-warn-rwx-segments" LINKER_SUPPORTS_NO_RWX_WARNING)
+ endif()
if(LINKER_SUPPORTS_NO_RWX_WARNING)
set(SITL_LINK_OPTIONS ${SITL_LINK_OPTIONS} "-Wl,--no-warn-rwx-segments")
endif()
From 9d44fe5592d82294b4f2fd1ba1b30c460b7c39de Mon Sep 17 00:00:00 2001
From: breadoven <56191411+breadoven@users.noreply.github.com>
Date: Tue, 3 Mar 2026 17:12:13 +0000
Subject: [PATCH 51/55] Trackback FC crash fix
---
src/main/navigation/rth_trackback.c | 9 +++++----
1 file changed, 5 insertions(+), 4 deletions(-)
diff --git a/src/main/navigation/rth_trackback.c b/src/main/navigation/rth_trackback.c
index dfdcf801f7c..2d9c5e53148 100644
--- a/src/main/navigation/rth_trackback.c
+++ b/src/main/navigation/rth_trackback.c
@@ -153,10 +153,11 @@ bool rthTrackBackSetNewPosition(void)
rth_trackback.activePointIndex = NAV_RTH_TRACKBACK_POINTS - 1;
}
- calculateAndSetActiveWaypointToLocalPosition(getRthTrackBackPosition());
-
- if (rth_trackback.activePointIndex - rth_trackback.WrapAroundCounter == 0) {
- rth_trackback.WrapAroundCounter = rth_trackback.activePointIndex = -1;
+ // Last trackback point reached when activePointIndex = WrapAroundCounter so only set position when not equal
+ if (rth_trackback.activePointIndex != rth_trackback.WrapAroundCounter) {
+ calculateAndSetActiveWaypointToLocalPosition(getRthTrackBackPosition());
+ } else {
+ rth_trackback.activePointIndex = -1; // if not already = -1 set to -1 to end trackback next iteration
}
} else {
setDesiredPosition(getRthTrackBackPosition(), 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_BEARING);
From 873e9d6480e054cb754ed24f290343c26f37058b Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Pawe=C5=82=20Spychalski?=
Date: Wed, 4 Mar 2026 19:31:40 +0100
Subject: [PATCH 52/55] Add AGENT.md rules
---
AGENT.md | 461 +++++++++++++++++++++++++++++++++++++++++++++++++++++++
1 file changed, 461 insertions(+)
create mode 100644 AGENT.md
diff --git a/AGENT.md b/AGENT.md
new file mode 100644
index 00000000000..50a15dc0af8
--- /dev/null
+++ b/AGENT.md
@@ -0,0 +1,461 @@
+# AGENT.md - Guide for AI Agents Working with INAV
+
+## Project Overview
+
+**INAV** is a navigation-capable flight controller firmware for multirotor, fixed-wing, and other RC vehicles. It is a community-driven project written primarily in C (C99/C11 standard) with support for STM32 F4, F7, H7, and AT32 microcontrollers.
+
+### Key Characteristics
+- **Type**: Embedded firmware for flight controllers
+- **Language**: C (C99/C11), with some C++ for unit tests
+- **Build System**: CMake (version 3.13+)
+- **License**: GNU GPL v3
+- **Version**: 9.0.1 (as of this writing)
+- **Codebase History**: Evolved from Cleanflight/Baseflight
+
+## Architecture and Structure
+
+### Core Components
+
+The INAV codebase is organized into the following major subsystems:
+
+1. **Flight Control (`fc/`)**: Core flight controller logic, initialization, MSP protocol handling
+2. **Sensors (`sensors/`)**: Gyro, accelerometer, compass, barometer, GPS, rangefinder, pitot tube
+3. **Flight (`flight/`)**: PID controllers, mixers, altitude hold, position hold, navigation
+4. **Navigation (`navigation/`)**: Waypoint missions, RTH (Return to Home), position hold
+5. **Drivers (`drivers/`)**: Hardware abstraction layer for MCU peripherals (SPI, I2C, UART, timers, etc.)
+6. **IO (`io/`)**: Serial communication, OSD, LED strips, telemetry
+7. **RX (`rx/`)**: Radio receiver protocols (CRSF, SBUS, IBUS, etc.)
+8. **Scheduler (`scheduler/`)**: Real-time task scheduling
+9. **Configuration (`config/`)**: Parameter groups, EEPROM storage, settings management
+10. **MSP (`msp/`)**: MultiWii Serial Protocol implementation
+11. **Telemetry (`telemetry/`)**: SmartPort, FPort, MAVLink, LTM, CRSF telemetry
+12. **Blackbox (`blackbox/`)**: Flight data recorder
+13. **Programming (`programming/`)**: Logic conditions and global functions for in-flight programming
+
+### Directory Structure
+
+```
+/src/main/ - Main source code
+ ├── build/ - Build configuration and macros
+ ├── common/ - Common utilities (math, filters, utils)
+ ├── config/ - Configuration system (parameter groups)
+ ├── drivers/ - Hardware drivers (MCU-specific)
+ ├── fc/ - Flight controller core
+ ├── flight/ - Flight control algorithms
+ ├── io/ - Input/output (serial, OSD, LED)
+ ├── msp/ - MSP protocol
+ ├── navigation/ - Navigation and autopilot
+ ├── rx/ - Radio receiver protocols
+ ├── sensors/ - Sensor drivers and processing
+ ├── scheduler/ - Task scheduler
+ ├── telemetry/ - Telemetry protocols
+ └── target/ - Board-specific configurations
+
+/docs/ - Documentation
+ └── development/ - Developer documentation
+
+/cmake/ - CMake build scripts
+/lib/ - External libraries
+/tools/ - Build and utility tools
+```
+
+## Coding Conventions
+
+### Naming Conventions
+
+1. **Types**: Use `_t` suffix for typedef'd types: `gyroConfig_t`, `pidController_t`
+2. **Enums**: Use `_e` suffix for enum types: `portMode_e`, `cfTaskPriority_e`
+3. **Functions**: Use camelCase with verb-phrase names: `gyroInit()`, `deleteAllPages()`
+4. **Variables**: Use camelCase nouns, avoid noise words like "data" or "info"
+5. **Booleans**: Question format: `isOkToArm()`, `canNavigate()`
+6. **Constants**: Upper case with underscores: `MAX_GYRO_COUNT`
+7. **Macros**: Upper case with underscores: `FASTRAM`, `STATIC_UNIT_TESTED`
+
+### Code Style
+
+- **Indentation**: 4 spaces (no tabs)
+- **Braces**: K&R style (opening brace on same line, except for functions)
+- **Line Length**: Keep reasonable (typically under 120 characters)
+- **Comments**: Explain WHY, not WHAT. Document variables at declaration, not at extern usage
+- **Header Guards**: Use `#pragma once` (modern convention used throughout codebase)
+
+### Memory Attributes
+
+INAV uses special memory attributes for performance-critical code on resource-constrained MCUs:
+
+```c
+FASTRAM // Fast RAM section (aligned)
+EXTENDED_FASTRAM // Extended fast RAM (STM32F4/F7 only)
+DMA_RAM // DMA-accessible RAM (STM32H7, AT32F43x)
+SLOW_RAM // Slower external RAM - deprecated, o not use
+STATIC_FASTRAM // Static variable in fast RAM
+STATIC_FASTRAM_UNIT_TESTED // Static fast RAM variable visible in unit tests
+```
+
+### Test Visibility Macros
+
+```c
+STATIC_UNIT_TESTED // static in production, visible in unit tests
+STATIC_INLINE_UNIT_TESTED // static inline in production, visible in tests
+INLINE_UNIT_TESTED // inline in production, visible in tests
+UNIT_TESTED // Always visible (no storage class)
+```
+
+## Build System
+
+### CMake Build Process
+
+INAV uses CMake with custom target definition functions:
+
+1. **Target Definition**: Each board has a `target.h` and optionally `CMakeLists.txt`
+2. **Hardware Function**: `target_stm32f405xg(NAME optional_params)`
+3. **Build Directory**: Always use out-of-source builds in `/build` directory
+
+### Building a Target
+
+```bash
+# From workspace root
+cd build
+cmake ..
+make MATEKF722SE # Build specific target
+make # Build all targets
+```
+
+### Target Configuration
+
+Targets are defined in `/src/main/target/TARGETNAME/`:
+- `target.h`: Hardware pin definitions, feature enables, MCU configuration
+- `target.c`: Board-specific initialization code
+- `CMakeLists.txt`: Build configuration (optional)
+
+Example target definition:
+```c
+#define TARGET_BOARD_IDENTIFIER "MF7S"
+#define LED0 PA14
+#define BEEPER PC13
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+```
+
+### Conditional Compilation
+
+Feature flags control code inclusion:
+```c
+#ifdef USE_GPS
+ // GPS code
+#endif
+
+#if defined(STM32F4)
+ // F4-specific code
+#elif defined(STM32F7)
+ // F7-specific code
+#endif
+```
+
+## Key Concepts
+
+### Parameter Groups (PG)
+
+INAV uses a sophisticated configuration system called "Parameter Groups" for persistent storage:
+
+```c
+// Define a configuration structure
+typedef struct {
+ uint8_t gyro_lpf_hz;
+ uint16_t gyro_kalman_q;
+ // ...
+} gyroConfig_t;
+
+// Register with reset template
+PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 12);
+
+// Define default values
+PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
+ .gyro_lpf_hz = 60,
+ .gyro_kalman_q = 200,
+ // ...
+);
+
+// Access in code
+gyroConfig()->gyro_lpf_hz
+```
+
+**Key Functions:**
+- `PG_REGISTER_WITH_RESET_TEMPLATE()`: Register with static defaults
+- `PG_REGISTER_WITH_RESET_FN()`: Register with function-based initialization
+- `PG_REGISTER_ARRAY()`: For arrays of configuration items
+- Parameter group IDs are in `config/parameter_group_ids.h`
+
+### Scheduler
+
+INAV uses a priority-based cooperative task scheduler:
+
+```c
+typedef enum {
+ TASK_PRIORITY_IDLE = 0,
+ TASK_PRIORITY_LOW = 1,
+ TASK_PRIORITY_MEDIUM = 3,
+ TASK_PRIORITY_HIGH = 5,
+ TASK_PRIORITY_REALTIME = 18,
+} cfTaskPriority_e;
+```
+
+Tasks are defined in `fc/fc_tasks.c` with priority and desired execution period.
+
+### Sensors and Calibration
+
+Sensors use a common pattern:
+1. **Detection**: Auto-detect hardware at boot (`gyroDetect()`, `baroDetect()`)
+2. **Initialization**: Configure sensor parameters
+3. **Calibration**: Zero-offset calibration (gyro, accelerometer)
+4. **Data Processing**: Apply calibration, alignment, and filtering
+
+### Flight Control Loop
+
+The main control loop follows this pattern:
+1. **Gyro Task** (highest priority): Read gyro, apply filters
+2. **PID Task**: Calculate PID corrections
+3. **RX Task**: Process radio input
+4. **Other Tasks**: Sensors, telemetry, OSD, etc. (lower priority)
+
+### MSP Protocol
+
+MultiWii Serial Protocol is used for configuration and telemetry:
+- Request/response model
+- Message types defined in `msp/msp_protocol.h`
+- Handlers in `fc/fc_msp.c`
+
+## Common Patterns
+
+### Hardware Abstraction
+
+INAV abstracts hardware through resource allocation:
+
+```c
+// IO pins
+IO_t pin = IOGetByTag(IO_TAG(PA5));
+IOInit(pin, OWNER_SPI, RESOURCE_SPI_SCK, 1);
+
+// Timers
+const timerHardware_t *timer = timerGetByTag(IO_TAG(PA8), TIM_USE_ANY);
+
+// DMA
+dmaIdentifier_e dma = dmaGetIdentifier(DMA1_Stream0);
+```
+
+### Error Handling
+
+INAV uses several approaches:
+1. **Return codes**: Boolean success/failure or error enums
+2. **Diagnostics**: `sensors/diagnostics.c` for sensor health
+3. **Status indicators**: Beeper codes, LED patterns for user feedback
+4. **Logging**: CLI-based logging system
+
+### Filter Chains
+
+Sensor data typically goes through multiple filtering stages:
+
+```c
+// Low-pass filters
+gyroLpfApplyFn = lowpassFilterGetApplyFn(filterType);
+gyroLpfApplyFn(&gyroLpfState[axis], sample);
+
+// Notch filters (for dynamic filtering)
+for (int i = 0; i < dynamicNotchCount; i++) {
+ sample = biquadFilterApply(¬chFilter[i], sample);
+}
+```
+
+### Board Alignment
+
+All sensors go through board alignment transforms to correct for mounting orientation:
+
+```c
+// Apply board alignment rotation matrix
+applySensorAlignment(gyroData, gyroData, gyroAlign);
+```
+
+### SITL (Software In The Loop)
+
+INAV can be compiled for host system simulation:
+```bash
+cmake -DSITL=ON ..
+make
+```
+
+## Development Workflow
+
+### Branching Strategy
+
+- **`maintenance-X.x`**: Current version development (e.g., `maintenance-9.x`)
+- **`maintenance-Y.x`**: Next major version (e.g., `maintenance-10.x`)
+- **`master`**: Tracks current version, receives merges from maintenance branches
+
+### Pull Request Guidelines
+
+1. **Target Branch**:
+ - Bug fixes and backward-compatible features → current maintenance branch
+ - Breaking changes → next major version maintenance branch
+ - **Never** target `master` directly
+
+2. **Keep PRs Focused**: One feature/fix per PR
+
+3. **Code Quality**:
+ - Follow existing code style
+ - Add unit tests where possible
+ - Update documentation in `/docs`
+ - Test on real hardware when possible
+
+4. **Commit Messages**: Clear, descriptive messages
+
+### Important Files to Check
+
+Before making changes, review:
+- `docs/development/Development.md` - Development principles
+- `docs/development/Contributing.md` - Contribution guidelines
+- Target-specific files in `/src/main/target/`
+
+## Important Files and Directories
+
+### Configuration Files
+
+- `platform.h`: Platform-specific includes and defines
+- `target.h`: Board-specific hardware configuration
+- `config/parameter_group.h`: Parameter group system
+- `config/parameter_group_ids.h`: PG ID definitions
+- `fc/settings.yaml`: CLI settings definitions
+
+### Core Flight Control
+
+- `fc/fc_core.c`: Main flight control loop
+- `fc/fc_init.c`: System initialization
+- `fc/fc_tasks.c`: Task scheduler configuration
+- `flight/pid.c`: PID controller implementation
+- `flight/mixer.c`: Motor mixing
+
+### Key Headers
+
+- `build/build_config.h`: Build-time configuration macros
+- `common/axis.h`: Axis definitions (X, Y, Z, ROLL, PITCH, YAW)
+- `common/maths.h`: Math utilities and constants
+- `common/filter.h`: Digital filter implementations
+- `drivers/accgyro/accgyro.h`: Gyro/accelerometer interface
+
+## AI Agent Guidelines
+
+### When Adding Features
+
+1. **Understand the Module**: Read related files in the same directory
+2. **Check for Similar Code**: Search for similar features to maintain consistency
+3. **Follow Parameter Group Pattern**: New settings should use PG system
+4. **Add to Scheduler**: New periodic tasks go in `fc/fc_tasks.c`
+5. **Update Documentation**: Add/update files in `/docs`
+6. **Consider Target Support**: Use `#ifdef USE_FEATURE` for optional features
+7. **Generate CLI setting docs**: Remember to inform user to run `python src/utils/update_cli_docs.py`
+8. **Follow conding standard**: Follow MISRA C rules
+9. **Increase Paremeterer Group Version**: When changing PG structure, increase version corresponding in `PG_REGISTER`, `PG_REGISTER_WITH_RESET_FN`, `PG_REGISTER_WITH_RESET_TEMPLATE`, `PG_REGISTER_ARRAY` or `PG_REGISTER_ARRAY_WITH_RESET_FN`
+
+### When Fixing Bugs
+
+1. **Review Recent Changes**: Check git history for related modifications
+2. **Test Signal Path**: For sensor issues, trace from hardware through filters to consumer
+3. **Consider All Platforms**: STM32F4, F7, H7, and AT32 may behave differently
+4. **Check Memory Usage**: Embedded system has limited RAM/flash
+
+### When Refactoring
+
+1. **Maintain API Compatibility**: Unless targeting next major version
+2. **Preserve Unit Tests**: Update tests to match refactored code
+3. **Update Documentation**: Keep docs synchronized with code changes
+4. **Consider Performance**: Profile on target hardware, not just host compilation
+5. **Check All Callers**: Use grep/search to find all usage sites
+
+### Common Pitfalls to Avoid
+
+1. **Don't Ignore Memory Attributes**: FASTRAM placement affects real-time performance
+2. **Don't Break Parameter Groups**: Changing PG structure requires version bump
+3. **Don't Assume Hardware**: Always check feature flags (`#ifdef USE_GPS`)
+4. **Don't Break MSP**: Changes to MSP protocol affect configurator compatibility
+5. **Don't Commit Wrong Branch**: Target maintenance branch, not master
+6. **Don't Skip Documentation**: Code without docs increases support burden
+7. **Don't Hardcode Values**: Use parameter groups for configurable values
+
+### Searching the Codebase
+
+**Find definitions:**
+```bash
+grep -r "typedef.*_t" src/main/ # Find all type definitions
+grep -r "PG_REGISTER" src/main/ # Find parameter groups
+grep -r "TASK_" src/main/ # Find scheduled tasks
+```
+
+**Find usage:**
+```bash
+grep -r "functionName" src/main/
+grep -r "USE_GPS" src/main/target/ # Feature support by target
+```
+
+**Find similar code:**
+- Look in the same directory first
+- Check for similar sensor/peripheral implementations
+- Review git history: `git log --all --oneline --grep="keyword"`
+
+### Understanding Control Flow
+
+1. **Startup**: `main.c` → `fc_init.c:init()` → `fc_tasks.c:tasksInit()`
+2. **Main Loop**: `scheduler.c:scheduler()` executes tasks by priority
+3. **Critical Path**: Gyro → PID → Mixer → Motors (highest priority)
+4. **Configuration**: CLI/MSP → Parameter Groups → EEPROM
+
+### Cross-Platform Considerations
+
+Different MCU families have different characteristics:
+
+- **STM32F4**: Most common, 84-168 MHz, FPU, no cache
+- **STM32F7**: Faster, 216 MHz, FPU, I/D cache, requires cache management
+- **STM32H7**: Fastest, 480 MHz, more RAM, complex memory architecture (DTCM, SRAM)
+- **AT32F43x**: Chinese MCU, STM32F4-compatible, different peripherals
+
+Always test on target or use `#if defined()` guards for MCU-specific code.
+
+## Quick Reference
+
+### File Naming Patterns
+
+- `*_config.h`: Configuration structures (usually with PG)
+- `*_impl.h`: Implementation headers (MCU-specific)
+- `*_hal.h`: Hardware abstraction layer
+- `accgyro_*.c`: Gyro/accelerometer drivers
+- `bus_*.c`: Communication bus drivers (SPI, I2C)
+
+### Common Abbreviations
+
+- **FC**: Flight Controller
+- **PG**: Parameter Group
+- **MSP**: MultiWii Serial Protocol
+- **CLI**: Command Line Interface
+- **OSD**: On-Screen Display
+- **RTH**: Return to Home
+- **PID**: Proportional-Integral-Derivative (controller)
+- **IMU**: Inertial Measurement Unit (gyro + accel)
+- **AHRS**: Attitude and Heading Reference System
+- **ESC**: Electronic Speed Controller
+- **SITL**: Software In The Loop
+- **HITL**: Hardware In The Loop
+
+## Resources
+
+- **Main Repository**: https://github.com/iNavFlight/inav
+- **Configurator**: https://github.com/iNavFlight/inav-configurator
+- **Discord**: https://discord.gg/peg2hhbYwN
+- **Documentation**: https://github.com/iNavFlight/inav/wiki
+- **Release Notes**: https://github.com/iNavFlight/inav/releases
+
+## Version Information
+
+This document is accurate for INAV 9.0.1. As the project evolves, some details may change. Always refer to the latest documentation and code for authoritative information.
+
+---
+
+**Remember**: INAV flies aircraft that people build and fly. Code quality, safety, and reliability are paramount. When in doubt, ask the community or maintainers for guidance.
From 1e46d5b1689fd718fa880d284c5b30a8c11f85a2 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Thu, 5 Mar 2026 23:11:59 -0600
Subject: [PATCH 53/55] Use single-precision math where double is unnecessary
Replace three uses of double-precision library functions with their
float equivalents, eliminating software-emulated double math on the
Cortex-M7 FPV5-SP-D16 (single-precision-only) FPU:
- gps_ublox.c: atof() -> fastA2F() in gpsDecodeProtocolVersion().
atof() pulled in libc_nano strtod (28 KB of double-precision parsing
machinery) to parse simple version strings like "18.00". fastA2F()
is already in the codebase and covers this use case.
- maths.c: exp/pow (double) -> expf/powf in gaussian().
The explicit (double) casts defeated the -fsingle-precision-constant
flag. gaussian() is called from the IMU loop at up to 1000 Hz, so
switching to hardware-accelerated single-precision also improves
runtime performance.
- vtx_smartaudio.c: pow(10.0, ...) -> powf(10.0f, ...) in saDbiToMw().
Combined with the maths.c change, removes all callers of double pow,
dropping libm e_pow.o from the link entirely.
Flash savings on MATEKF722 (STM32F722, 512 KB):
text: -16,560 B data: -376 B total: -16,936 B (~16.5 KB)
---
src/main/common/maths.c | 2 +-
src/main/io/gps_ublox.c | 2 +-
src/main/io/vtx_smartaudio.c | 2 +-
3 files changed, 3 insertions(+), 3 deletions(-)
diff --git a/src/main/common/maths.c b/src/main/common/maths.c
index 993634d902d..2881d2b8938 100644
--- a/src/main/common/maths.c
+++ b/src/main/common/maths.c
@@ -526,7 +526,7 @@ bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu
}
float gaussian(const float x, const float mu, const float sigma) {
- return exp(-pow((double)(x - mu), 2) / (2 * pow((double)sigma, 2)));
+ return expf(-powf(x - mu, 2.0f) / (2.0f * powf(sigma, 2.0f)));
}
float bellCurve(const float x, const float curveWidth)
diff --git a/src/main/io/gps_ublox.c b/src/main/io/gps_ublox.c
index 82e1a4f655d..102284723df 100755
--- a/src/main/io/gps_ublox.c
+++ b/src/main/io/gps_ublox.c
@@ -549,7 +549,7 @@ static void gpsDecodeProtocolVersion(const char *proto, size_t bufferLength)
if (bufferLength > 13 && (!strncmp(proto, "PROTVER=", 8) || !strncmp(proto, "PROTVER ", 8))) {
proto+=8;
- float ver = atof(proto);
+ float ver = fastA2F(proto);
gpsState.swVersionMajor = (uint8_t)ver;
gpsState.swVersionMinor = (uint8_t)((ver - gpsState.swVersionMajor) * 100.0f);
diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c
index 7d5e213cce0..7e24d552929 100644
--- a/src/main/io/vtx_smartaudio.c
+++ b/src/main/io/vtx_smartaudio.c
@@ -212,7 +212,7 @@ int saDacToPowerIndex(int dac)
int saDbiToMw(uint16_t dbi) {
- uint16_t mw = (uint16_t)pow(10.0, dbi / 10.0);
+ uint16_t mw = (uint16_t)powf(10.0f, (float)dbi / 10.0f);
if (dbi > 14) {
// For powers greater than 25mW round up to a multiple of 50 to match expectations
From 2c7003f2c484040c935a18eca44872cff9a80703 Mon Sep 17 00:00:00 2001
From: Ray Morris
Date: Thu, 5 Mar 2026 23:25:04 -0600
Subject: [PATCH 54/55] Code review fixes for float math flash savings
Follow-up to the single-precision math change that saves ~17 KB of
flash on STM32F722 targets:
- maths.c: Replace powf(x, 2.0f) with explicit multiplies in
gaussian(). Clearer intent and avoids any dependency on libm
reducing integer-exponent powf to a multiply.
- vtx_smartaudio.c: Add roundf() before uint16_t cast in saDbiToMw().
powf(10.0f, 1.0f) may return 9.999...f on some libm implementations,
which would truncate to 9 mW instead of the correct 10 mW. roundf()
closes the hazard at the cost of one FPU instruction.
---
src/main/common/maths.c | 2 +-
src/main/io/vtx_smartaudio.c | 2 +-
2 files changed, 2 insertions(+), 2 deletions(-)
diff --git a/src/main/common/maths.c b/src/main/common/maths.c
index 2881d2b8938..d591e40de81 100644
--- a/src/main/common/maths.c
+++ b/src/main/common/maths.c
@@ -526,7 +526,7 @@ bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu
}
float gaussian(const float x, const float mu, const float sigma) {
- return expf(-powf(x - mu, 2.0f) / (2.0f * powf(sigma, 2.0f)));
+ return expf(-((x - mu) * (x - mu)) / (2.0f * sigma * sigma));
}
float bellCurve(const float x, const float curveWidth)
diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c
index 7e24d552929..acb2a34e6dc 100644
--- a/src/main/io/vtx_smartaudio.c
+++ b/src/main/io/vtx_smartaudio.c
@@ -212,7 +212,7 @@ int saDacToPowerIndex(int dac)
int saDbiToMw(uint16_t dbi) {
- uint16_t mw = (uint16_t)powf(10.0f, (float)dbi / 10.0f);
+ uint16_t mw = (uint16_t)roundf(powf(10.0f, (float)dbi / 10.0f));
if (dbi > 14) {
// For powers greater than 25mW round up to a multiple of 50 to match expectations
From a85fa5fc217b8005b4123fa63c9ad3d796855e5e Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?Pawe=C5=82=20Spychalski?=
Date: Fri, 6 Mar 2026 09:45:48 +0100
Subject: [PATCH 55/55] Target cleanup
---
src/main/target/BRAHMA_H7/config.c | 1 -
src/main/target/BRAHMA_H7/target.h | 1 -
2 files changed, 2 deletions(-)
diff --git a/src/main/target/BRAHMA_H7/config.c b/src/main/target/BRAHMA_H7/config.c
index 1065971614a..0f1fec5a816 100644
--- a/src/main/target/BRAHMA_H7/config.c
+++ b/src/main/target/BRAHMA_H7/config.c
@@ -28,5 +28,4 @@ void targetConfiguration(void)
{
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2;
- beeperConfigMutable()->pwmMode = true;
}
diff --git a/src/main/target/BRAHMA_H7/target.h b/src/main/target/BRAHMA_H7/target.h
index 175d01a1376..002626036e1 100644
--- a/src/main/target/BRAHMA_H7/target.h
+++ b/src/main/target/BRAHMA_H7/target.h
@@ -34,7 +34,6 @@
#define BEEPER PA15
#define BEEPER_INVERTED
-// #define BEEPER_PWM_FREQUENCY 2000
// *************** IMU generic ***********************
#define USE_DUAL_GYRO