mirror of https://github.com/ArduPilot/ardupilot
171 lines
4.2 KiB
Plaintext
171 lines
4.2 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# Omnibus F4 PRO with on-board current sensor
|
|
# with F405 mcu, mpu6000 and bmi270 imu, bmp280 barometer, 7456 series osd and sdcard
|
|
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
HAL_CHIBIOS_ARCH_F405 1
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 131
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
# flash size
|
|
FLASH_SIZE_KB 1024
|
|
FLASH_RESERVE_START_KB 64
|
|
|
|
# order of I2C buses
|
|
I2C_ORDER I2C2
|
|
|
|
# order of UARTs
|
|
SERIAL_ORDER OTG1 USART1 USART3 USART6 UART4
|
|
|
|
#adc
|
|
PC1 BAT_CURR_SENS ADC1 SCALE(1)
|
|
PC2 BAT_VOLT_SENS ADC1 SCALE(1)
|
|
|
|
#analog rssi pin (also could be used as analog airspeed input)
|
|
PA0 RSSI_IN ADC1
|
|
define BOARD_RSSI_ANA_PIN 0
|
|
|
|
#pwm output. 1 - 4 on main header, 5 & 6 on separated header w/o 5V supply, 7 & 8 on CH5 and CH6 pads
|
|
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50)
|
|
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51)
|
|
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
|
|
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53)
|
|
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(54)
|
|
PA8 TIM1_CH1 TIM1 PWM(6) GPIO(55)
|
|
PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56)
|
|
PC9 TIM8_CH4 TIM8 PWM(8) GPIO(59)
|
|
|
|
PA4 MPU6000_CS CS
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
# note that this board needs PULLUP on I2C pins
|
|
PB10 I2C2_SCL I2C2 PULLUP
|
|
PB11 I2C2_SDA I2C2 PULLUP
|
|
|
|
# use I2C pins as USART3 (SERIAL2) in BRD_ALT_CONFIG=1 & 4
|
|
PB10 USART3_TX USART3 ALT(1)
|
|
PB11 USART3_RX USART3 ALT(1)
|
|
PB10 USART3_TX USART3 ALT(4)
|
|
PB11 USART3_RX USART3 ALT(4)
|
|
|
|
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
|
|
|
|
# UART4 TX available as an alternative config on PA0 (RSSI pad) with BRD_ALT_CONFIG=2
|
|
PA0 UART4_TX UART4 ALT(2)
|
|
|
|
# full UART4 also available as alt config on PA0 (RSSI pad) and PA1 (PWM output chan 5) with BRD_ALT_CONFIG=3 & 4
|
|
PA0 UART4_TX UART4 ALT(3)
|
|
PA1 UART4_RX UART4 ALT(3)
|
|
PA0 UART4_TX UART4 ALT(4)
|
|
PA1 UART4_RX UART4 ALT(4)
|
|
|
|
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_BLUE OUTPUT LOW GPIO(1)
|
|
define HAL_GPIO_A_LED_PIN 1
|
|
|
|
#dummy assignment required to allow AP_NOTIFY to use board led
|
|
define HAL_GPIO_B_LED_PIN 2
|
|
|
|
PB4 TIM3_CH1 TIM3 GPIO(58) ALARM LOW
|
|
|
|
#use LED-STRIP output as general purpose GPIO
|
|
PB6 GP_GPIO OUTPUT LOW GPIO(70)
|
|
|
|
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
|
|
|
|
|
|
# SPI Device table
|
|
SPIDEV bmi270 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 10*MHZ
|
|
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 8*MHZ
|
|
SPIDEV sdcard SPI2 DEVID2 SDCARD_CS MODE0 400*KHZ 25*MHZ
|
|
SPIDEV bmp280 SPI3 DEVID3 BMP280_CS MODE3 1*MHZ 8*MHZ
|
|
SPIDEV osd SPI3 DEVID4 OSD_CS MODE0 10*MHZ 10*MHZ
|
|
|
|
# one IMU BMI270 or MPU6000
|
|
IMU Invensense SPI:mpu6000 ROTATION_YAW_180
|
|
IMU BMI270 SPI:bmi270 ROTATION_ROLL_180
|
|
|
|
|
|
# one baro
|
|
BARO BMP280 SPI:bmp280
|
|
define AP_BARO_BACKEND_DEFAULT_ENABLED 0
|
|
define AP_BARO_BMP280_ENABLED 1
|
|
|
|
# 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
|
|
|
|
STORAGE_FLASH_PAGE 1
|
|
define HAL_STORAGE_SIZE 15360
|
|
|
|
define HAL_OS_FATFS_IO 1
|
|
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
|
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|
|
|
# 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 OSD_ENABLED 1
|
|
define HAL_OSD_TYPE_DEFAULT 1
|
|
|
|
#To complementary channels work we define this
|
|
define STM32_PWM_USE_ADVANCED TRUE
|
|
|
|
#font for the osd
|
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
|
|
|
|
# disable SMBUS monitors to save flash
|
|
define AP_BATTERY_SMBUS_ENABLED 0
|
|
|
|
# disable parachute and sprayer to save flash
|
|
define HAL_PARACHUTE_ENABLED 0
|
|
define HAL_SPRAYER_ENABLED 0
|
|
|
|
# reduce max size of embedded params for apj_tool.py
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
|
|
|
# save some flash
|
|
include ../include/save_some_flash.inc
|
|
define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 0
|
|
|
|
# only include ublox GPS driver
|
|
include ../include/minimal_GPS.inc
|