mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 14:13:42 -04:00
eca8cf3414
move to single OSD font on some boards this saves about 12k on these boards. They were also extremely close to overflowing flash, under 2k on some Now that we support having an OSD font on the microSD card (where available) we can reduce built in fonts without a large functionality impact This also disables some less used features on these boards: - generator support - object avoidance path planning - precision landing This will give us some breathing room on these boards
143 lines
3.0 KiB
Plaintext
143 lines
3.0 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# for iFlight Beast F7 hardware.
|
|
# thanks to betaflight for pin information
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F7xx STM32F745xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1026
|
|
|
|
# crystal frequency, setup to use external oscillator
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
FLASH_SIZE_KB 1024
|
|
|
|
# bootloader takes first sector
|
|
FLASH_RESERVE_START_KB 96
|
|
|
|
# only one I2C bus
|
|
I2C_ORDER I2C1
|
|
|
|
# order of UARTs (and USB)
|
|
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY EMPTY UART7
|
|
|
|
# Buzzer - DMA timer channel use by LEDs
|
|
#PD15 TIM4_CH4 TIM4 GPIO(80) ALARM
|
|
PD15 BUZZER OUTPUT GPIO(80) LOW
|
|
define HAL_BUZZER_PIN 80
|
|
define HAL_BUZZER_ON 1
|
|
define HAL_BUZZER_OFF 0
|
|
|
|
# USB
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# Debug
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# SPI1 for MPU6000
|
|
PA4 MPU6000_CS CS
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
# SPI3 for Flash Storage 16mb
|
|
PA15 FLASH_CS CS
|
|
PC10 SPI3_SCK SPI3
|
|
PC11 SPI3_MISO SPI3
|
|
PC12 SPI3_MOSI SPI3
|
|
|
|
# SPI4 for OSD
|
|
PE4 AT7456E_CS CS
|
|
PE2 SPI4_SCK SPI4
|
|
PE5 SPI4_MISO SPI4
|
|
PE6 SPI4_MOSI SPI4
|
|
|
|
# I2C1 for baro
|
|
PB8 I2C1_SCL I2C1 PULLUP
|
|
PB9 I2C1_SDA I2C1 PULLUP
|
|
|
|
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
# define default battery setup
|
|
define HAL_BATT_VOLT_PIN 13
|
|
define HAL_BATT_CURR_PIN 12
|
|
define HAL_BATT_VOLT_SCALE 10.9
|
|
define HAL_BATT_CURR_SCALE 100
|
|
define HAL_BATT_MONITOR_DEFAULT 4
|
|
|
|
PC5 RSSI_ADC ADC1
|
|
|
|
# USART1 - RCIN
|
|
PA10 USART1_RX USART1
|
|
PA9 USART1_TX USART1
|
|
|
|
# USART2 (DJI)
|
|
PA2 USART2_TX USART2
|
|
PA3 USART2_RX USART2 NODMA
|
|
|
|
# USART3 (DJI RCIN)
|
|
PB11 USART3_RX USART3
|
|
define HAL_SERIAL3_PROTOCOL SerialProtocol_RCIN
|
|
|
|
# UART4
|
|
PA0 UART4_TX UART4
|
|
PA1 UART4_RX UART4 NODMA
|
|
|
|
# UART7
|
|
PE7 UART7_RX UART7
|
|
PE8 UART7_TX UART7 NODMA
|
|
|
|
# Motors
|
|
PB1 TIM3_CH4 TIM3 PWM(1) GPIO(50) BIDIR # 1
|
|
PE9 TIM1_CH1 TIM1 PWM(2) GPIO(51) # 2
|
|
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR # 3
|
|
PB0 TIM3_CH3 TIM3 PWM(4) GPIO(53) # 4
|
|
|
|
# NeoPixel LED strip
|
|
PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54)
|
|
PC13 LED0 OUTPUT LOW GPIO(90) # Blue LED
|
|
|
|
DMA_PRIORITY USART1* TIM1* TIM3*
|
|
# TIM3_CH4 is shared with TIM3_UP
|
|
DMA_NOSHARE SPI3* TIM1_CH2
|
|
|
|
define HAL_STORAGE_SIZE 16384
|
|
define STORAGE_FLASH_PAGE 1
|
|
|
|
# enable logging to dataflash
|
|
define HAL_LOGGING_DATAFLASH
|
|
|
|
# spi devices
|
|
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ
|
|
SPIDEV dataflash SPI3 DEVID2 FLASH_CS MODE3 32*MHZ 32*MHZ
|
|
SPIDEV osd SPI4 DEVID4 AT7456E_CS MODE0 10*MHZ 10*MHZ
|
|
|
|
# no built-in compass and no external I2C so no compass
|
|
define ALLOW_ARM_NO_COMPASS
|
|
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
|
define HAL_I2C_INTERNAL_MASK 0
|
|
|
|
# one IMU
|
|
IMU Invensense SPI:mpu6000 ROTATION_YAW_270
|
|
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
|
|
|
# one BARO
|
|
BARO BMP280 I2C:0:0x76
|
|
|
|
# setup for OSD
|
|
define OSD_ENABLED 1
|
|
define HAL_OSD_TYPE_DEFAULT 1
|
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
|
|
|
|
define BOARD_PWM_COUNT_DEFAULT 5
|
|
define STM32_PWM_USE_ADVANCED TRUE
|
|
|
|
# save some flash
|
|
define GENERATOR_ENABLED 0
|
|
define AC_OAPATHPLANNER_ENABLED 0
|
|
define PRECISION_LANDING 0
|