Skip to content

Conversation

@CoreWingDev
Copy link

@CoreWingDev CoreWingDev commented Jan 26, 2026

User description

CoreWing F405 Wing V2

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 on I2C1 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 string
  • Configures all three SPI buses with pin assignments
  • Sets up 6 UARTs plus USB VCP and softserial
  • Defines I2C1 for sensors (barometer, magnetometer, rangefinder, pitot)
  • Configures ICM42688P gyro with CW270 alignment on SPI1
  • Enables MAX7456 OSD on SPI2 and SD card on SPI3
  • Sets up ADC channels for voltage, current, airspeed, and RSSI
  • Defines 11 PWM outputs with LED strip and PINIO support
+174/-0 
target.c
Timer and sensor hardware initialization                                 

src/main/target/COREWINGF405WINGV2/target.c

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

src/main/target/COREWINGF405WINGV2/config.c

  • Sets UART6 as default CRSF RX serial port
  • Configures UART5 for GPS functionality
  • Configures UART1 for MSP protocol
  • Enables PINIO user1 box on PC13
+41/-0   
CMakeLists.txt
Build system configuration                                                             

src/main/target/COREWINGF405WINGV2/CMakeLists.txt

  • Adds CMake 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 +34 to +41
void targetConfiguration(void)
{
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;

pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
}
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggestion: Store the result of findSerialPortIndexByIdentifier() and guard against -1 before indexing portConfigs to avoid out-of-bounds writes when a port identifier is unavailable/misconfigured. [Learned best practice, importance: 6]

Suggested change
void targetConfiguration(void)
{
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;
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
}
void targetConfiguration(void)
{
const int usart6Index = findSerialPortIndexByIdentifier(SERIAL_PORT_USART6);
const int usart5Index = findSerialPortIndexByIdentifier(SERIAL_PORT_USART5);
const int usart1Index = findSerialPortIndexByIdentifier(SERIAL_PORT_USART1);
if (usart6Index >= 0) {
serialConfigMutable()->portConfigs[usart6Index].functionMask = FUNCTION_RX_SERIAL;
}
if (usart5Index >= 0) {
serialConfigMutable()->portConfigs[usart5Index].functionMask = FUNCTION_GPS;
}
if (usart1Index >= 0) {
serialConfigMutable()->portConfigs[usart1Index].functionMask = FUNCTION_MSP;
}
pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1;
}

@sensei-hacker sensei-hacker changed the base branch from master to maintenance-9.x January 26, 2026 04:42
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.

3 participants