Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
31 commits
Select commit Hold shift + click to select a range
a9dae25
msp: add minimum power index to MSP_VTX_CONFIG
sensei-hacker Dec 19, 2025
cebc906
Refactor OMNIBUSF4 targets into separate directories
sensei-hacker Dec 22, 2025
476a0cb
Clean up dead code and obsolete comments from OMNIBUS split
sensei-hacker Dec 22, 2025
c79e53a
Remove all dead code from OMNIBUSF4 directory
sensei-hacker Dec 22, 2025
e3d0bda
Fix critical OMNIBUSF4V3_ICM configuration bug and remove dead code
sensei-hacker Dec 22, 2025
dce7687
Remove outdated and misleading comments from OMNIBUS split
sensei-hacker Dec 22, 2025
2331e01
Remove dead code from OMNIBUSF4PRO/target.c
sensei-hacker Dec 22, 2025
0fead0f
Remove outdated comments and redundant conditional from OMNIBUS split
sensei-hacker Dec 22, 2025
e6dc927
Fix inconsistent indentation remnants in OMNIBUS split
sensei-hacker Dec 22, 2025
cba6d29
Reduce CPU overhead by rate-limiting updateArmingStatus() to 200 Hz
sensei-hacker Dec 23, 2025
798a612
Fix AGL velocity estimation using squared acceleration weight factor
sensei-hacker Jan 17, 2026
5cf56e8
Fix comment/code mismatch in position estimator weight factors
sensei-hacker Jan 21, 2026
43fe3ab
Remove CLAUDE.md and brother/ from .gitignore
sensei-hacker Feb 8, 2026
f2f6e0e
improve pos est sensor corrections
breadoven Feb 8, 2026
13e56b7
fixes and improvements
breadoven Feb 9, 2026
034c119
Merge branch 'maintenance-9.x' into abo_pos_est_sensor_corr_refactor
breadoven Feb 10, 2026
1c39cd8
Update navigation_pos_estimator.c
breadoven Feb 10, 2026
ffd4b9e
Update navigation_pos_estimator.c
breadoven Feb 10, 2026
7cdf954
fixes
breadoven Feb 11, 2026
1a854b6
Bump firmware version to 9.0.1
sensei-hacker Feb 12, 2026
c8df08c
Merge pull request #11329 from sensei-hacker/release/bump-version-9.0.1
sensei-hacker Feb 13, 2026
d44f2cf
Merge pull request #11255 from sensei-hacker/fix/agl-velocity-weight-…
sensei-hacker Feb 13, 2026
c50b5ef
Fix GPS capability poll blocking for 500ms every 5 seconds
sensei-hacker Feb 13, 2026
dff5011
Remove unnecessary ptWaitTimeout blocking from capability polls
sensei-hacker Feb 13, 2026
682e55a
Fix NEXUSX default IMU orientation
sensei-hacker Feb 15, 2026
32970d4
Merge pull request #11200 from sensei-hacker/rate-limit-updateArmingS…
sensei-hacker Feb 18, 2026
3326796
Merge pull request #11332 from sensei-hacker/fix/gps-capa-poll-stall
sensei-hacker Feb 18, 2026
77c677d
Merge pull request #11322 from breadoven/abo_pos_est_sensor_corr_refa…
sensei-hacker Feb 18, 2026
c428cc9
Merge pull request #11190 from sensei-hacker/feature-vtx-power-min
sensei-hacker Feb 21, 2026
1bf1814
Merge pull request #11338 from sensei-hacker/fix/issue-11325-nexusx-i…
sensei-hacker Feb 25, 2026
eca5746
Merge upstream/maintenance-9.x - resolve OMNIBUSF4V3_ICM conflicts
sensei-hacker Feb 25, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -46,3 +46,7 @@ launch.json
# Assitnow token and files for test script
tokens.yaml
*.ubx

# Local development files
.semgrepignore
build_sitl/
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ else()
endif()


project(INAV VERSION 9.0.0)
project(INAV VERSION 9.0.1)


enable_language(ASM)
Expand Down
7 changes: 6 additions & 1 deletion src/main/fc/fc_core.c
Original file line number Diff line number Diff line change
Expand Up @@ -946,7 +946,12 @@ void taskMainPidLoop(timeUs_t currentTimeUs)

processPilotAndFailSafeActions(dT);

updateArmingStatus();
// Check battery, GPS signal, arming status etc @ 200 Hz
static uint8_t armingStatusDivider = 0;
if (++armingStatusDivider >= 10) {
armingStatusDivider = 0;
updateArmingStatus();
}

