mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 23:48:31 -04:00
1b1e5b1085
correct battery setup for MambaF405v2 provide suitable serial defaults for MambaF405v2 reallocate DMA channels to allow full DMA on USART3 and NeoPixel on MambaF405v2 add camera control pin to MambaF405v2
173 lines
4.1 KiB
Plaintext
173 lines
4.1 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
# Mamba F405 MK2
|
|
# With F405 MCU, MPU6000 IMU and 7456 series OSD
|
|
# Based on Mamba F405 from jeanphilippehell
|
|
@ thanks to betaflight for pin information
|
|
|
|
# MCU class and specific type.
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
HAL_CHIBIOS_ARCH_F405 1
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1019
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
# board voltage
|
|
STM32_VDD 330U
|
|
|
|
STM32_ST_USE_TIMER 4
|
|
define CH_CFG_ST_RESOLUTION 16
|
|
|
|
# order of I2C buses
|
|
I2C_ORDER I2C1
|
|
|
|
# order of UARTs (and USB)
|
|
# this order follows the labels on the board
|
|
# namely COMPUTER, PPM/SBUS (configurable as USART), TX3/RX3, TX6/RX6
|
|
SERIAL_ORDER OTG1 USART1 EMPTY USART3 EMPTY EMPTY USART6
|
|
|
|
# The pins that USB is connected on
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
PC5 VBUS INPUT OPENDRAIN
|
|
|
|
# USART1 is wired to SBUS and PPM input
|
|
# RC input defaults to timer capture
|
|
PA10 TIM1_CH3 TIM1 RCININT PULLDOWN
|
|
PA9 USART1_TX USART1
|
|
|
|
# Alt config to allow RCIN on UART
|
|
PA10 USART1_RX USART1 ALT(1)
|
|
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
|
|
|
|
# SBUS inversion control pin, active low
|
|
PC0 USART1_RXINV OUTPUT HIGH GPIO(78) POL(0)
|
|
|
|
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None
|
|
|
|
# USART3 (VTX)
|
|
PB10 USART3_TX USART3
|
|
PB11 USART3_RX USART3
|
|
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Tramp
|
|
|
|
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None
|
|
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_None
|
|
|
|
# USART6 (ESC Telemetry)
|
|
PC6 USART6_TX USART6
|
|
PC7 USART6_RX USART6
|
|
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_ESCTelemetry
|
|
|
|
# The pins for SWD debugging with a STlinkv2 or black-magic probe (not tested)
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
# ADC
|
|
PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
|
PC2 RSSI_ADC ADC1
|
|
PC3 BATT_CURRENT_SENS ADC1 SCALE(1)
|
|
|
|
# PWM output. 1 - 4 on ESC header
|
|
PA3 TIM2_CH4 TIM2 PWM(1) GPIO(50) BIDIR
|
|
PB0 TIM3_CH3 TIM3 PWM(2) GPIO(51)
|
|
PB1 TIM3_CH4 TIM3 PWM(3) GPIO(52) BIDIR
|
|
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53)
|
|
|
|
# Board LEDs
|
|
PB5 LED_BLUE OUTPUT LOW GPIO(1)
|
|
PB4 LED_GREEN OUTPUT LOW GPIO(2)
|
|
define HAL_GPIO_A_LED_PIN 1
|
|
define HAL_GPIO_B_LED_PIN 2
|
|
|
|
# External LEDs
|
|
PA0 TIM5_CH1 TIM5 PWM(5) GPIO(54)
|
|
|
|
# Buzzer
|
|
PA8 BUZZER OUTPUT GPIO(80) LOW
|
|
define HAL_BUZZER_PIN 80
|
|
|
|
# Camera control
|
|
PB9 CAM_C OUTPUT LOW GPIO(81)
|
|
define RELAY2_PIN_DEFAULT 81
|
|
|
|
# Note that this board needs PULLUP on I2C pins
|
|
PB6 I2C1_SCL I2C1 PULLUP
|
|
PB7 I2C1_SDA I2C1 PULLUP
|
|
|
|
# SPI1 - Internal IMU
|
|
PA4 MPU6000_CS CS
|
|
PA5 SPI1_SCK SPI1
|
|
PA6 SPI1_MISO SPI1
|
|
PA7 SPI1_MOSI SPI1
|
|
|
|
# SPI2 - OSD
|
|
PB15 SPI2_MOSI SPI2
|
|
PB14 SPI2_MISO SPI2
|
|
PB13 SPI2_SCK SPI2
|
|
# OSD max7456
|
|
PB12 OSD_CS CS
|
|
|
|
# SPI3 - dataflash
|
|
PC10 SPI3_SCK SPI3
|
|
PC11 SPI3_MISO SPI3
|
|
PC12 SPI3_MOSI SPI3
|
|
# Dataflash M25P16
|
|
PB3 FLASH_CS CS
|
|
|
|
# SPI Device table
|
|
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ
|
|
SPIDEV icm42688 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 10*MHZ
|
|
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
|
|
SPIDEV osd SPI2 DEVID4 OSD_CS MODE0 10*MHZ 10*MHZ
|
|
|
|
# One IMU rotated in yaw
|
|
IMU Invensense SPI:mpu6000 ROTATION_YAW_90
|
|
IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180
|
|
|
|
# Probe for I2C BMP280
|
|
BARO BMP280 I2C:0:0x76
|
|
define AP_BARO_BACKEND_DEFAULT_ENABLED 0
|
|
define AP_BARO_BMP280_ENABLED 1
|
|
define HAL_BARO_ALLOW_INIT_NO_BARO 1
|
|
|
|
# no built-in compass, but probe the i2c bus for all possible
|
|
# external compass types
|
|
define ALLOW_ARM_NO_COMPASS
|
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
|
define HAL_I2C_INTERNAL_MASK 0
|
|
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
|
|
|
# enable logging to dataflash
|
|
define HAL_LOGGING_DATAFLASH_ENABLED 1
|
|
define HAL_STORAGE_SIZE 15360
|
|
STORAGE_FLASH_PAGE 1
|
|
|
|
# flash size
|
|
FLASH_SIZE_KB 1024
|
|
# reserve 32k for bootloader and 32k for flash storage
|
|
FLASH_RESERVE_START_KB 64
|
|
|
|
# define default battery setup
|
|
define HAL_BATT_VOLT_PIN 11
|
|
define HAL_BATT_CURR_PIN 13
|
|
define HAL_BATT_VOLT_SCALE 11
|
|
define HAL_BATT_CURR_SCALE 25.0
|
|
define HAL_BATT_MONITOR_DEFAULT 4
|
|
|
|
# Analog RSSI pin (also could be used as analog airspeed input)
|
|
define BOARD_RSSI_ANA_PIN 12
|
|
|
|
# Setup for OSD
|
|
define OSD_ENABLED 1
|
|
define HAL_OSD_TYPE_DEFAULT 1
|
|
# Font for the osd
|
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
|
|
|
DMA_PRIORITY TIM2* TIM3*
|
|
|
|
# minimal drivers to reduce flash usage
|
|
include ../include/minimize_fpv_osd.inc
|