AP_HAL_ChibiOS: add support for SpeedyBeeF405v4

This commit is contained in:
Andy Piper 2023-10-13 10:32:57 +01:00 committed by Randy Mackay
parent ab6e240f80
commit b8f92841d7
5 changed files with 308 additions and 0 deletions

View File

@ -0,0 +1,100 @@
# SpeedyBee F405 v4 Flight Controller
The SpeedyBee F405 v4 is a flight controller produced by [SpeedyBee](http://www.speedybee.com/).
## Features
- STM32F405 microcontroller
- ICM42688 IMU
- DPS310 barometer
- SDCard
- AT7456E OSD
- 6 UARTs
- 9 PWM outputs
## Pinout
![SpeedyBee F405 v4](SpeedyBee_F405_v4_Board_Top.JPG "SpeedyBee F405 v4")
![SpeedyBee F405 v4](SpeedyBee_F405_v4_Board_Bottom.JPG "SpeedyBee F405 v4")
## UART Mapping
The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the
receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
- SERIAL0 -> USB
- SERIAL1 -> UART1 (DJI-VTX, DMA-enabled)
- SERIAL2 -> UART2 (RCIN, DMA-enabled)
- SERIAL3 -> UART3 (CAM)
- SERIAL4 -> UART4 (connected to internal BT module, not currently usable by ArduPilot)
- SERIAL5 -> UART5 (ESC Telemetry)
- SERIAL6 -> UART6 (GPS, DMA-enabled)
## RC Input
RC input is configured on the R2 (UART2_RX) pin for most RC unidirectional protocols except SBUS which should be applied at the SBUS pin. PPM is not supported.
For Fport, a bi-directional inverter will be required. See https://ardupilot.org/plane/docs/common-connecting-sport-fport.html
For CRSF/ELRS/SRXL2 connection of the receiver to T2 will also be required.
## FrSky Telemetry
FrSky Telemetry is supported using the Tx pin of any UART including SERIAL2/UART2. You need to set the following parameters to enable support for FrSky S.PORT (example shows SERIAL3).
- SERIAL3_PROTOCOL 10
- SERIAL3_OPTIONS 7
## OSD Support
The SpeedyBee F405 v4 supports OSD using OSD_TYPE 1 (MAX7456 driver).
## VTX Support
The JST-GH-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 9v so be careful not to connect
this to a peripheral requiring 5v.
## PWM Output
The SpeedyBee F405 v4 supports up to 9 PWM outputs. The pads for motor output
M1 to M4 on the motor connector, plus M9 for LED strip or another
PWM output.
The PWM is in 5 groups:
- PWM 1-2 in group1
- PWM 3-4 in group2
- PWM 5-6 in group3
- PWM 7-8 in group4
- PWM 9 in group5
Channels within the same group need to use the same output rate. If
any channel in a group uses DShot then all channels in the group need
to use DShot. Channels 1-4 support bi-directional DShot.
## Battery Monitoring
The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input.
The voltage sensor can handle up to 6S.
LiPo batteries.
The default battery parameters are:
- BATT_MONITOR 4
- BATT_VOLT_PIN 10
- BATT_CURR_PIN 11
- BATT_VOLT_MULT 11.2
- BATT_AMP_PERVLT 52.7 (will need to be adjusted for whichever current sensor is attached)
## Compass
The SpeedyBee F405 v4 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads.
## Loading Firmware
Initial firmware load can be done with DFU by plugging in USB with the
bootloader button pressed. Then you should load the "with_bl.hex"
firmware, using your favourite DFU loading tool.
Once the initial firmware is loaded you can update the firmware using
any ArduPilot ground station software. Updates should be done with the
*.apj firmware files.

Binary file not shown.

After

Width:  |  Height:  |  Size: 104 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 143 KiB

View File

@ -0,0 +1,43 @@
# hw definition file for processing by chibios_hwdef.py
# for SPEEDYBEEF405V4 hardware.
# thanks to betaflight for pin information
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 1136
# 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
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# Chip select pins
PC14 SDCARD1_CS CS
PB12 OSD1_CS CS
PA4 GYRO1_CS CS
PA8 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0

View File

@ -0,0 +1,165 @@
# hw definition file for processing by chibios_hwdef.py
# for SPEEDYBEEF405V4 hardware.
# thanks to betaflight for pin information
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 1136
# 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
STM32_ST_USE_TIMER 5
# SPI devices
# SPI1
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# SPI2
PB13 SPI2_SCK SPI2
PC2 SPI2_MISO SPI2
PC3 SPI2_MOSI SPI2
# SPI3
PB3 SPI3_SCK SPI3
PB4 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3
# Chip select pins
PC14 SDCARD1_CS CS
PB12 OSD1_CS CS
PA4 GYRO1_CS CS
# Beeper
PC15 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 (DJI / VTX)
PA10 USART1_RX USART1 NODMA
PA9 USART1_TX USART1 NODMA
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_DJI_FPV
# USART2 (RCIN)
PA2 USART2_TX USART2
PA3 USART2_RX USART2
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
# USART3 (CAM)
PC10 USART3_TX USART3 NODMA
PC11 USART3_RX USART3 NODMA
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None
# UART4 (Bluetooth)
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None
# UART5 (ESC Telemetry)
PD2 UART5_RX UART5 NODMA
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry
define DEFAULT_SERIAL5_BAUD 19200
# USART6 (GPS)
PC6 USART6_TX USART6
PC7 USART6_RX USART6
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_GPS
define DEFAULT_SERIAL6_BAUD AP_SERIALMANAGER_GPS_BAUD
# I2C ports
I2C_ORDER I2C1
# I2C1
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
# Servos
PB14 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
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
define HAL_BATT_CURR_PIN 11
define HAL_BATT_CURR_SCALE 25.0
PC5 RSSI_ADC ADC1
define BOARD_RSSI_ANA_PIN 15
define HAL_BATT_MONITOR_DEFAULT 4
# MOTORS
PB6 TIM4_CH1 TIM4 PWM(1) GPIO(50) # M1
PB7 TIM4_CH2 TIM4 PWM(2) GPIO(51) BIDIR # M2
PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52) # M3
PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) BIDIR # M4
PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54) # M5
PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) # M6
PB10 TIM2_CH3 TIM2 PWM(7) GPIO(56) # M7
PA15 TIM2_CH1 TIM2 PWM(8) GPIO(57) # M8
# LEDs
PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # M9
PC13 LED0 OUTPUT LOW GPIO(90)
define HAL_GPIO_A_LED_PIN 90
define HAL_GPIO_LED_OFF 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
define AP_BARO_BACKEND_DEFAULT_ENABLED 0
define AP_BARO_SPL06_ENABLED 1
BARO SPL06 I2C:0:0x76
# IMU setup
SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ
# SDCard
SPIDEV sdcard SPI3 DEVID1 SDCARD1_CS MODE0 400*KHZ 25*MHZ
IMU Invensensev3 SPI:imu1 ROTATION_PITCH_180_YAW_270
DMA_NOSHARE TIM3_UP TIM8_UP TIM2_UP SPI1*
DMA_PRIORITY TIM3_UP TIM8_UP TIM2_UP SPI1*
# 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
# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
# minimal drivers to reduce flash usage
include ../include/minimize_fpv_osd.inc
define DEFAULT_NTF_LED_TYPES 257