Skip to content

Conversation

@MakeSomeFakeNews
Copy link

@MakeSomeFakeNews MakeSomeFakeNews commented Jan 26, 2026

User description

Summary

Adds support for the CoreWing F405 Wing V2 flight controller board.

Hardware Specifications

Component Specification
MCU STM32F405RGT6
Gyro ICM42688P (ICM42605 driver) on SPI1 (CW270 alignment)
OSD MAX7456 on SPI2
Blackbox SD Card on SPI3
Barometer SPA06-003 on I2C1
Magnetometer All supported via I2C1
Motor/Servo Outputs S1-S10 with DMA (full DSHOT support)
UARTs 6 (UART1-6) + USB VCP + 1 Softserial = 8 ports
LEDs PA14 (Blue), PA13 (Green)
Beeper PC15 (Inverted)
LED Strip PA8
ADC Vbat (PC0), Current (PC1), Airspeed (PC5), RSSI (PC4)
PINIO PC13 (USER1)
Default RX CRSF on UART6

Default Port Configuration

Port Function
UART1 MSP
UART5 GPS
UART6 CRSF RX

Pin Mapping

Motor/Servo Outputs

Output Pin Timer
S1 PB7 TIM4 CH2
S2 PB6 TIM4 CH1
S3 PB0 TIM3 CH3
S4 PB1 TIM3 CH4
S5 PC8 TIM8 CH3
S6 PC9 TIM8 CH4
S7 PB14 TIM8 CH2N
S8 PA15 TIM2 CH1
S9 PB10 TIM2 CH3
S10 PB11 TIM2 CH4
S11 PB15 TIM12 CH2

SPI Bus Assignment

Bus Pins (SCK/MISO/MOSI) Device
SPI1 PA5/PA6/PA7 ICM42688P Gyro (CS: PA4)
SPI2 PB13/PC2/PC3 MAX7456 OSD (CS: PB12)
SPI3 PB3/PB4/PB5 SD Card (CS: PC14)

I2C Bus Assignment

Bus Pins (SCL/SDA) Devices
I2C1 PB8/PB9 Barometer, Magnetometer, Rangefinder, Pitot

UART Pin Mapping

UART TX RX
UART1 PA9 PA10
UART2 PA2 PA3
UART3 PC10 PC11
UART4 PA0 PA1
UART5 PC12 PD2
UART6 PC6 PC7
Softserial1 PA2 PA2

Notes

  • Designed for fixed-wing aircraft with 11 servo/motor outputs
  • Supports rangefinder (US42) and pitot tube via I2C1
  • SD card blackbox logging enabled by default
  • Current meter scale: 158

PR Type

Enhancement

Description

  • Adds support for CoreWing F405 Wing V2 flight controller board
  • Configures ICM42688P gyro with CW270 alignment
  • Enables 11 motor/servo outputs with full DMA/DSHOT support
  • Includes 6 UARTs, OSD, SD card blackbox, barometer, and PINIO features

Block Diagram

flowchart LR
  MCU["STM32F405RGT6"]
  SPI1["SPI1: ICM42688P Gyro"]
  SPI2["SPI2: MAX7456 OSD"]
  SPI3["SPI3: SD Card"]
  I2C["I2C1:SPA06-003 Baro + Mag"]
  OUTPUTS["11 Servo/Motor Outputs"]
  UART["6 UARTs + USB VCP"]
  PINIO["PINIO: USER1"]

  MCU --> SPI1
  MCU --> SPI2
  MCU --> SPI3
  MCU --> I2C
  MCU --> OUTPUTS
  MCU --> UART
  MCU --> PINIO
Loading

PR Type

Enhancement


Description

  • Adds support for CoreWing F405 Wing V2 flight controller board

  • Configures ICM42688P gyro with CW270 alignment on SPI1

  • Enables 11 motor/servo outputs with full DMA/DSHOT support

  • Includes 6 UARTs, OSD, SD card blackbox, barometer, magnetometer

  • Supports rangefinder, pitot tube, LED strip, and PINIO features


Diagram Walkthrough

flowchart LR
  MCU["STM32F405RGT6"]
  SPI1["SPI1: ICM42688P Gyro"]
  SPI2["SPI2: MAX7456 OSD"]
  SPI3["SPI3: SD Card"]
  I2C["I2C1: Baro/Mag/Rangefinder"]
  UART["6 UARTs + USB VCP"]
  PWM["11 Motor/Servo Outputs"]
  
  MCU --> SPI1
  MCU --> SPI2
  MCU --> SPI3
  MCU --> I2C
  MCU --> UART
  MCU --> PWM
Loading

File Walkthrough

Relevant files
Configuration changes
target.h
Complete hardware configuration and pin definitions           

src/main/target/COREWINGF405WINGV2/target.h

  • Defines board identifier CW4W2 and product name
  • Configures all three SPI buses with pin mappings for gyro, OSD, and SD
    card
  • Sets up 6 UARTs plus VCP and softserial with pin assignments
  • Configures I2C1 for barometer, magnetometer, rangefinder, and pitot
    sensors
  • Defines ADC channels for voltage, current, RSSI, and airspeed
    monitoring
  • Enables LED strip, DSHOT, ESC sensor, and PINIO features
  • Sets default features including OSD, telemetry, and blackbox logging
