You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
153 lines
3.1 KiB
153 lines
3.1 KiB
# hw definition file for KakuteF4 hardware |
|
|
|
|
|
|
|
# MCU class and specific type |
|
MCU STM32F4xx STM32F405xx |
|
|
|
# Betaflight motor order for copter |
|
define HAL_FRAME_TYPE_DEFAULT 12 |
|
|
|
# board ID for firmware load |
|
APJ_BOARD_ID 122 |
|
|
|
# crystal frequency |
|
OSCILLATOR_HZ 8000000 |
|
|
|
define STM32_ST_USE_TIMER 4 |
|
define CH_CFG_ST_RESOLUTION 16 |
|
|
|
FLASH_SIZE_KB 1024 |
|
|
|
|
|
# only one I2C bus |
|
I2C_ORDER I2C1 |
|
|
|
# LEDs |
|
PB5 LED_BLUE OUTPUT LOW GPIO(0) |
|
|
|
# buzzer |
|
PC9 BUZZER OUTPUT GPIO(80) LOW |
|
define HAL_BUZZER_PIN 80 |
|
define HAL_BUZZER_ON 1 |
|
define HAL_BUZZER_OFF 0 |
|
|
|
# spi1 bus for IMU |
|
PA5 SPI1_SCK SPI1 |
|
PA6 SPI1_MISO SPI1 |
|
PA7 SPI1_MOSI SPI1 |
|
|
|
# spi3 for dataflash and OSD |
|
PC10 SPI3_SCK SPI3 |
|
PC11 SPI3_MISO SPI3 |
|
PC12 SPI3_MOSI SPI3 |
|
PB14 MAX7456_CS CS |
|
|
|
# dataflash M25P16 |
|
PB3 FLASH_CS CS |
|
|
|
PC4 ICM20689_CS CS |
|
PC5 ICM20689_DRDY INPUT |
|
|
|
# only one I2C bus in normal config |
|
PB8 I2C1_SCL I2C1 |
|
PB9 I2C1_SDA I2C1 |
|
|
|
# analog pins |
|
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1) |
|
PC2 BATT_CURRENT_SENS ADC1 SCALE(1) |
|
|
|
# RSSI analog input |
|
PC1 RSSI_ADC_PIN ADC1 SCALE(1) |
|
define BOARD_RSSI_ANA_PIN 11 |
|
|
|
# define default battery setup |
|
define HAL_BATT_VOLT_PIN 13 |
|
define HAL_BATT_CURR_PIN 12 |
|
define HAL_BATT_VOLT_SCALE 10.1 |
|
define HAL_BATT_CURR_SCALE 17.0 |
|
|
|
# order of UARTs (and USB) |
|
SERIAL_ORDER OTG1 USART6 USART1 UART4 UART5 USART3 |
|
|
|
# rcinput is PB11 |
|
PB11 TIM2_CH4 TIM2 RCININT FLOAT LOW |
|
PB10 USART3_TX USART3 |
|
|
|
# SBUS inversion control pin, active low |
|
PB15 SBUS_INVERT OUTPUT LOW |
|
|
|
# for FrSky S.PORT. Has builtin inverters and diode to combine |
|
# RX and TX onto the one pin |
|
PA9 USART1_TX USART1 |
|
PA10 USART1_RX USART1 |
|
|
|
# default Serial2 to FrSky telemetry |
|
define HAL_SERIAL2_PROTOCOL 10 |
|
|
|
# USART6, telem1, SERIAL1 |
|
PC6 USART6_TX USART6 |
|
PC7 USART6_RX USART6 |
|
|
|
# UART4 (GPS), SERIAL3 |
|
PA1 UART4_RX UART4 NODMA |
|
PA0 UART4_TX UART4 NODMA |
|
|
|
# UART5 (ESC telemetry sensor), SERIAL4 |
|
PD2 UART5_RX UART5 |
|
|
|
PA11 OTG_FS_DM OTG1 |
|
PA12 OTG_FS_DP OTG1 |
|
|
|
# USB detection |
|
PA8 VBUS INPUT OPENDRAIN |
|
|
|
# debug |
|
PA13 JTMS-SWDIO SWD |
|
PA14 JTCK-SWCLK SWD |
|
|
|
# PWM out pins. Note that channel order follows the ArduPilot motor |
|
# order conventions |
|
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) |
|
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) |
|
PA3 TIM5_CH4 TIM5 PWM(3) GPIO(52) |
|
PA2 TIM5_CH3 TIM5 PWM(4) GPIO(53) |
|
|
|
PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54) # LED strip |
|
define HAL_NEOPIXEL_COUNT 8 |
|
|
|
define HAL_STORAGE_SIZE 15360 |
|
define STORAGE_FLASH_PAGE 2 |
|
|
|
# reserve 32k for bootloader and 32k for flash storage |
|
FLASH_RESERVE_START_KB 64 |
|
|
|
# no built-in compass, but probe the i2c bus for all possible |
|
# external compass types |
|
define ALLOW_ARM_NO_COMPASS |
|
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE |
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES |
|
define HAL_I2C_INTERNAL_MASK 0 |
|
define HAL_COMPASS_AUTO_ROT_DEFAULT 2 |
|
|
|
# SPI devices |
|
SPIDEV mpu6000 SPI1 DEVID1 ICM20689_CS MODE3 1*MHZ 8*MHZ |
|
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ |
|
SPIDEV osd SPI3 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ |
|
|
|
# one IMU |
|
IMU Invensense SPI:mpu6000 ROTATION_YAW_180 |
|
|
|
# one baro |
|
BARO BMP280 I2C:0:0x76 |
|
|
|
# enable logging to dataflash |
|
define HAL_LOGGING_DATAFLASH |
|
|
|
# setup for OSD |
|
define OSD_ENABLED 1 |
|
define HAL_OSD_TYPE_DEFAULT 1 |
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin |
|
|
|
# 8 PWM available by default |
|
define BOARD_PWM_COUNT_DEFAULT 8
|
|
|