mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
071dca8fe8
This makes the default orientation match betaflight (i.e. USB connector top of the board at the front, ESC connector bottom of the board to the rear).
140 lines
2.9 KiB
Plaintext
140 lines
2.9 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# Omnibus F4 Nano V6 only
|
|
# with F405 mcu, mpu6000 imu, bmp280 barometer, 7456 series osd, no flash log storage
|
|
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 133
|
|
|
|
# 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
|
|
|
|
# order of I2C buses
|
|
I2C_ORDER I2C2
|
|
|
|
# order of UARTs
|
|
UART_ORDER OTG1 USART6 USART1 UART4
|
|
|
|
#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(50)
|
|
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51)
|
|
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
|
|
PB5 TIM3_CH2 TIM3 PWM(4) GPIO(53)
|
|
|
|
|
|
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
|
|
|
|
PB15 SPI2_MOSI SPI2
|
|
PB14 SPI2_MISO SPI2
|
|
PB13 SPI2_SCK SPI2
|
|
|
|
|
|
PA10 USART1_RX USART1
|
|
PA9 USART1_TX USART1
|
|
|
|
PC6 USART6_TX USART6
|
|
PC7 USART6_RX USART6
|
|
|
|
# UART4 (ESC sensor)
|
|
PA1 UART4_RX UART4
|
|
|
|
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
|
|
|
|
PA8 LED OUTPUT HIGH GPIO(41)
|
|
#PB4 TIM3_CH1 TIM3 GPIO(70) ALARM
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
PC5 VBUS INPUT OPENDRAIN
|
|
|
|
#LED strip output pad used for RC input
|
|
PB6 TIM4_CH1 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_RX OUTPUT LOW
|
|
PC9 SBUS_INVERT_TX OUTPUT LOW
|
|
|
|
# SPI Device table
|
|
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 8*MHZ
|
|
SPIDEV bmp280 SPI3 DEVID3 BMP280_CS MODE3 1*MHZ 8*MHZ
|
|
SPIDEV osd SPI3 DEVID4 OSD_CS MODE0 10*MHZ 10*MHZ
|
|
|
|
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSNANOV6
|
|
|
|
define HAL_INS_DEFAULT HAL_INS_MPU60XX_SPI
|
|
define HAL_INS_DEFAULT_ROTATION ROTATION_YAW_90
|
|
|
|
define HAL_BARO_DEFAULT HAL_BARO_BMP280_SPI
|
|
define HAL_BARO_BMP280_NAME "bmp280"
|
|
|
|
# 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 STORAGE_FLASH_PAGE 1
|
|
define HAL_STORAGE_SIZE 15360
|
|
|
|
|
|
# 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
|
|
|
|
#analog rssi pin (also could be used as analog airspeed input)
|
|
#PA0 - ADC123_CH0
|
|
define BOARD_RSSI_ANA_PIN 0
|
|
|
|
|
|
define HAL_GPIO_A_LED_PIN 41
|
|
|
|
define OSD_ENABLED ENABLED
|
|
define HAL_OSD_TYPE_DEFAULT 1
|
|
|
|
#To complementary channels work we define this
|
|
define STM32_PWM_USE_ADVANCED TRUE
|
|
|
|
define BOARD_PWM_COUNT_DEFAULT 4
|
|
|
|
#define CH_DBG_ENABLE_ASSERTS TRUE
|
|
#define CH_DBG_ENABLE_CHECKS TRUE
|
|
#define CH_DBG_SYSTEM_STATE_CHECK TRUE
|
|
#define CH_DBG_ENABLE_STACK_CHECK TRUE
|
|
|
|
#font for the osd
|
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|