mirror of https://github.com/ArduPilot/ardupilot
232 lines
5.8 KiB
Plaintext
232 lines
5.8 KiB
Plaintext
# hw definition file for processing by chibios_hwdef.py
|
|
# for QioTekZealotF427 hardware from Qio-tek.com
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F427xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1021
|
|
|
|
FLASH_SIZE_KB 2048
|
|
|
|
env OPTIMIZE -O2
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 24000000
|
|
|
|
# this is the STM32 timer that ChibiOS will use for the low level
|
|
# driver. This must be a 32 bit timer. We currently only support
|
|
# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details
|
|
|
|
# ChibiOS system timer
|
|
STM32_ST_USE_TIMER 5
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
|
|
# this is the pin that senses USB being connected. It is an input pin
|
|
# setup as OPENDRAIN
|
|
PA9 VBUS INPUT OPENDRAIN
|
|
|
|
# The normal usage of this ordering is:
|
|
# 1) SERIAL0: console (primary mavlink, usually USB)
|
|
# 2) SERIAL1: telem1
|
|
# 3) SERIAL2: telem2 (recommend ESP8266)
|
|
# 4) SERIAL3: primary GPS
|
|
# 5) SERIAL4: telem3 or GPS2
|
|
# 6) SERIAL5: extra UART or sbus output (usually RTOS debug console)
|
|
|
|
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5
|
|
|
|
# UART1
|
|
PB6 USART1_TX USART1
|
|
PB7 USART1_RX USART1
|
|
|
|
# USART2 for Mavlink2 wifi module set baudrate to 921600
|
|
PD5 USART2_TX USART2 NODMA
|
|
PD6 USART2_RX USART2
|
|
|
|
define HAL_SERIAL2_PROTOCOL SerialProtocol_MAVLink2
|
|
define HAL_SERIAL2_BAUD 921600
|
|
|
|
# USART3 for gps1
|
|
PD8 USART3_TX USART3 NODMA
|
|
PD9 USART3_RX USART3
|
|
|
|
# UART4
|
|
PC10 UART4_TX UART4 NODMA
|
|
PC11 UART4_RX UART4 NODMA
|
|
|
|
# UART5
|
|
PC12 UART5_TX UART5 NODMA
|
|
PD2 UART5_RX UART5 NODMA
|
|
|
|
# CAN bus
|
|
PD0 CAN1_RX CAN1
|
|
PD1 CAN1_TX CAN1
|
|
|
|
define HAL_STORAGE_SIZE 16384
|
|
|
|
# SPI1 for IMU Baro OSD
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
PA4 ICM20689_CS CS
|
|
PE10 MAX7456_CS CS
|
|
PB2 ICM20602_CS CS
|
|
PC15 DPS310_CS CS
|
|
PD3 BMI055_G_CS CS
|
|
PD4 BMI055_A_CS CS
|
|
PA8 ICM20649_CS CS
|
|
|
|
# SPI bus for dataflash AND SD
|
|
PB13 SPI2_SCK SPI2
|
|
PB14 SPI2_MISO SPI2
|
|
PB15 SPI2_MOSI SPI2
|
|
|
|
PB12 FRAM_CS CS SPEED_VERYLOW
|
|
PE15 FLASH_CS CS
|
|
|
|
# SPI3 bus for reserve
|
|
PB3 SPI3_SCK SPI3
|
|
PB4 SPI3_MISO SPI3
|
|
PB5 SPI3_MOSI SPI3
|
|
|
|
SPIDEV icm20689 SPI1 DEVID1 ICM20689_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV icm20602 SPI1 DEVID2 ICM20602_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV bmi055_g SPI1 DEVID3 BMI055_G_CS MODE3 10*MHZ 10*MHZ
|
|
SPIDEV bmi055_a SPI1 DEVID4 BMI055_A_CS MODE3 10*MHZ 10*MHZ
|
|
SPIDEV icm20649 SPI1 DEVID5 ICM20649_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV icm42605 SPI1 DEVID5 ICM20649_CS MODE3 2*MHZ 8*MHZ
|
|
SPIDEV dps310 SPI1 DEVID2 DPS310_CS MODE3 5*MHZ 5*MHZ
|
|
SPIDEV osd SPI1 DEVID2 MAX7456_CS MODE0 10*MHZ 10*MHZ
|
|
SPIDEV ramtron SPI2 DEVID2 FRAM_CS MODE3 8*MHZ 8*MHZ
|
|
SPIDEV sdcard SPI2 DEVID3 FLASH_CS MODE0 1*MHZ 8*MHZ
|
|
|
|
# Three IMUs, icm20649 for reserve
|
|
IMU Invensense SPI:icm20689 ROTATION_NONE
|
|
IMU Invensense SPI:icm20602 ROTATION_NONE
|
|
IMU BMI055 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_90
|
|
IMU BMI088 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_90
|
|
IMU Invensensev2 SPI:icm20649 ROTATION_NONE
|
|
IMU Invensensev3 SPI:icm42605 ROTATION_NONE
|
|
|
|
# one baro, check both addressess
|
|
BARO DPS280 SPI:dps310
|
|
BARO MS56XX I2C:0:0x76
|
|
BARO MS56XX I2C:0:0x77
|
|
|
|
|
|
# enable RAMTROM parameter storage
|
|
define HAL_WITH_RAMTRON 1
|
|
# enable FAT filesystem support
|
|
define HAL_OS_FATFS_IO 1
|
|
# now some defines for logging and terrain data files
|
|
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
|
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
|
|
|
# define the order that I2C buses
|
|
I2C_ORDER I2C2 I2C1
|
|
PB8 I2C1_SCL I2C1
|
|
PB9 I2C1_SDA I2C1
|
|
PB10 I2C2_SCL I2C2
|
|
PB11 I2C2_SDA I2C2
|
|
|
|
# look for I2C compass
|
|
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_270
|
|
COMPASS QMC5883L I2C:0:0x0D false ROTATION_ROLL_180_YAW_270
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|
define HAL_I2C_INTERNAL_MASK 1
|
|
|
|
# PWM out pins
|
|
PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50)
|
|
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51)
|
|
PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52)
|
|
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53)
|
|
PE9 TIM1_CH1 TIM1 PWM(5) GPIO(54)
|
|
PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55)
|
|
PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56)
|
|
PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57)
|
|
|
|
PD13 TIM4_CH2 TIM4 PWM(9) GPIO(58)
|
|
PD12 TIM4_CH1 TIM4 PWM(10) GPIO(59)
|
|
PD15 TIM4_CH4 TIM4 PWM(11) GPIO(60)
|
|
PD14 TIM4_CH3 TIM4 PWM(12) GPIO(61)
|
|
PC9 TIM3_CH4 TIM3 PWM(13) GPIO(62) NODMA
|
|
PC8 TIM3_CH3 TIM3 PWM(14) GPIO(63) NODMA
|
|
|
|
PC14 EXTERN_GPIO1 OUTPUT GPIO(1)
|
|
PC13 EXTERN_GPIO2 OUTPUT GPIO(2)
|
|
PE4 EXTERN_GPIO3 OUTPUT GPIO(3)
|
|
PE6 EXTERN_GPIO4 OUTPUT GPIO(4)
|
|
define RELAY1_PIN_DEFAULT 1
|
|
define RELAY2_PIN_DEFAULT 2
|
|
define RELAY3_PIN_DEFAULT 3
|
|
define RELAY4_PIN_DEFAULT 4
|
|
|
|
# also USART6_RX for serial RC
|
|
PC7 TIM8_CH2 TIM8 RCININT PULLUP LOW
|
|
|
|
# LED setup is similar to PixRacer
|
|
define HAL_HAVE_PIXRACER_LED
|
|
PE3 LED_RED OUTPUT GPIO(10)
|
|
PE2 LED_GREEN OUTPUT GPIO(11)
|
|
PE1 LED_BLUE OUTPUT GPIO(12)
|
|
PE0 LED_YELOW OUTPUT GPIO(13)
|
|
|
|
define HAL_GPIO_A_LED_PIN 10
|
|
define HAL_GPIO_B_LED_PIN 11
|
|
define HAL_GPIO_C_LED_PIN 12
|
|
|
|
define HAL_GPIO_LED_ON 0
|
|
define HAL_GPIO_LED_OFF 1
|
|
|
|
# analog in
|
|
PC0 PRESSURE_SENS ADC1 SCALE(2)
|
|
PC1 RSSI_IN ADC1 SCALE(2)
|
|
|
|
# define the primary battery connectors.
|
|
|
|
PC2 BATT_CURRENT_SENS ADC1 SCALE(2)
|
|
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(2)
|
|
PB0 BATT2_CURRENT_SENS ADC1 SCALE(2)
|
|
PB1 BATT2_VOLTAGE_SENS ADC1 SCALE(2)
|
|
PC4 VDD_5V_SENS ADC1 SCALE(2)
|
|
PC5 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(12)
|
|
|
|
define HAL_BATT_VOLT_PIN 13
|
|
define HAL_BATT_CURR_PIN 12
|
|
define HAL_BATT2_VOLT_PIN 9
|
|
define HAL_BATT2_CURR_PIN 8
|
|
define HAL_BATT_VOLT_SCALE 20
|
|
define HAL_BATT_CURR_SCALE 17
|
|
define HAL_BATT2_VOLT_SCALE 20
|
|
define HAL_BATT2_CURR_SCALE 17
|
|
|
|
|
|
define HAL_HAVE_IMU_HEATER 1
|
|
PE12 HEATER_EN OUTPUT LOW GPIO(5)
|
|
define HAL_HEATER_GPIO_PIN 5
|
|
define HAL_IMU_TEMP_DEFAULT 45
|
|
|
|
define HAL_HAVE_SAFETY_SWITCH 1
|
|
PE7 LED_SAFETY OUTPUT
|
|
PE8 SAFETY_IN INPUT PULLDOWN
|
|
PE5 TIM9_CH1 TIM9 ALARM
|
|
|
|
# setup for OSD
|
|
define OSD_ENABLED 1
|
|
define HAL_OSD_TYPE_DEFAULT 1
|
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
|
|
|
# drdy pins
|
|
PA15 DRDY_ICM20689 INPUT
|
|
PA10 DRDY_ICM20602 INPUT
|
|
PD11 DRDY_ICM20649 INPUT
|
|
|
|
define BOARD_PWM_COUNT_DEFAULT 14
|