mirror of https://github.com/ArduPilot/ardupilot
197 lines
4.4 KiB
Plaintext
197 lines
4.4 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# F405AIO, developed by Robin Luo
|
|
|
|
#################################################
|
|
### MCU CONFIGURATION ###
|
|
#################################################
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1116
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
define STM32_ST_USE_TIMER 5
|
|
define CH_CFG_ST_RESOLUTION 32
|
|
|
|
# reserve 16k for bootloader, 16k for OSD and 32k for flash storage
|
|
FLASH_RESERVE_START_KB 64
|
|
FLASH_SIZE_KB 1024
|
|
|
|
#define HAL_STORAGE_SIZE 16384
|
|
define HAL_STORAGE_SIZE 15360
|
|
STORAGE_FLASH_PAGE 1
|
|
|
|
# enable FLASH/RAMTROM parameter storage
|
|
#define HAL_WITH_DATAFLASH 1
|
|
# enable logging to dataflash
|
|
#define HAL_LOGGING_DATAFLASH_ENABLED 1
|
|
|
|
# order of UARTs
|
|
# | sr0| sr1 | sr2 | GPS |
|
|
SERIAL_ORDER OTG1 USART1 USART3 UART4 USART6 USART2
|
|
|
|
#################################################
|
|
### PIN DEFINITIONS ###
|
|
#################################################
|
|
|
|
PA0 UART4_TX UART4
|
|
PA1 UART4_RX UART4
|
|
|
|
PA9 USART1_TX USART1
|
|
PA10 USART1_RX USART1
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
PC6 USART6_TX USART6
|
|
PC7 USART6_RX USART6
|
|
|
|
PB10 USART3_TX USART3
|
|
PB11 USART3_RX USART3
|
|
|
|
# default to timer for RC input
|
|
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN LOW
|
|
|
|
# alternative using USART2
|
|
PA2 USART2_TX USART2 NODMA
|
|
PA3 USART2_RX USART2 NODMA ALT(1)
|
|
|
|
|
|
# IMU SPI
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
PA4 GYRO1_CS CS
|
|
PC3 GYRO2_CS CS
|
|
PC4 GYRO1_DRDY INPUT
|
|
PB2 GYRO2_DRDY INPUT
|
|
|
|
# SD CARD SPI
|
|
PC10 SPI3_SCK SPI3
|
|
PC11 SPI3_MISO SPI3
|
|
PC12 SPI3_MOSI SPI3
|
|
PD2 SDCARD_CS CS
|
|
PA14 FLASH_CS CS
|
|
|
|
# MAG SPI
|
|
PB13 SPI2_SCK SPI2
|
|
PB14 SPI2_MISO SPI2
|
|
PB15 SPI2_MOSI SPI2
|
|
PB12 MAG_CS CS
|
|
PC5 MAG_DRDY INPUT
|
|
PA8 ESPI_CS CS
|
|
|
|
# I2C1
|
|
PB6 I2C1_SCL I2C1
|
|
PB7 I2C1_SDA I2C1
|
|
|
|
#define HAL_USE_I2C TRUE
|
|
#define STM32_I2C_USE_I2C1 TRUE
|
|
# I2C Buses
|
|
I2C_ORDER I2C1
|
|
#define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
|
|
|
# CAN
|
|
PB8 CAN1_RX CAN1
|
|
PB9 CAN1_TX CAN1
|
|
# CAN Buses
|
|
#CAN_ORDER 1
|
|
|
|
# reduce memory usage
|
|
define UAVCAN_NODE_POOL_SIZE 1024
|
|
|
|
PC0 RSSI_ADC_PIN ADC1 SCALE(1)
|
|
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
|
|
PC14 LED_BLUE OUTPUT LOW GPIO(0)
|
|
PA13 LED_GREEN OUTPUT LOW GPIO(1)
|
|
PC15 LED_RED OUTPUT LOW GPIO(2)
|
|
|
|
define AP_NOTIFY_GPIO_LED_3_ENABLED 1
|
|
define HAL_GPIO_A_LED_PIN 0
|
|
define HAL_GPIO_B_LED_PIN 1
|
|
define HAL_GPIO_C_LED_PIN 2
|
|
|
|
|
|
#pwm output
|
|
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50)
|
|
PB5 TIM3_CH2 TIM3 PWM(2) GPIO(51)
|
|
PB4 TIM3_CH1 TIM3 PWM(3) GPIO(52)
|
|
PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53)
|
|
PB3 TIM2_CH2 TIM2 PWM(5) GPIO(54)
|
|
PA15 TIM2_CH1 TIM2 PWM(6) GPIO(55)
|
|
PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56)
|
|
PC9 TIM8_CH4 TIM8 PWM(8) GPIO(57)
|
|
#PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58)
|
|
#PA2 TIM2_CH3 TIM2 PWM(10) GPIO(59)
|
|
|
|
PC13 VBUS INPUT OPENDRAIN
|
|
|
|
# default to all pins low to avoid ESD issues
|
|
DEFAULTGPIO OUTPUT LOW PULLDOWN
|
|
|
|
#################################################
|
|
### DEVICES ###
|
|
#################################################
|
|
|
|
# BMI160 on SPI1
|
|
SPIDEV bmi160 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 4*MHZ
|
|
# ICM42688 on SPI1
|
|
SPIDEV icm42688 SPI1 DEVID2 GYRO2_CS MODE3 1*MHZ 4*MHZ
|
|
# QMI8658 on SPI1
|
|
#SPIDEV LSM6DSL SPI1 DEVID2 GYRO2_CS MODE3 1*MHZ 4*MHZ
|
|
|
|
# MAG on SPI2
|
|
SPIDEV lis3mdl SPI2 DEVID3 MAG_CS MODE3 500*KHZ 500*KHZ
|
|
#SPIDEV lis3mdl SPI2 DEVID6 MAG_CS MODE3 500*KHZ 500*KHZ
|
|
|
|
# SD Card on SPI3
|
|
SPIDEV sdcard SPI3 DEVID4 SDCARD_CS MODE3 400*KHZ 25*MHZ
|
|
|
|
# Flash Card on SPI3
|
|
SPIDEV dataflash SPI3 DEVID5 FLASH_CS MODE3 500*KHZ 25*MHZ
|
|
|
|
# two IMU
|
|
IMU BMI160 SPI:bmi160 ROTATION_ROLL_180_YAW_270
|
|
IMU Invensensev3 SPI:icm42688 ROTATION_NONE
|
|
#IMU LSM6DSL SPI:lsm6dsl ROTATION_ROLL_180
|
|
|
|
# one baro, multiple possible choices for different board variants
|
|
BARO BMP280 I2C:0:0x76
|
|
|
|
# one mag
|
|
COMPASS LIS3MDL SPI:lis3mdl false ROTATION_ROLL_180_YAW_90
|
|
|
|
|
|
define HAL_OS_FATFS_IO 1
|
|
|
|
# define default battery setup
|
|
define HAL_BATT_MONITOR_DEFAULT 4
|
|
define HAL_BATT_VOLT_PIN 12
|
|
define HAL_BATT_CURR_PIN 11
|
|
define HAL_BATT_VOLT_SCALE 9.2
|
|
define HAL_BATT_CURR_SCALE 50.0
|
|
|
|
#analog rssi pin (also could be used as analog airspeed input)
|
|
# PC0 - ADC1_CH10
|
|
define BOARD_RSSI_ANA_PIN 10
|
|
|
|
# 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 OSD_ENABLED 0
|
|
|
|
|
|
# --------------------- save flash ----------------------
|
|
include ../include/minimize_features.inc
|
|
|