SpeedyBee F405 40A AIO 1-6S

Does the SpeedyBee F405 40A AIO 1-6S support ardupilot firmware like F405 V3/V4 or mini

Speedybee doesn’t think so.
Supported Flight Controller Firmware- BetaFlight (Default), INAV

They write the same for f405 v3/v4. But they support ardupilot. Probably speedybee doesn’t like ardupilot.

Actually they are a Ardupilot Corporate Partner now.

Very strange partners, if they don’t write about ardupilot firmware anywhere.

They do on some Flight Controllers. It looks like they haven’t updated their website and manuals since Ardupilot has been supported on some boards. But I don’t know about that one.

This is what customer support told me: Dear Customer,

Thank you for your message.

We regret to inform you that the SpeedyBee F405 AIO flight controller is not compatible with Ardupilot firmware. It only supports Betaflight and INAV firmware.

Additionally, the SpeedyBee F4V3/V4 flight controllers are also not compatible with Ardupilot firmware.

If you have any further questions or need additional assistance, please feel free to reach out to us.
Thank you for your understanding.

Regards,
SpeedyBee Customer Service
Anna.

Good Ardupilot partners :slight_smile:

Someone in customer service that doesn’t know what they are talking about?
Speedybee F405 V3
Speedybee F405 V4

Any update on this board? I’m also very interested on this as I had to replace my brand new faulty GN745 AIO V4.

How do I contribute? I had the board already installed on my 2.5" cinewhoop. Also I’m very bad at software, but I know my hardware.

I am tempted to flash it with speedybeef4v4 using custom builder, but probably a bad idea to do so.

I’m learning lots of new things here. Following this guide:
Porting to a new flight controller board — Dev documentation

I managed to create the hwdef.dat compiled and succesfully uploaded to the board. This board use the new baro SPA06 which it seem not supported yet in copter 4.5.7 but should be supported in the upcoming 4.7.0

Now, I don’t know much about github yet, don’t know how to submit PR, haven’t done extensive testing, and I’m sure there will be something wrong with my code.

If anyone is interested to test or review, please update us! It will be very helpful

hwdef.dat is based on SpeedyBeeF405Mini

# hw definition file for processing by chibios_hwdef.py
# for SPEEDYBEEF405AIO hardware.
# thanks to betaflight for pin information

# MCU class and specific type
MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 5271

# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000

FLASH_SIZE_KB 1024

# bootloader takes first sector
FLASH_RESERVE_START_KB 48

define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 1

# SPI devices

# SPI1
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# SPI2
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2

# SPI3
PB3 SPI3_SCK SPI3
PB4 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3

# Chip select pins
PB12 FLASH1_CS CS
PD5 OSD1_CS CS
PA4 GYRO1_CS CS

# Beeper
PD11 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80

# SERIAL ports
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# USART1
PA10 USART1_RX USART1
PA9 USART1_TX USART1
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_None

# USART2 (SBUS)
PD6 USART2_RX USART2
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None

# USART3 (DJI)
PD8 USART3_TX USART3
PD9 USART3_RX USART3
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_MSP_DisplayPort

# UART4
PC10 UART4_TX UART4 NODMA
PC11 UART4_RX UART4 NODMA
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None

# UART5 (GPS)
PC12 UART5_TX UART5
PD2 UART5_RX UART5
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_GPS
define DEFAULT_SERIAL5_BAUD 115

# USART6 (ELRS)
PC6 USART6_TX USART6
PC7 USART6_RX USART6
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN

# I2C ports
I2C_ORDER I2C1
# I2C1
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1

# Servos
PD15 CAMERA1 OUTPUT GPIO(70) LOW
define RELAY2_PIN_DEFAULT 70

# ADC ports

# ADC1
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
define HAL_BATT_VOLT_PIN 10
define HAL_BATT_VOLT_SCALE 11.0
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
define HAL_BATT_CURR_PIN 11
define HAL_BATT_CURR_SCALE 40.0
#PC5 RSSI_ADC ADC1
#define BOARD_RSSI_ANA_PIN 15
define HAL_BATT_MONITOR_DEFAULT 4

