From f4786d1569aa524bbefa7973f1f4edb19c174ca2 Mon Sep 17 00:00:00 2001 From: "Git bot (blckmn)" Date: Wed, 4 Jun 2025 06:25:03 +0000 Subject: [PATCH 1/4] Auto updated submodule references [04-06-2025] --- src/config | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/config b/src/config index eda6b30999..7970f07307 160000 --- a/src/config +++ b/src/config @@ -1 +1 @@ -Subproject commit eda6b309994923772eeab82fce3d6d8c3c0812a2 +Subproject commit 7970f0730766941d2202cf0174943bef7f85d3ce From 8853356e716505e27525f39f29fdaa6c28b37f46 Mon Sep 17 00:00:00 2001 From: mjs1441 Date: Wed, 4 Jun 2025 15:39:45 +0100 Subject: [PATCH 2/4] Allow for builds with certain features disabled. (#14420) * Allow for builds with certain features disabled. Fix build for when the following are disabled: USE_DMA USE_DSHOT_TELEMETRY USE_SERIAL_PASSTHROUGH * Tweak #ifdef / UNUSED as per code review. --- src/main/drivers/accgyro/accgyro_spi_bmi160.c | 2 ++ src/main/drivers/accgyro/accgyro_spi_bmi270.c | 2 ++ src/main/drivers/dshot.h | 7 ++----- src/main/drivers/dshot_command.c | 2 ++ src/main/msp/msp.c | 6 ++++++ 5 files changed, 14 insertions(+), 5 deletions(-) diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi160.c b/src/main/drivers/accgyro/accgyro_spi_bmi160.c index 31260a0f96..fbf4aacb81 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi160.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi160.c @@ -267,6 +267,7 @@ extiCallbackRec_t bmi160IntCallbackRec; // Called in ISR context // Gyro read has just completed +#ifdef USE_DMA static busStatus_e bmi160Intcallback(uint32_t arg) { gyroDev_t *gyro = (gyroDev_t *)arg; @@ -280,6 +281,7 @@ static busStatus_e bmi160Intcallback(uint32_t arg) return BUS_READY; } +#endif static void bmi160ExtiHandler(extiCallbackRec_t *cb) { diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi270.c b/src/main/drivers/accgyro/accgyro_spi_bmi270.c index f13f39c75f..a64cfa64b4 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi270.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi270.c @@ -278,6 +278,7 @@ extiCallbackRec_t bmi270IntCallbackRec; */ // Called in ISR context // Gyro read has just completed +#ifdef USE_DMA static busStatus_e bmi270Intcallback(uint32_t arg) { gyroDev_t *gyro = (gyroDev_t *)arg; @@ -291,6 +292,7 @@ static busStatus_e bmi270Intcallback(uint32_t arg) return BUS_READY; } +#endif static void bmi270ExtiHandler(extiCallbackRec_t *cb) { diff --git a/src/main/drivers/dshot.h b/src/main/drivers/dshot.h index 19105b0659..609fc22892 100644 --- a/src/main/drivers/dshot.h +++ b/src/main/drivers/dshot.h @@ -95,6 +95,8 @@ uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb); extern bool useDshotTelemetry; extern uint8_t dshotMotorCount; +bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig); + #ifdef USE_DSHOT_TELEMETRY typedef struct dshotTelemetryMotorState_s { @@ -113,7 +115,6 @@ typedef struct dshotTelemetryState_s { dshotRawValueState_t rawValueState; } dshotTelemetryState_t; -#ifdef USE_DSHOT_TELEMETRY extern uint32_t readDoneCount; FAST_DATA_ZERO_INIT extern uint32_t inputStampUs; @@ -125,10 +126,6 @@ typedef struct dshotTelemetryCycleCounters_s { FAST_DATA_ZERO_INIT extern dshotTelemetryCycleCounters_t dshotDMAHandlerCycleCounters; -#endif - -bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig); - extern dshotTelemetryState_t dshotTelemetryState; #ifdef USE_DSHOT_TELEMETRY_STATS diff --git a/src/main/drivers/dshot_command.c b/src/main/drivers/dshot_command.c index a2fa5da17c..fc95dbc3aa 100644 --- a/src/main/drivers/dshot_command.c +++ b/src/main/drivers/dshot_command.c @@ -216,9 +216,11 @@ void dshotCommandWrite(uint8_t index, uint8_t motorCount, uint8_t command, dshot } if (commandType == DSHOT_CMD_TYPE_BLOCKING) { +#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY) bool isBitbangActive = false; #ifdef USE_DSHOT_BITBANG isBitbangActive = isDshotBitbangActive(&motorConfig()->dev); +#endif #endif // Fake command in queue. Blocking commands are launched from cli, and no inline commands are running for (uint8_t i = 0; i < motorDeviceCount(); i++) { diff --git a/src/main/msp/msp.c b/src/main/msp/msp.c index de6d7d2492..9d4434cbe7 100644 --- a/src/main/msp/msp.c +++ b/src/main/msp/msp.c @@ -255,6 +255,7 @@ static void mspEscPassthroughFn(serialPort_t *serialPort) } #endif +#ifdef USE_SERIAL_PASSTHROUGH static serialPort_t *mspFindPassthroughSerialPort(void) { serialPortUsage_t *portUsage = NULL; @@ -284,6 +285,7 @@ static void mspSerialPassthroughFn(serialPort_t *serialPort) serialPassthrough(passthroughPort, serialPort, NULL, NULL); } } +#endif static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn) { @@ -297,6 +299,7 @@ static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessF } switch (mspPassthroughMode) { +#ifdef USE_SERIAL_PASSTHROUGH case MSP_PASSTHROUGH_SERIAL_ID: case MSP_PASSTHROUGH_SERIAL_FUNCTION_ID: if (mspFindPassthroughSerialPort()) { @@ -308,6 +311,9 @@ static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessF sbufWriteU8(dst, 0); } break; +#else + UNUSED(mspPostProcessFn); +#endif #ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE case MSP_PASSTHROUGH_ESC_4WAY: // get channel number From 31887f84b158d21488aa705d591ad250c1ca41ec Mon Sep 17 00:00:00 2001 From: Jay Blackman Date: Thu, 5 Jun 2025 10:28:31 +1000 Subject: [PATCH 3/4] PICO: Preparing for I2C device using I2C0 (#14422) --- src/main/drivers/bus_i2c.h | 16 +++++++--------- src/main/drivers/bus_i2c_impl.h | 14 ++++++++------ src/main/platform.h | 2 +- .../platform/platform.h} | 3 +++ .../platform/platform.h} | 11 +++++++---- .../platform/platform.h} | 2 ++ .../platform/platform.h} | 18 ++++++++++++++++++ src/test/unit/platform.h | 2 ++ 8 files changed, 48 insertions(+), 20 deletions(-) rename src/platform/APM32/{platform_mcu.h => include/platform/platform.h} (98%) rename src/platform/AT32/{platform_mcu.h => include/platform/platform.h} (96%) rename src/platform/SIMULATOR/{platform_mcu.h => include/platform/platform.h} (97%) rename src/platform/STM32/{platform_mcu.h => include/platform/platform.h} (97%) diff --git a/src/main/drivers/bus_i2c.h b/src/main/drivers/bus_i2c.h index 74dcfadb3d..91751dda24 100644 --- a/src/main/drivers/bus_i2c.h +++ b/src/main/drivers/bus_i2c.h @@ -31,20 +31,18 @@ typedef enum I2CDevice { I2CINVALID = -1, - I2CDEV_1 = 0, + I2CDEV_FIRST = 0, +#if defined(USE_I2C_DEVICE_0) + I2CDEV_0 = I2CDEV_FIRST, + I2CDEV_1, +#else + I2CDEV_1 = I2CDEV_FIRST, +#endif I2CDEV_2, I2CDEV_3, I2CDEV_4, } I2CDevice; -#if defined(STM32F4) || defined(APM32F4) -#define I2CDEV_COUNT 3 -#elif defined(STM32F7) -#define I2CDEV_COUNT 4 -#else -#define I2CDEV_COUNT 4 -#endif - // Macros to convert between CLI bus number and I2CDevice. #define I2C_CFG_TO_DEV(x) ((x) - 1) #define I2C_DEV_TO_CFG(x) ((x) + 1) diff --git a/src/main/drivers/bus_i2c_impl.h b/src/main/drivers/bus_i2c_impl.h index 0dd1fb2c99..34f932e248 100644 --- a/src/main/drivers/bus_i2c_impl.h +++ b/src/main/drivers/bus_i2c_impl.h @@ -32,12 +32,12 @@ typedef struct i2cPinDef_s { ioTag_t ioTag; -#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if I2C_TRAIT_AF_PIN uint8_t af; #endif } i2cPinDef_t; -#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if I2C_TRAIT_AF_PIN #define I2CPINDEF(pin, af) { DEFIO_TAG_E(pin), af } #else #define I2CPINDEF(pin) { DEFIO_TAG_E(pin) } @@ -48,14 +48,16 @@ typedef struct i2cHardware_s { I2C_TypeDef *reg; i2cPinDef_t sclPins[I2C_PIN_SEL_MAX]; i2cPinDef_t sdaPins[I2C_PIN_SEL_MAX]; +#if PLATFORM_TRAIT_RCC rccPeriphTag_t rcc; +#endif uint8_t ev_irq; uint8_t er_irq; } i2cHardware_t; extern const i2cHardware_t i2cHardware[]; -#if defined(STM32F4) +#if I2C_TRAIT_STATE typedef struct i2cState_s { volatile bool error; volatile bool busy; @@ -74,7 +76,7 @@ typedef struct i2cDevice_s { I2C_TypeDef *reg; IO_t scl; IO_t sda; -#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if I2C_TRAIT_AF_PIN uint8_t sclAF; uint8_t sdaAF; #endif @@ -82,10 +84,10 @@ typedef struct i2cDevice_s { uint16_t clockSpeed; // MCU/Driver dependent member follows -#if defined(STM32F4) +#if I2C_TRAIT_STATE i2cState_t state; #endif -#if defined(USE_HAL_DRIVER) || defined(AT32F4) +#if I2C_TRAIT_HANDLE I2C_HandleTypeDef handle; #endif } i2cDevice_t; diff --git a/src/main/platform.h b/src/main/platform.h index 4f0a0f9ed1..e7c3583fdc 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -33,7 +33,7 @@ #include "target/common_pre.h" // MCU specific platform from platform/X -#include "platform_mcu.h" +#include "platform/platform.h" #include "target.h" #include "target/common_post.h" diff --git a/src/platform/APM32/platform_mcu.h b/src/platform/APM32/include/platform/platform.h similarity index 98% rename from src/platform/APM32/platform_mcu.h rename to src/platform/APM32/include/platform/platform.h index 10299b6d5c..a2798016e9 100644 --- a/src/platform/APM32/platform_mcu.h +++ b/src/platform/APM32/include/platform/platform.h @@ -193,6 +193,9 @@ #define PLATFORM_TRAIT_RCC 1 #define UART_TRAIT_AF_PORT 1 #define SERIAL_TRAIT_PIN_CONFIG 1 +#define I2C_TRAIT_AF_PIN 1 +#define I2CDEV_COUNT 3 +#define I2C_TRAIT_HANDLE 1 #define UARTHARDWARE_MAX_PINS 4 diff --git a/src/platform/AT32/platform_mcu.h b/src/platform/AT32/include/platform/platform.h similarity index 96% rename from src/platform/AT32/platform_mcu.h rename to src/platform/AT32/include/platform/platform.h index 2c55895061..9da68a042c 100644 --- a/src/platform/AT32/platform_mcu.h +++ b/src/platform/AT32/include/platform/platform.h @@ -144,12 +144,15 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; #define UART_TX_BUFFER_ATTRIBUTE // NONE #define UART_RX_BUFFER_ATTRIBUTE // NONE -#define PLATFORM_TRAIT_RCC 1 -#define UART_TRAIT_AF_PIN 1 -#define UART_TRAIT_PINSWAP 1 +#define PLATFORM_TRAIT_RCC 1 +#define UART_TRAIT_AF_PIN 1 +#define UART_TRAIT_PINSWAP 1 #define SERIAL_TRAIT_PIN_CONFIG 1 +#define I2C_TRAIT_AF_PIN 1 +#define I2CDEV_COUNT 4 +#define I2C_TRAIT_HANDLE 1 -#define UARTHARDWARE_MAX_PINS 5 +#define UARTHARDWARE_MAX_PINS 5 #define UART_REG_RXD(base) ((base)->dt) #define UART_REG_TXD(base) ((base)->dt) diff --git a/src/platform/SIMULATOR/platform_mcu.h b/src/platform/SIMULATOR/include/platform/platform.h similarity index 97% rename from src/platform/SIMULATOR/platform_mcu.h rename to src/platform/SIMULATOR/include/platform/platform.h index be11284f04..7fdf22c0f5 100644 --- a/src/platform/SIMULATOR/platform_mcu.h +++ b/src/platform/SIMULATOR/include/platform/platform.h @@ -33,3 +33,5 @@ // no serial pins are defined for the simulator #define SERIAL_TRAIT_PIN_CONFIG 0 + +#define I2CDEV_COUNT 0 diff --git a/src/platform/STM32/platform_mcu.h b/src/platform/STM32/include/platform/platform.h similarity index 97% rename from src/platform/STM32/platform_mcu.h rename to src/platform/STM32/include/platform/platform.h index f8c2e75d80..52f5ef8e56 100644 --- a/src/platform/STM32/platform_mcu.h +++ b/src/platform/STM32/include/platform/platform.h @@ -419,3 +419,21 @@ extern uint8_t _dmaram_end__; #define SERIAL_TRAIT_PIN_CONFIG 1 #define USB_DP_PIN PA12 + +#if defined(STM32F4) +#define I2C_TRAIT_STATE 1 +#endif + +#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) +#define I2C_TRAIT_AF_PIN 1 +#endif + +#if defined(USE_HAL_DRIVER) +#define I2C_TRAIT_HANDLE 1 +#endif + +#if defined(STM32F4) +#define I2CDEV_COUNT 3 +#else +#define I2CDEV_COUNT 4 +#endif diff --git a/src/test/unit/platform.h b/src/test/unit/platform.h index dd03dce802..8f59e69f76 100644 --- a/src/test/unit/platform.h +++ b/src/test/unit/platform.h @@ -124,6 +124,8 @@ typedef struct } ADC_TypeDef; #define SPIDEV_COUNT 0 +#define I2CDEV_COUNT 0 + #define WS2811_DMA_TC_FLAG (void *)1 #define WS2811_DMA_HANDLER_IDENTIFER 0 #define NVIC_PriorityGroup_2 0x500 From 0f294102428577646e90add5223d60c805eb6c7d Mon Sep 17 00:00:00 2001 From: "Git bot (blckmn)" Date: Thu, 5 Jun 2025 06:25:03 +0000 Subject: [PATCH 4/4] Auto updated submodule references [05-06-2025] --- src/config | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/config b/src/config index 7970f07307..737c3460fa 160000 --- a/src/config +++ b/src/config @@ -1 +1 @@ -Subproject commit 7970f0730766941d2202cf0174943bef7f85d3ce +Subproject commit 737c3460fa621696af079367c86ca2be28194631