mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: FoxeerF405v2
This commit is contained in:
parent
c302ea6e70
commit
dbfcd6c678
Binary file not shown.
After Width: | Height: | Size: 265 KiB |
|
@ -0,0 +1,98 @@
|
|||
# FoxeerF405v2 Flight Controller
|
||||
|
||||
The FoxeerF405v2 is a flight controller produced by [Foxeer](https://www.foxeer.com/).
|
||||
|
||||
## Features
|
||||
|
||||
- MCU - STM32F405 32-bit processor
|
||||
- IMU - ICM42688
|
||||
- Barometer - DPS310
|
||||
- OSD - AT7456E
|
||||
- Onboard Flash: 128Mbit
|
||||
- 6x UARTs
|
||||
- 9x PWM Outputs (8 Motor Output, 1 LED)
|
||||
- Battery input voltage: 2S-8S
|
||||
- BEC 3.3V 0.5A
|
||||
- BEC 5V 2A
|
||||
- BEC 10V 2A
|
||||
|
||||
## Pinout
|
||||
|
||||
![FoxeerF405v2 Board](FoxeerF405v2.jpg "FoxeerF405v2")
|
||||
|
||||
## 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 (ESC Telemetry)
|
||||
- SERIAL2 -> UART2 (RX, DMA-enabled)
|
||||
- SERIAL3 -> UART3 (VTX)
|
||||
- SERIAL4 -> UART4
|
||||
- SERIAL5 -> UART5 (GPS, DMA-enabled)
|
||||
- SERIAL6 -> UART6
|
||||
|
||||
## RC Input
|
||||
|
||||
RC input is configured by default on the R2 (UART2_RX) pad. It supports all serial RC
|
||||
protocols. For protocols requiring separate half-duplex serial to transmit
|
||||
telemetry (such as FPort) you should setup SERIAL1 as an RC input serial port,
|
||||
with half-duplex, pin-swap and inversion enabled.
|
||||
|
||||
## FrSky Telemetry
|
||||
|
||||
FrSky Telemetry can be supported using the T1 pin (UART1 transmit). You need to set the following parameters to enable support for FrSky S.PORT
|
||||
|
||||
- SERIAL1_PROTOCOL 10
|
||||
- SERIAL1_OPTIONS 7
|
||||
|
||||
## OSD Support
|
||||
|
||||
The FoxeerF405v2 supports OSD using OSD_TYPE 1 (MAX7456 driver) or OSD_TYPE 3 if using DJI OSD
|
||||
|
||||
## PWM Output
|
||||
|
||||
The FoxeerF405v2 supports up to 9 PWM outputs. The pads for motor output
|
||||
M1 to M8 are provided on both the motor connectors and on separate pads, plus
|
||||
M9 on a separate pad for LED strip or another PWM output.
|
||||
|
||||
The PWM is in 4 groups:
|
||||
|
||||
- PWM 1,4 in group1
|
||||
- PWM 2,3 in group2
|
||||
- PWM 5,9 in group3
|
||||
- PWM 6-8 in group4
|
||||
|
||||
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.
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has a builting voltage and current sensor. The current
|
||||
sensor can read up to 130 Amps. The voltage sensor can handle up to 8S
|
||||
LiPo batteries.
|
||||
|
||||
The correct battery setting parameters are:
|
||||
|
||||
- BATT_MONITOR 4
|
||||
- BATT_VOLT_PIN 10
|
||||
- BATT_CURR_PIN 11
|
||||
- BATT_VOLT_MULT 11
|
||||
- BATT_AMP_PERVLT 142.9
|
||||
|
||||
## Compass
|
||||
|
||||
The FoxeerF405v2 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.
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for FOXEERF405V2 hardware.
|
||||
# thanks to betaflight for pin information
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID AP_HW_FOXEERF405_V2
|
||||
|
||||
# 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
|
||||
|
||||
# default to all pins low to avoid ESD issues
|
||||
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
||||
|
||||
|
||||
# Chip select pins
|
||||
PB12 FLASH1_CS CS
|
||||
PC14 OSD1_CS CS
|
||||
PA4 GYRO1_CS CS
|
||||
|
||||
PA13 LED_BOOTLOADER OUTPUT LOW
|
||||
define HAL_LED_ON 0
|
|
@ -0,0 +1,164 @@
|
|||
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for FOXEERF405V2 hardware.
|
||||
# thanks to betaflight for pin information
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F4xx STM32F405xx
|
||||
|
||||
HAL_CHIBIOS_ARCH_F405 1
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID AP_HW_FOXEERF405_V2
|
||||
|
||||
# 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
|
||||
PB12 FLASH1_CS CS
|
||||
PC14 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
|
||||
PA10 USART1_RX USART1 NODMA
|
||||
PA9 USART1_TX USART1 NODMA
|
||||
|
||||
# USART2
|
||||
PA2 USART2_TX USART2
|
||||
PA3 USART2_RX USART2
|
||||
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
||||
|
||||
# USART3
|
||||
PC10 USART3_TX USART3 NODMA
|
||||
PC11 USART3_RX USART3 NODMA
|
||||
|
||||
# UART4
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
|
||||
# UART5
|
||||
PC12 UART5_TX UART5
|
||||
PD2 UART5_RX UART5
|
||||
|
||||
# USART6
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
PC7 USART6_RX USART6 NODMA
|
||||
|
||||
# I2C ports
|
||||
I2C_ORDER I2C1
|
||||
# I2C1
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
|
||||
# Servos
|
||||
PB1 SERVO1 OUTPUT GPIO(70) LOW
|
||||
define RELAY2_PIN_DEFAULT 70
|
||||
PB14 CAMERA1 OUTPUT GPIO(71) LOW
|
||||
define RELAY3_PIN_DEFAULT 71
|
||||
|
||||
# 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 142.9
|
||||
PC5 RSSI_ADC ADC1
|
||||
define BOARD_RSSI_ANA_PIN 15
|
||||
define HAL_BATT_MONITOR_DEFAULT 4
|
||||
|
||||
# MOTORS
|
||||
PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) # M1
|
||||
PC9 TIM8_CH4 TIM8 PWM(2) GPIO(51) # M2
|
||||
PC8 TIM8_CH3 TIM8 PWM(3) GPIO(52) # M3
|
||||
PB15 TIM1_CH3N TIM1 PWM(4) GPIO(53) # M4
|
||||
PB6 TIM4_CH1 TIM4 PWM(5) GPIO(54) # M5
|
||||
PA15 TIM2_CH1 TIM2 PWM(6) GPIO(55) # M6
|
||||
PB11 TIM2_CH4 TIM2 PWM(7) GPIO(56) # M7
|
||||
PB10 TIM2_CH3 TIM2 PWM(8) GPIO(57) # M8
|
||||
|
||||
PB7 TIM4_CH2 TIM4 PWM(9) GPIO(58) # LED
|
||||
|
||||
# LEDs
|
||||
|
||||
PA13 LED0 OUTPUT LOW GPIO(90)
|
||||
define HAL_GPIO_A_LED_PIN 90
|
||||
|
||||
PA14 LED1 OUTPUT LOW GPIO(91)
|
||||
define HAL_GPIO_B_LED_PIN 91
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# 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 DPS310 I2C:0:0x76
|
||||
|
||||
# IMU setup
|
||||
|
||||
# IMU setup
|
||||
SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ
|
||||
|
||||
IMU Invensensev3 SPI:imu1 ROTATION_PITCH_180_YAW_90
|
||||
DMA_NOSHARE TIM1_UP TIM8_UP TIM4_UP TIM2_UP SPI1*
|
||||
DMA_PRIORITY TIM1_UP TIM8_UP TIM4_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
|
||||
|
||||
include ../include/minimize_fpv_osd.inc
|
|
@ -370,6 +370,8 @@ define HAL_BATT_CURR_SCALE %.1f
|
|||
for led in sorted(functions["LED"].values()):
|
||||
if (led[3].endswith('_STRIP')):
|
||||
pin = led[1]
|
||||
if not pin in timers.keys():
|
||||
continue
|
||||
timer = timers[pin]
|
||||
nmotors = nmotors+1
|
||||
f.write("%s %s_%s %s PWM(%s) GPIO(%s) # M%s\n" % (led[1], timer[1], timer[2], timer[1], nmotors, 49+nmotors, nmotors))
|
||||
|
@ -382,7 +384,7 @@ define HAL_GPIO_%s_LED_PIN %u
|
|||
f.write("define HAL_GPIO_LED_OFF 1\n")
|
||||
|
||||
# write out devices
|
||||
if settings['blackbox_device'] == 'SPIFLASH':
|
||||
if 'blackbox_device' in settings and settings['blackbox_device'] == 'SPIFLASH' or 'USE_FLASH' in defines:
|
||||
write_flash_config(f, settings['flash_spi_bus'])
|
||||
|
||||
if 'max7456_spi_bus' in settings:
|
||||
|
|
Loading…
Reference in New Issue