# MOTORS
PA1 TIM5_CH2 TIM5 PWM(1) GPIO(50)       # M1
PA0 TIM5_CH1 TIM5 PWM(2) GPIO(51) BIDIR # M2
PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR # M3
PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53)       # M4

# LEDs
PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) # M5

define AP_NOTIFY_GPIO_LED_1_ENABLED 1
PD7 LED0 OUTPUT LOW GPIO(90)
define AP_NOTIFY_GPIO_LED_1_PIN 90

# Dataflash setup
SPIDEV dataflash SPI3 DEVID1 FLASH1_CS     MODE3 104*MHZ 104*MHZ

define HAL_LOGGING_DATAFLASH_ENABLED 1

# OSD setup
SPIDEV osd SPI2 DEVID1 OSD1_CS   MODE0  10*MHZ  10*MHZ

define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

# Barometer setup
BARO SPL06 I2C:0:0x76
        
# IMU setup

# IMU setup
SPIDEV imu1   SPI1 DEVID1 GYRO1_CS   MODE3   1*MHZ   8*MHZ

IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180_YAW_135
#DMA_NOSHARE TIM2_UP TIM5_UP SPI1*
DMA_PRIORITY TIM5* SPI1* USART6_RX*

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
define HAL_DEFAULT_INS_FAST_SAMPLE 3
# Motor order implies Betaflight/X for standard ESCs
define HAL_FRAME_TYPE_DEFAULT 12

include ../include/minimize_fpv_osd.inc

hwdef-bl.dat is based on SpeedyBeeF405Mini

# hw definition file for processing by chibios_hwdef.py
# for SPEEDYBEEF405AIO hardware.
# thanks to betaflight for pin information

# MCU class and specific type
MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 5271

# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000

FLASH_SIZE_KB 1024

# bootloader starts at zero offset
FLASH_RESERVE_START_KB 0

# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 48

# order of UARTs (and USB)
SERIAL_ORDER OTG1

# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

# Chip select pins
PB12 FLASH1_CS CS
PD5 OSD1_CS CS
PA4 GYRO1_CS CS

PA8 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0

What I have tested:

  • baro, imu, external compass QMC5883L (i2c)
  • RC_IN using ELRS on Serial6
  • motor output using dshot300
  • voltage reading
  • BLE to SpeedyBee App is not working with Ardupiot (as expected)

What I have NOT tested:

  • flying it
  • GPS lock using GM10 w/compass (gps detected as u-blox, but not tested outdoor yet)
  • MSP_Displayport for DJI O3 on Serial3
  • Dataflash logs
  • current reading
  • something else I might miss

What I WILL NOT test:

  • SBUS
  • LED
  • buzzer
  • analog camera & osd
  • devices on different serial ports (I had mine already soldered so I cannot change ports, wires are very small and fragile)

forgive my ignorance, it seems copter 4.6.0 already support SPA06 barometer

So, I messed up the mapping.

  • SPI2 is supposed to be for the dataflash and SPI3 is for OSD chip
  • Correct pin for current sensor is at pin 12 (PC2 on ADC1)
  • I have to set BATT_AMP_OFFSET 0.033 on my board to get good current reading
  • I set mine with BATT_VOLT_MULT 11.11 to get more accurate voltage reading. If other board also have same multiplier maybe we can set this as default?

I also enabled the turtle mode in the config

What I tested using copter 4.6.0-beta4:

  • IMU & baro behaving normally with correct orientation (board yaw 45 as normally mounted)
  • my board is mounted upside-down so I set mine to AHRS_ORIENTATION 8 (ROLL 180)
  • dataflash log is functioning
  • QMC5883L on I2C is working
  • RC_IN with ELRS on Serial6 is working
  • motor mapping is correct (motor layout follows betaflight configuration)
  • motor output with dshot300 and dshot600 are good
  • voltage current reading & scales are good (BATT_AMP_OFFSET need tuning)
  • GPS lock with GM10 nano on Serial5 (u-blox detected)
  • MSP DisplayPort with DJI O3 on Serial3
  • 2.5 minutes flying in stabilize mode

