2023-03-22 06:08:39 -03:00
|
|
|
|
|
|
|
# hw definition file for processing by chibios_hwdef.py
|
|
|
|
# for FLYWOOF405PRO hardware.
|
|
|
|
# thanks to betaflight for pin information
|
|
|
|
|
|
|
|
# MCU class and specific type
|
|
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
|
|
|
|
# board ID for firmware load
|
|
|
|
APJ_BOARD_ID 1137
|
|
|
|
|
|
|
|
# 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 4
|
|
|
|
define CH_CFG_ST_RESOLUTION 16
|
|
|
|
|
|
|
|
# SPI devices
|
|
|
|
|
|
|
|
# SPI1
|
|
|
|
PA5 SPI1_SCK SPI1
|
|
|
|
PA6 SPI1_MISO SPI1
|
|
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
|
|
|
|
# SPI3
|
|
|
|
PC10 SPI3_SCK SPI3
|
|
|
|
PC11 SPI3_MISO SPI3
|
|
|
|
PC12 SPI3_MOSI SPI3
|
|
|
|
|
|
|
|
# Chip select pins
|
|
|
|
PB3 FLASH1_CS CS
|
|
|
|
PB14 OSD1_CS CS
|
|
|
|
PB12 GYRO1_CS CS
|
|
|
|
|
|
|
|
# Beeper
|
|
|
|
PC13 BUZZER OUTPUT GPIO(80) LOW
|
|
|
|
define HAL_BUZZER_PIN 80
|
|
|
|
define HAL_BUZZER_ON 1
|
|
|
|
define HAL_BUZZER_OFF 0
|
|
|
|
|
|
|
|
# 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 (GPS)
|
|
|
|
PA10 USART1_RX USART1 NODMA
|
|
|
|
PB6 USART1_TX USART1 NODMA
|
|
|
|
DEFAULT_SERIAL1_PROTOCOL SerialProtocol_GPS
|
|
|
|
|
|
|
|
# USART2 (ESC Telemetry)
|
|
|
|
PD6 USART2_RX USART2 NODMA
|
|
|
|
DEFAULT_SERIAL2_PROTOCOL SerialProtocol_ESCTelemetry
|
|
|
|
|
|
|
|
# USART3 (DJI)
|
|
|
|
PB10 USART3_TX USART3
|
|
|
|
PB11 USART3_RX USART3
|
|
|
|
DEFAULT_SERIAL3_PROTOCOL SerialProtocol_DJI_FPV
|
|
|
|
|
|
|
|
# UART4 (SBUS)
|
|
|
|
PA0 UART4_TX UART4
|
|
|
|
PA1 UART4_RX UART4 NODMA ALT(1)
|
|
|
|
PA1 TIM5_CH2 TIM5 RCININT PULLDOWN LOW
|
|
|
|
|
|
|
|
# UART5
|
|
|
|
# No suitable timer for this pin so cannot use RCININT
|
|
|
|
# and too difficult to get a DMA channel
|
|
|
|
PD2 UART5_RX UART5 NODMA
|
|
|
|
DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None
|
|
|
|
|
|
|
|
# USART6 (RCIN)
|
|
|
|
PC6 USART6_TX USART6
|
|
|
|
PC7 USART6_RX USART6
|
|
|
|
DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
|
|
|
|
|
|
|
# I2C ports
|
|
|
|
I2C_ORDER I2C1
|
|
|
|
# I2C1
|
|
|
|
PB8 I2C1_SCL I2C1
|
|
|
|
PB9 I2C1_SDA I2C1
|
|
|
|
|
|
|
|
BARO DPS310 I2C:0:0x76
|
|
|
|
|
|
|
|
# Servos
|
|
|
|
|
|
|
|
# ADC ports
|
|
|
|
|
|
|
|
# ADC1
|
|
|
|
PC0 RSSI_ADC ADC1
|
|
|
|
define BOARD_RSSI_ANA_PIN 10
|
|
|
|
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
define HAL_BATT_CURR_PIN 12
|
|
|
|
define HAL_BATT_CURR_SCALE 58.8
|
|
|
|
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
|
|
define HAL_BATT_VOLT_PIN 13
|
|
|
|
define HAL_BATT_VOLT_SCALE 11.0
|
|
|
|
define HAL_BATT_MONITOR_DEFAULT 4
|
|
|
|
|
|
|
|
# MOTORS
|
|
|
|
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) # M1
|
|
|
|
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR # M2
|
|
|
|
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52) BIDIR # M3
|
|
|
|
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53) # M4
|
|
|
|
PB5 TIM3_CH2 TIM3 PWM(5) GPIO(54) # M5
|
|
|
|
PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) # M6
|
|
|
|
PB4 TIM3_CH1 TIM3 PWM(7) GPIO(56) # M7
|
|
|
|
PC8 TIM8_CH3 TIM8 PWM(8) GPIO(57) # M8
|
|
|
|
|
|
|
|
# LEDs
|
|
|
|
PA9 TIM1_CH2 TIM1 PWM(9) GPIO(58) # M9
|
|
|
|
|
|
|
|
PC14 LED0 OUTPUT LOW GPIO(90)
|
|
|
|
define HAL_GPIO_A_LED_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 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
|
|
|
|
|
|
|
|
# IMU setup
|
|
|
|
|
|
|
|
# IMU setup
|
|
|
|
SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ
|
|
|
|
IMU Invensensev3 SPI:imu1 ROTATION_NONE
|
|
|
|
#DMA_NOSHARE TIM3_UP TIM2_UP TIM8_UP SPI1*
|
|
|
|
DMA_PRIORITY TIM3* TIM2* TIM8_UP SPI1* TIM1_UP
|
|
|
|
|
|
|
|
# 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
|
2023-10-15 10:19:04 -03:00
|
|
|
|
|
|
|
include ../include/minimize_fpv_osd.inc
|
2024-03-31 09:21:42 -03:00
|
|
|
|