mirror of https://github.com/ArduPilot/ardupilot
201 lines
4.7 KiB
Plaintext
201 lines
4.7 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# Matek F405-Wing, developed by David Ingraham
|
|
# Board configuration borrowed from Inav F405SE target
|
|
|
|
# Read hwdef/fmuv3/hwdef.dat for more info on these options
|
|
|
|
# SerialX ports are mapped as printed on the top board
|
|
# R1/T1 -> Serial1
|
|
# R2 -> Sbus (T2 not currently used or available)
|
|
# R3/T3 -> Serial3
|
|
# R4/T4 -> Serial4
|
|
# R5/T5 -> Serial5
|
|
# R6/T6 -> Serial6
|
|
|
|
# Note: UART4/Serial4, UART5/Serial5, USART6/Serial6 have no DMA on RX (TX always DMA).
|
|
# If sending highspeed serial data (eg. 921600 baud) to the board, use Serial1/Serial3.
|
|
|
|
#################################################
|
|
### MCU CONFIGURATION ###
|
|
#################################################
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 127
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
define STM32_ST_USE_TIMER 5
|
|
define CH_CFG_ST_RESOLUTION 32
|
|
|
|
# reserve 16k for bootloader, 16k for OSD and 32k for flash storage
|
|
FLASH_RESERVE_START_KB 64
|
|
FLASH_SIZE_KB 1024
|
|
|
|
define HAL_STORAGE_SIZE 15360
|
|
define STORAGE_FLASH_PAGE 1
|
|
|
|
|
|
# I2C Buses
|
|
I2C_ORDER I2C1 I2C2
|
|
|
|
# order of UARTs
|
|
SERIAL_ORDER OTG1 USART1 EMPTY USART3 UART4 UART5 USART6 USART2
|
|
|
|
#################################################
|
|
### PIN DEFINITIONS ###
|
|
#################################################
|
|
|
|
PA0 UART4_TX UART4
|
|
PA1 UART4_RX UART4
|
|
|
|
# default to timer for RC input
|
|
PA3 TIM9_CH2 TIM9 RCININT FLOAT LOW
|
|
|
|
# alternative using USART2
|
|
PA2 USART2_TX USART2 NODMA
|
|
PA3 USART2_RX USART2 NODMA ALT(1)
|
|
|
|
PA4 MPU_CS CS
|
|
|
|
# IMU SPI
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
PA9 USART1_TX USART1
|
|
PA10 USART1_RX USART1
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
PA14 LED_BLUE OUTPUT LOW GPIO(0)
|
|
PA13 LED_GREEN OUTPUT LOW GPIO(1) # optional
|
|
|
|
define HAL_GPIO_A_LED_PIN 0
|
|
define HAL_GPIO_B_LED_PIN 1
|
|
|
|
|
|
#pwm output
|
|
PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50)
|
|
PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51)
|
|
PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52)
|
|
PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53)
|
|
PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54)
|
|
PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55)
|
|
PB14 TIM1_CH2N TIM1 PWM(7) GPIO(56)
|
|
PB15 TIM1_CH3N TIM1 PWM(8) GPIO(57)
|
|
PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58)
|
|
PA15 TIM2_CH1 TIM2 PWM(10) GPIO(59) #on LED pin,allows odd motor groups
|
|
|
|
|
|
# SD CARD SPI
|
|
PB3 SPI3_SCK SPI3
|
|
PB4 SPI3_MISO SPI3
|
|
PB5 SPI3_MOSI SPI3
|
|
PC14 SDCARD_CS CS
|
|
|
|
PB8 I2C1_SCL I2C1
|
|
PB9 I2C1_SDA I2C1
|
|
|
|
PB10 I2C2_SCL I2C2
|
|
PB11 I2C2_SDA I2C2
|
|
|
|
# OSD SPI
|
|
PB12 OSD_CS CS
|
|
PB13 SPI2_SCK SPI2
|
|
PC2 SPI2_MISO SPI2
|
|
PC3 SPI2_MOSI SPI2
|
|
|
|
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
PC5 RSSI_ADC_PIN ADC1 SCALE(1)
|
|
|
|
PC6 USART6_TX USART6
|
|
PC7 USART6_RX USART6
|
|
|
|
PC10 USART3_TX USART3
|
|
PC11 USART3_RX USART3
|
|
|
|
PC12 UART5_TX UART5
|
|
PD2 UART5_RX UART5
|
|
|
|
PC13 VBUS INPUT OPENDRAIN
|
|
|
|
PC15 BUZZER OUTPUT GPIO(80) LOW
|
|
define HAL_BUZZER_PIN 80
|
|
define HAL_BUZZER_ON 1
|
|
define HAL_BUZZER_OFF 0
|
|
|
|
#################################################
|
|
### DEVICES ###
|
|
#################################################
|
|
|
|
# MPU6000 on SPI
|
|
SPIDEV mpu6000 SPI1 DEVID1 MPU_CS MODE3 1*MHZ 4*MHZ
|
|
|
|
# OSD on SPI
|
|
SPIDEV osd SPI2 DEVID2 OSD_CS MODE0 10*MHZ 10*MHZ
|
|
|
|
# SD Card on SPI
|
|
SPIDEV sdcard SPI3 DEVID3 SDCARD_CS MODE0 400*KHZ 25*MHZ
|
|
|
|
# one IMU
|
|
IMU Invensense SPI:mpu6000 ROTATION_YAW_180
|
|
|
|
# one baro, multiple possible choices for different board variants
|
|
BARO BMP280 I2C:0:0x76
|
|
BARO DPS310 I2C:0:0x76
|
|
|
|
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_MONITOR_DEFAULT 4
|
|
define HAL_BATT_VOLT_PIN 10
|
|
define HAL_BATT_CURR_PIN 11
|
|
define HAL_BATT_VOLT_SCALE 11
|
|
define HAL_BATT_CURR_SCALE 31.7
|
|
|
|
#analog rssi pin (also could be used as analog airspeed input)
|
|
# PC5 - ADC12_CH15
|
|
define BOARD_RSSI_ANA_PIN 15
|
|
|
|
# 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
|
|
|
|
define OSD_ENABLED 1
|
|
define HAL_OSD_TYPE_DEFAULT 1
|
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
|
|
|
|
define STM32_PWM_USE_ADVANCED TRUE
|
|
|
|
# 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
|
|
|
|
# reduce max size of embedded params for apj_tool.py
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
|
|
define HAL_WITH_DSP FALSE
|
|
|
|
# save some flash
|
|
define HAL_GENERATOR_ENABLED 0
|
|
define AC_OAPATHPLANNER_ENABLED 0
|
|
define PRECISION_LANDING 0
|
|
define HAL_BARO_WIND_COMP_ENABLED 0
|
|
define GRIPPER_ENABLED 0
|