mirror of https://github.com/ArduPilot/ardupilot
123 lines
2.6 KiB
Plaintext
123 lines
2.6 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# Omnibus F4 PRO, Omnibus F4 V3 boards
|
|
# with F405 mcu, mpu6000 imu, bmp280 barometer, 7456 series osd and sdcard
|
|
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
HAL_CHIBIOS_ARCH_F405 1
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 70
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
STM32_PLLM_VALUE 8
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
# flash size
|
|
FLASH_SIZE_KB 1024
|
|
FLASH_RESERVE_START_KB 64
|
|
|
|
CCM_RAM_SIZE_KB 64
|
|
RAM_SIZE_KB 128
|
|
|
|
# order of I2C buses
|
|
I2C_ORDER I2C2
|
|
|
|
# order of UARTs
|
|
UART_ORDER OTG1 USART6 USART1
|
|
|
|
#adc
|
|
PC1 BAT_CURR_SENS ADC1 SCALE(1)
|
|
PC2 BAT_VOLT_SENS ADC1 SCALE(1)
|
|
PA0 RSSI_IN ADC1
|
|
|
|
#pwm output
|
|
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(26)
|
|
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(27)
|
|
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(17)
|
|
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(16)
|
|
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(15)
|
|
PA8 TIM1_CH1 TIM1 PWM(6) GPIO(41)
|
|
|
|
PA4 MPU6000_CS CS
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
PB10 I2C2_SCL I2C2
|
|
PB11 I2C2_SDA I2C2
|
|
|
|
PB15 SPI2_MOSI SPI2
|
|
PB14 SPI2_MISO SPI2
|
|
PB13 SPI2_SCK SPI2
|
|
PB12 SDCARD_CS CS
|
|
|
|
PA10 USART1_RX USART1
|
|
PA9 USART1_TX USART1
|
|
|
|
PC6 USART6_TX USART6
|
|
PC7 USART6_RX USART6
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
PA15 OSD_CS CS
|
|
PB3 BMP280_CS CS
|
|
PC12 SPI3_MOSI SPI3
|
|
PC11 SPI3_MISO SPI3
|
|
PC10 SPI3_SCK SPI3
|
|
|
|
PB5 LED OUTPUT HIGH GPIO(57)
|
|
PB4 TIM3_CH1 TIM3 GPIO(56) ALARM
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
PC5 VBUS INPUT OPENDRAIN
|
|
|
|
# "PPM" solder pad/resistor should be soldered and "S-BUS" resistor/solder pad removed
|
|
# Overwise UART1 or UART6 or RCIN will not work
|
|
PB8 TIM4_CH3 TIM4 RCININT PULLDOWN LOW
|
|
|
|
#Omnibus F4 V3 and later had hw inverter on UART6
|
|
#Overide it to use as GPS UART port
|
|
PC8 SBUS_INVERT OUTPUT LOW
|
|
|
|
# SPI Device table
|
|
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 8*MHZ
|
|
SPIDEV sdcard SPI2 DEVID2 SDCARD_CS MODE3 1*MHZ 16*MHZ
|
|
SPIDEV bmp280 SPI3 DEVID3 BMP280_CS MODE3 1*MHZ 8*MHZ
|
|
SPIDEV osd SPI3 DEVID4 OSD_CS MODE0 1*MHZ 4*MHZ
|
|
|
|
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSF4PRO
|
|
|
|
define HAL_INS_DEFAULT HAL_INS_MPU60XX_SPI
|
|
define HAL_INS_DEFAULT_ROTATION ROTATION_YAW_180
|
|
|
|
define HAL_BARO_DEFAULT HAL_BARO_BMP280_SPI
|
|
define HAL_BARO_BMP280_NAME "bmp280"
|
|
|
|
define HAL_COMPASS_DEFAULT HAL_COMPASS_HMC5843
|
|
define HAL_COMPASS_HMC5843_I2C_BUS 0
|
|
define HAL_COMPASS_HMC5843_I2C_ADDR 0x1E
|
|
|
|
define STORAGE_FLASH_PAGE 1
|
|
define HAL_STORAGE_SIZE 8192
|
|
|
|
# define default battery setup
|
|
define HAL_BATT_VOLT_PIN 12
|
|
define HAL_BATT_CURR_PIN 11
|
|
define HAL_BATT_VOLT_SCALE 11
|
|
define HAL_BATT_CURR_SCALE 18.2
|
|
|
|
define HAL_GPIO_A_LED_PIN 57
|
|
|
|
#To complementary channels work we define this
|
|
define STM32_PWM_USE_ADVANCED TRUE
|
|
|
|
define BOARD_PWM_COUNT_DEFAULT 6
|