+174/-0 
target.c
Timer and sensor hardware initialization                                 

src/main/target/COREWINGF405WINGV2/target.c

  • Registers ICM42688P gyro on SPI1 with CW270 alignment
  • Defines 11 timer hardware entries for motor/servo outputs with DMA
    assignments
  • Configures LED strip on TIM1 CH1 (PA8)
  • Sets up softserial1 TX on TIM5 CH3 (PA2)
+48/-0   
config.c
Default serial port and PINIO configuration                           

src/main/target/COREWINGF405WINGV2/config.c

  • Sets UART6 as default RX serial port for CRSF receiver
  • Configures UART5 for GPS functionality
  • Configures UART1 for MSP protocol
  • Sets PINIO1 as USER1 box for permanent ID mapping
+41/-0   
CMakeLists.txt
Build system configuration                                                             

src/main/target/COREWINGF405WINGV2/CMakeLists.txt

  • Adds build target for STM32F405 MCU variant
+1/-0     

@github-actions
Copy link

Branch Targeting Suggestion

You've targeted the master branch with this PR. Please consider if a version branch might be more appropriate:

  • maintenance-9.x - If your change is backward-compatible and won't create compatibility issues between INAV firmware and Configurator 9.x versions. This will allow your PR to be included in the next 9.x release.

  • maintenance-10.x - If your change introduces compatibility requirements between firmware and configurator that would break 9.x compatibility. This is for PRs which will be included in INAV 10.x

If master is the correct target for this change, no action is needed.


This is an automated suggestion to help route contributions to the appropriate branch.

@qodo-code-review
Copy link
Contributor

ⓘ Your approaching your monthly quota for Qodo. Upgrade your plan

PR Compliance Guide 🔍

All compliance sections have been disabled in the configurations.

Comment on lines +61 to +84
#define USE_UART2
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3

#define USE_UART3
#define UART3_TX_PIN PC10
#define UART3_RX_PIN PC11

#define USE_UART4
#define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1

#define USE_UART5
#define UART5_TX_PIN PC12
#define UART5_RX_PIN PD2

#define USE_UART6
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7

//Optional Softserial on UART2 TX Pin PA2
#define USE_SOFTSERIAL1
#define SOFTSERIAL_1_TX_PIN PA2
#define SOFTSERIAL_1_RX_PIN PA2
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggestion: Change SOFTSERIAL_1_RX_PIN from PA2 to PA3 to resolve the pin conflict with SOFTSERIAL_1_TX_PIN and align it with the UART2_RX_PIN. [possible issue, importance: 8]

Suggested change
#define USE_UART2
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define USE_UART3
#define UART3_TX_PIN PC10
#define UART3_RX_PIN PC11
#define USE_UART4
#define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1
#define USE_UART5
#define UART5_TX_PIN PC12
#define UART5_RX_PIN PD2
#define USE_UART6
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
//Optional Softserial on UART2 TX Pin PA2
#define USE_SOFTSERIAL1
#define SOFTSERIAL_1_TX_PIN PA2
#define SOFTSERIAL_1_RX_PIN PA2
#define USE_UART2
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
...
//Optional Softserial on UART2 TX Pin PA2
#define USE_SOFTSERIAL1
#define SOFTSERIAL_1_TX_PIN PA2
#define SOFTSERIAL_1_RX_PIN PA3

Comment on lines +36 to +38
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_RX_SERIAL;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_GPS;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_MSP;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggestion: Add checks to verify that the index returned by findSerialPortIndexByIdentifier is not -1 before using it to access the portConfigs array, preventing potential out-of-bounds access. [possible issue, importance: 6]

Suggested change
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_RX_SERIAL;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_GPS;
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_MSP;
int idx;
idx = findSerialPortIndexByIdentifier(SERIAL_PORT_USART6);
if (idx >= 0) serialConfigMutable()->portConfigs[idx].functionMask = FUNCTION_RX_SERIAL;
idx = findSerialPortIndexByIdentifier(SERIAL_PORT_USART5);
if (idx >= 0) serialConfigMutable()->portConfigs[idx].functionMask = FUNCTION_GPS;
idx = findSerialPortIndexByIdentifier(SERIAL_PORT_USART1);
if (idx >= 0) serialConfigMutable()->portConfigs[idx].functionMask = FUNCTION_MSP;

#include "drivers/pinio.h"
#include "drivers/sensor.h"

BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggestion: Change the hardware identifier from DEVHW_ICM42605 to DEVHW_ICM42688 in the BUSDEV_REGISTER_SPI_TAG macro to match the actual ICM42688P sensor on the board. [general, importance: 7]

Suggested change
BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42605, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);
BUSDEV_REGISTER_SPI_TAG(busdev_icm42688, DEVHW_ICM42688, ICM42605_SPI_BUS, ICM42605_CS_PIN, NONE, 0, DEVFLAGS_NONE, IMU_ICM42605_ALIGN);

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

1 participant