ardupilot/libraries/AP_HAL_ChibiOS/hwdef/OMNIBUSF7V2-bdshot/hwdef.dat
Andy Piper 401e5c2073 AP_HAL_ChibiOS: add support for bidir DShot support in RCOutput
add support for sampling GPIO pins using timer
don't restart pwm group when not doing bi-dir
fix hwdef generation preproc for TIM DMA
decode telemetry at the start of the dshot cycle
calculate dshot pulse separation correctly and ensure we output rapidly enough
calculate dshot min periods and timeouts correctly
refactor dshot_send() into dshot_send_groups()
use bi-dir dshot channel mask
selectively enable bi-dir RC Channels
process bi-dir mask correctly when allocating DMA channels
allow UP and CH DMA channel sharing
optionally enable bidir vars in hwdef.

enable bi-dir dshot in KakuteF7Mini
enable bi-dir dshot in OmnibusF4Pro
enable bi-dir dshot in OmnibusNanoV6
enable bi-dir dshot in MatekF405
enable bi-dir dshot in fmuv5
enable bi-dir dshot in fmuv3
enable bi-dir dshot in OmnibusF7V2
enable bi-dir dshot in OmnibusNanoV6
enable bi-dir dshot in CubeOrange
enable bi-dir dshot in Pixracer
enable bi-dir dshot in mRoPixracerPro

Co-authored-by: bugobliterator <siddharthbharatpurohit@gmail.com>
2020-12-30 19:14:16 +11:00

146 lines
3.1 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
# for OMNIBUSF7V2 hardware.
@ thanks to betaflight for pin information
# MCU class and specific type
MCU STM32F7xx STM32F745xx
# board ID for firmware load
APJ_BOARD_ID 121
# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000
FLASH_SIZE_KB 1024
# reserve one sector for bootloader and 2 for storage
FLASH_RESERVE_START_KB 96
# only one I2C bus
I2C_ORDER I2C2
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART1 USART3 USART6 USART2 UART7
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PE0 LED0 OUTPUT LOW
PD15 TIM4_CH4 TIM4 GPIO(57) ALARM
# ICM-20608 on SPI1
PA4 MPU6000_CS CS
# MPU6500 on SPI3
PA15 MPU6500_CS CS
# SPI1 for IMU and baro
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# SPI2 for MAX7456 OSD
PB12 MAX7456_CS CS
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PC12 SPI3_MOSI SPI3
# SPI4 for SDCard
PE4 SDCARD_CS CS
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
# external I2C device2, pins shared with USART3, normally disabled
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# baro is BMP280 on SPI1
PA1 BMP280_CS CS
# mag is on I2C if connected
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
PC5 RSSI_ADC ADC1
# setup two IMUs
IMU Invensense SPI:mpu6000 ROTATION_NONE
IMU Invensense SPI:mpu6500 ROTATION_YAW_90
# USART1
PA10 USART1_RX USART1
PA9 USART1_TX USART1
# RC input using timer by default
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN
# alternative RC input using USART2
PA3 USART2_RX USART2 NODMA ALT(1)
# USART3, enabled as ALT config in place of I2C
PB10 USART3_TX USART3 ALT(2)
PB11 USART3_RX USART3 ALT(2)
# USART6
PC7 USART6_RX USART6
PC6 USART6_TX USART6
# UART7 (V2 version, ESC telem)
PE7 UART7_RX UART7
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50)
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) BIDIR
PE9 TIM1_CH1 TIM1 PWM(3) GPIO(52) BIDIR
PE11 TIM1_CH2 TIM1 PWM(4) GPIO(53)
DMA_PRIORITY ADC* USART6* TIM1_CH1 TIM3_CH4 TIM1_UP TIM3_UP SPI4* SPI1*
define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 1
# spi devices
SPIDEV bmp280 SPI1 DEVID1 BMP280_CS MODE3 1*MHZ 8*MHZ
SPIDEV mpu6000 SPI1 DEVID2 MPU6000_CS MODE3 1*MHZ 4*MHZ
SPIDEV mpu6500 SPI3 DEVID1 MPU6500_CS MODE3 1*MHZ 4*MHZ
SPIDEV sdcard SPI4 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
SPIDEV osd SPI2 DEVID1 MAX7456_CS MODE0 10*MHZ 10*MHZ
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# 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 HAL_COMPASS_AUTO_ROT_DEFAULT 2
# disable SMBUS and fuel battery monitors to save flash
define HAL_BATTMON_SMBUS_ENABLE 0
define HAL_BATTMON_FUEL_ENABLE 0
# disable parachute and sprayer to save flash
define HAL_PARACHUTE_ENABLED 0
define HAL_SPRAYER_ENABLED 0
# one baro
BARO BMP280 SPI:bmp280
define OSD_ENABLED 1
define OSD_PARAM_ENABLED 0
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin