mirror of https://github.com/ArduPilot/ardupilot
169 lines
3.5 KiB
Plaintext
169 lines
3.5 KiB
Plaintext
|
|
# 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
|
|
PA9 USART1_TX USART1
|
|
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_ESCTelemetry
|
|
|
|
# USART2
|
|
PA2 USART2_TX USART2
|
|
PA3 USART2_RX USART2
|
|
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN
|
|
|
|
# USART3
|
|
PC10 USART3_TX USART3
|
|
PC11 USART3_RX USART3 NODMA
|
|
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Tramp
|
|
|
|
# UART4
|
|
PA0 UART4_TX UART4
|
|
PA1 UART4_RX UART4
|
|
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_MSP_DisplayPort
|
|
|
|
# UART5
|
|
PC12 UART5_TX UART5 NODMA
|
|
PD2 UART5_RX UART5 NODMA
|
|
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_GPS
|
|
|
|
# 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
|
|
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
|
|
|
|
# Servos
|
|
PB1 TIM3_CH4 TIM3 PWM(10) GPIO(70) NODMA # S1 / M10
|
|
PB0 TIM3_CH3 TIM3 PWM(11) GPIO(72) NODMA # S2 / M11
|
|
|
|
# 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_ON 0
|
|
|
|
# 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
|
|
|
|
# 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
|