Here’s the latest hwdef.bat


# hw definition file for processing by chibios_hwdef.py
# for SPEEDYBEEF405AIO hardware.
# thanks to betaflight for pin information

# MCU class and specific type
MCU STM32F4xx STM32F405xx

# board ID for firmware load
APJ_BOARD_ID 5271

# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000

FLASH_SIZE_KB 1024

# bootloader takes first sector
FLASH_RESERVE_START_KB 48

define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 1

# SPI devices

# SPI1
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1

# SPI2
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2

# SPI3
PB3 SPI3_SCK SPI3
PB4 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3

# Chip select pins
PB12 FLASH1_CS CS
PD5 OSD1_CS CS
PA4 GYRO1_CS CS

# Beeper
PD11 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80

# SERIAL ports
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1

# USART1
PA10 USART1_RX USART1
PA9 USART1_TX USART1
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_None

# USART2 (SBUS)
PD6 USART2_RX USART2
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None

# USART3 (DJI)
PD8 USART3_TX USART3
PD9 USART3_RX USART3
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_MSP_DisplayPort

# UART4
PC10 UART4_TX UART4 NODMA
PC11 UART4_RX UART4 NODMA
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None

# UART5 (GPS)
PC12 UART5_TX UART5
PD2 UART5_RX UART5
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_GPS
define DEFAULT_SERIAL5_BAUD 115

# USART6 (ELRS)
PC6 USART6_TX USART6
PC7 USART6_RX USART6
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN

# I2C ports
I2C_ORDER I2C1
# I2C1
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1

# camera control
PD15 CAMERA1 OUTPUT GPIO(70) LOW
define RELAY1_PIN_DEFAULT 70

# ADC ports

# ADC1
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
define HAL_BATT_VOLT_PIN 10
define HAL_BATT_VOLT_SCALE 11.0
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
define HAL_BATT_CURR_PIN 12
define HAL_BATT_CURR_SCALE 40.0
define HAL_BATT_MONITOR_DEFAULT 4

# MOTORS
PA1 TIM5_CH2 TIM5 PWM(1) GPIO(50)       # M1
PA0 TIM5_CH1 TIM5 PWM(2) GPIO(51) BIDIR # M2
PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR # M3
PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53)       # M4

# LEDs
PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) # M5

define AP_NOTIFY_GPIO_LED_1_ENABLED 1
PD7 LED0 OUTPUT LOW GPIO(90)
define AP_NOTIFY_GPIO_LED_1_PIN 90

# Dataflash setup
SPIDEV dataflash SPI2 DEVID1 FLASH1_CS     MODE3 104*MHZ 104*MHZ

define HAL_LOGGING_DATAFLASH_ENABLED 1

# OSD setup
SPIDEV osd SPI3 DEVID1 OSD1_CS   MODE0  10*MHZ  10*MHZ

define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

# Barometer setup
BARO SPL06 I2C:0:0x76
        
# IMU setup

# IMU setup
SPIDEV imu1   SPI1 DEVID1 GYRO1_CS   MODE3   1*MHZ   8*MHZ

IMU Invensensev3 SPI:imu1 ROTATION_ROLL_180_YAW_135
#DMA_NOSHARE TIM2_UP TIM5_UP SPI1*
DMA_PRIORITY TIM5* SPI1* USART6_RX*

# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
define HAL_DEFAULT_INS_FAST_SAMPLE 3

# Motor order implies Betaflight/X for standard ESCs
define HAL_FRAME_TYPE_DEFAULT 12

# Enable turtle mode
define MODE_TURTLE_ENABLED 1

include ../include/minimize_fpv_osd.inc

I’m happy with this. Can’t wait for 4.6.0 to be released as stable

1 Like