if (rxConfig()->rcFilterFrequency) {
rcInterpolationApply(isRXDataNew, currentTimeUs);
Expand Down
6 changes: 6 additions & 0 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -1550,6 +1550,12 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU8(dst, vtxDevice->capability.bandCount);
sbufWriteU8(dst, vtxDevice->capability.channelCount);
sbufWriteU8(dst, vtxDevice->capability.powerCount);

uint8_t minPowerIndex = 1;
if (deviceType == VTXDEV_MSP) {
minPowerIndex = 0;
}
sbufWriteU8(dst, minPowerIndex);
}
else {
sbufWriteU8(dst, VTXDEV_UNKNOWN); // no VTX configured
Expand Down
2 changes: 0 additions & 2 deletions src/main/io/gps_ublox.c
Original file line number Diff line number Diff line change
Expand Up @@ -1231,11 +1231,9 @@ STATIC_PROTOTHREAD(gpsProtocolStateThread)
if (gpsState.hwVersion == UBX_HW_VERSION_UNKNOWN)
{
pollVersion();
ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS);
}

pollGnssCapabilities();
ptWaitTimeout((_ack_state == UBX_ACK_GOT_ACK || _ack_state == UBX_ACK_GOT_NAK), GPS_CFG_CMD_TIMEOUT_MS);
}
}
}
Expand Down
209 changes: 122 additions & 87 deletions src/main/navigation/navigation_pos_estimator.c

Large diffs are not rendered by default.

2 changes: 1 addition & 1 deletion src/main/navigation/navigation_pos_estimator_agl.c
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ void estimationCalculateAGL(estimationContext_t * ctx)
// Update estimate
posEstimator.est.aglAlt += posEstimator.est.aglVel * ctx->dt;
posEstimator.est.aglAlt += posEstimator.imu.accelNEU.z * sq(ctx->dt) / 2.0f * posEstimator.imu.accWeightFactor;
posEstimator.est.aglVel += posEstimator.imu.accelNEU.z * ctx->dt * sq(posEstimator.imu.accWeightFactor);
posEstimator.est.aglVel += posEstimator.imu.accelNEU.z * ctx->dt * posEstimator.imu.accWeightFactor;

// Apply correction
if (posEstimator.est.aglQual == SURFACE_QUAL_HIGH) {
Expand Down
25 changes: 17 additions & 8 deletions src/main/navigation/navigation_pos_estimator_flow.c
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,13 @@ bool estimationCalculateCorrection_XY_FLOW(estimationContext_t * ctx)
return false;
}

if (!opflow.updateDt) {
return true;
}
posEstimator.flow.updateDt = opflow.updateDt;
opflow.updateDt = 0.0f;
const float dt = posEstimator.flow.updateDt;

// Calculate linear velocity based on angular velocity and altitude
// Technically we should calculate arc length here, but for fast sampling this is accurate enough
fpVector3_t flowVel = {
Expand All @@ -88,8 +95,9 @@ bool estimationCalculateCorrection_XY_FLOW(estimationContext_t * ctx)
const float flowVelXInnov = flowVel.x - posEstimator.est.vel.x;
const float flowVelYInnov = flowVel.y - posEstimator.est.vel.y;

ctx->estVelCorr.x = flowVelXInnov * positionEstimationConfig()->w_xy_flow_v * ctx->dt;
ctx->estVelCorr.y = flowVelYInnov * positionEstimationConfig()->w_xy_flow_v * ctx->dt;
const float w_xy_flow_v = positionEstimationConfig()->w_xy_flow_v;
ctx->estVelCorr.x = flowVelXInnov * w_xy_flow_v * dt;
ctx->estVelCorr.y = flowVelYInnov * w_xy_flow_v * dt;

// Calculate position correction if possible/allowed
if ((ctx->newFlags & EST_GPS_XY_VALID)) {
Expand All @@ -98,24 +106,25 @@ bool estimationCalculateCorrection_XY_FLOW(estimationContext_t * ctx)
posEstimator.est.flowCoordinates[Y] = posEstimator.gps.pos.y;
}
else if (positionEstimationConfig()->allow_dead_reckoning) {
posEstimator.est.flowCoordinates[X] += flowVel.x * ctx->dt;
posEstimator.est.flowCoordinates[Y] += flowVel.y * ctx->dt;
posEstimator.est.flowCoordinates[X] += flowVel.x * dt;
posEstimator.est.flowCoordinates[Y] += flowVel.y * dt;

const float flowResidualX = posEstimator.est.flowCoordinates[X] - posEstimator.est.pos.x;
const float flowResidualY = posEstimator.est.flowCoordinates[Y] - posEstimator.est.pos.y;

ctx->estPosCorr.x = flowResidualX * positionEstimationConfig()->w_xy_flow_p * ctx->dt;
ctx->estPosCorr.y = flowResidualY * positionEstimationConfig()->w_xy_flow_p * ctx->dt;
const float w_xy_flow_p = positionEstimationConfig()->w_xy_flow_p;
ctx->estPosCorr.x = flowResidualX * w_xy_flow_p * dt;
ctx->estPosCorr.y = flowResidualY * w_xy_flow_p * dt;

ctx->newEPH = updateEPE(posEstimator.est.eph, ctx->dt, calc_length_pythagorean_2D(flowResidualX, flowResidualY), positionEstimationConfig()->w_xy_flow_p);
ctx->newEPH = updateEPE(posEstimator.est.eph, dt, calc_length_pythagorean_2D(flowResidualX, flowResidualY), w_xy_flow_p);
}

DEBUG_SET(DEBUG_FLOW, 0, RADIANS_TO_DEGREES(posEstimator.flow.flowRate[X]));
DEBUG_SET(DEBUG_FLOW, 1, RADIANS_TO_DEGREES(posEstimator.flow.flowRate[Y]));
DEBUG_SET(DEBUG_FLOW, 2, posEstimator.est.flowCoordinates[X]);
DEBUG_SET(DEBUG_FLOW, 3, posEstimator.est.flowCoordinates[Y]);

return true;
return ctx->applyCorrections = true;
#else
UNUSED(ctx);
return false;
Expand Down
4 changes: 4 additions & 0 deletions src/main/navigation/navigation_pos_estimator_private.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ typedef struct {
fpVector3_t vel; // GPS velocity (cms)
float eph;
float epv;
float updateDt;
} navPositionEstimatorGPS_t;

typedef struct {
Expand All @@ -79,6 +80,7 @@ typedef struct {
float alt; // Raw barometric altitude (cm)
float epv;
float baroAltRate; // Baro altitude rate of change (cm/s)
float updateDt;
} navPositionEstimatorBARO_t;

typedef struct {
Expand All @@ -105,6 +107,7 @@ typedef struct {
float quality;
float flowRate[2];
float bodyRate[2];
float updateDt;
} navPositionEstimatorFLOW_t;

typedef struct {
Expand Down Expand Up @@ -180,6 +183,7 @@ typedef struct {
fpVector3_t estPosCorr;
fpVector3_t estVelCorr;
fpVector3_t accBiasCorr;
bool applyCorrections;
} estimationContext_t;

extern navigationPosEstimator_t posEstimator;
Expand Down
1 change: 1 addition & 0 deletions src/main/sensors/opflow.c
Original file line number Diff line number Diff line change
Expand Up @@ -171,6 +171,7 @@ void opflowUpdate(timeUs_t currentTimeUs)
if (opflow.dev.updateFn(&opflow.dev)) {
// Indicate valid update
opflow.isHwHealty = true;
opflow.updateDt = US2S(currentTimeUs - opflow.lastValidUpdate);
opflow.lastValidUpdate = currentTimeUs;
opflow.rawQuality = opflow.dev.rawData.quality;

Expand Down
1 change: 1 addition & 0 deletions src/main/sensors/opflow.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ typedef struct opflow_s {

opflowQuality_e flowQuality;
timeUs_t lastValidUpdate;
float updateDt;
bool isHwHealty;
float flowRate[2]; // optical flow angular rate in rad/sec measured about the X and Y body axis
float bodyRate[2]; // body inertial angular rate in rad/sec measured about the X and Y body axis
Expand Down
2 changes: 2 additions & 0 deletions src/main/target/DYSF4/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
target_stm32f405xg(DYSF4PRO)
target_stm32f405xg(DYSF4PROV2)
47 changes: 47 additions & 0 deletions src/main/target/DYSF4/target.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
/*
* 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 <http://www.gnu.org/licenses/>.
*/

#include <stdint.h>

#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
#include "drivers/bus.h"

timerHardware_t timerHardware[] = {

DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S1_OUT D1_ST7
DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S2_OUT D1_ST2
DEF_TIM(TIM2, CH4, PA3, TIM_USE_OUTPUT_AUTO, 0, 1), // S3_OUT D1_ST6
DEF_TIM(TIM2, CH3, PA2, TIM_USE_OUTPUT_AUTO, 0, 0), // S4_OUT D1_ST1

// { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_OUTPUT_AUTO }, // MOTOR_3
DEF_TIM(TIM5, CH2, PA1, TIM_USE_OUTPUT_AUTO, 0, 0), // S5_OUT MOTOR, SERVO or LED
DEF_TIM(TIM1, CH1, PA8, TIM_USE_OUTPUT_AUTO, 0, 0), // S6_OUT


// DEF_TIM(TIM12, CH1, PB14, TIM_USE_PPM, 0, 0), // PPM
DEF_TIM(TIM12, CH2, PB15, TIM_USE_ANY, 0, 0), // S2_IN
DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), // S3_IN, UART6_TX
DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // S4_IN, UART6_RX
DEF_TIM(TIM8, CH3, PC8, TIM_USE_ANY, 0, 0), // S5_IN
DEF_TIM(TIM8, CH4, PC9, TIM_USE_ANY, 0, 0), // S6_IN

};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
159 changes: 159 additions & 0 deletions src/main/target/DYSF4/target.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,159 @@
/*
* 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 <http://www.gnu.org/licenses/>.
*/

#pragma once

// This directory contains: DYSF4PRO, DYSF4PROV2

#if defined(DYSF4PRO)
#define TARGET_BOARD_IDENTIFIER "DYS4"
#elif defined(DYSF4PROV2)
#define TARGET_BOARD_IDENTIFIER "DY42"
#endif

#define USBD_PRODUCT_STRING "DysF4Pro"

#define LED0 PB5

#define BEEPER PB4
#define BEEPER_INVERTED

#if defined(DYSF4PROV2)
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define I2C_EXT_BUS BUS_I2C1
#else
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C_DEVICE_2_SHARES_UART3
#define I2C_EXT_BUS BUS_I2C2
#endif

#define UG2864_I2C_BUS I2C_EXT_BUS

#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1

#define USE_IMU_MPU6000
#define IMU_MPU6000_ALIGN CW180_DEG

#define USE_MAG
#define MAG_I2C_BUS I2C_EXT_BUS
#define USE_MAG_ALL

#define TEMPERATURE_I2C_BUS I2C_EXT_BUS

#define USE_BARO
#define BARO_I2C_BUS I2C_EXT_BUS
#define USE_BARO_BMP085
#define USE_BARO_BMP280
#define USE_BARO_MS5611

#define PITOT_I2C_BUS I2C_EXT_BUS

#define USE_RANGEFINDER
#define RANGEFINDER_I2C_BUS I2C_EXT_BUS

#define USE_VCP
#define VBUS_SENSING_PIN PC5
#define VBUS_SENSING_ENABLED


#define USE_UART1
#define UART1_RX_PIN PA10
#define UART1_TX_PIN PA9
#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2

#define USE_UART3
#define UART3_RX_PIN PB11
#define UART3_TX_PIN PB10

#define USE_UART6
#define UART6_RX_PIN PC7
#define UART6_TX_PIN PC6

#define USE_SOFTSERIAL1
#define SOFTSERIAL_1_RX_PIN PC8
#define SOFTSERIAL_1_TX_PIN PC9

#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1

#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART1

#define USE_SPI

#define USE_SPI_DEVICE_1


#define USE_SPI_DEVICE_3
#define SPI3_NSS_PIN PB3
#define SPI3_SCK_PIN PC10
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12

#define USE_MAX7456
#define MAX7456_SPI_BUS BUS_SPI3
#define MAX7456_CS_PIN PA15

#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define M25P16_CS_PIN SPI3_NSS_PIN
#define M25P16_SPI_BUS BUS_SPI3
#define USE_FLASHFS
#define USE_FLASH_M25P16

#define USE_ADC
#define ADC_CHANNEL_1_PIN PC1
#define ADC_CHANNEL_2_PIN PC2

#ifdef DYSF4PRO
#define ADC_CHANNEL_3_PIN PC3
#else
#define ADC_CHANNEL_3_PIN PA0
#endif

#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1
#define VBAT_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3

#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)

#define USE_LED_STRIP
#define WS2811_PIN PA1

#define DISABLE_RX_PWM_FEATURE
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_VBAT | FEATURE_OSD)

#define USE_SPEKTRUM_BIND
#define BIND_PIN PB11 // USART3 RX

#define USE_SERIAL_4WAY_BLHELI_INTERFACE

// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS 6
#define TARGET_MOTOR_COUNT 6
#define USE_DSHOT
#define USE_ESC_SENSOR

#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff

2 changes: 1 addition & 1 deletion src/main/target/NEXUSX/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#define SPI1_MOSI_PIN PA7

#define USE_IMU_ICM42605 // is actually ICM42688P
#define IMU_ICM42605_ALIGN CW180_DEG
#define IMU_ICM42605_ALIGN CW0_DEG
#define ICM42605_CS_PIN PA4
#define ICM42605_EXTI_PIN PB8
#define ICM42605_SPI_BUS BUS_SPI1
Expand Down
Loading
Loading