AP_HAL_ChibiOS: add support for MambaF405 2022 MK4

mark DMA on MambaF405US-I2C UARTs
correct RSSI pin on MambaF405US-I2C
This commit is contained in:
Andy Piper 2022-06-08 17:38:48 +01:00 committed by Andrew Tridgell
parent 34f327404a
commit ed6f7fb9e9
5 changed files with 109 additions and 3 deletions

View File

@ -0,0 +1,88 @@
# Mamba Basic F405 MK4 Flight Controller
The Mamba Basic line of flight controllers are produced by [Diatone](https://www.diatone.us).
## Features
- STM32F405RGT6 microcontroller
- MPU6000 IMU
- AT7456E OSD
- 4 UARTs
- 7 PWM outputs (6 Motor Output, 1 LED)
## Pinout
![Mamba Basic 20x20 Pinout](basic20pinout.png)
## UART Mapping
The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the
receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
|Name|Pin|Function|
|:-|:-|:-|
|SERIAL0|COMPUTER|USB|
|SERIAL1|PPM/RX1/SBUS/TX1|UART1 (RC Input)|
|SERIAL2|TX2/RX2|UART2 (DMA-enabled)|
|SERIAL3|TX3/RX3|UART3 (Telem1)|
|SERIAL4|TX4/RX4|UART4 (Empty)|
|SERIAL6|TX6/RX6|UART6 (GPS, DMA-enabled)|
## RC Input
RC input is configured on the PPM (UART1_RX) pin. It supports all RC protocols.
## OSD Support
The Mamba F405 MK4 supports OSD using OSD_TYPE 1 (MAX7456 driver).
## PWM Output
The Mamba F405 MK4 supports up to 7 PWM outputs. The pads for motor output ESC1 to ESC4 on the above diagram are for the 4 outputs. All outputs support DShot as well as all PWM types. Motors 1-4 support bi-directional DShot.
The PWM is in 4 groups:
- PWM 1,2 in group1
- PWM 3,4 in group2
- PWM 5,6 in group3
- PWM 7 in group4
Channels within the same group need to use the same output rate. If
any channel in a group uses DShot then all channels in the group need
to use DShot.
## Battery Monitoring
The board has a builting voltage sensor. The voltage sensor can handle up to 6S
LiPo batteries.
The correct battery setting parameters are:
- BATT_MONITOR 3
- BATT_VOLT_PIN 11
- BATT_VOLT_MULT around 11.0
- BATT_CURR_PIN 13
- BATT_CURR_MULT around 28 with the 20x20 40A ESC (calculated, needs to be verified)
## Compass
The Mamba Basic flight controllers do not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads.
## Alternate settings
It is possible to set alternate configurations with the BRD_ALT_CONFIG parameter.
|BRD_ALT_CONFIG|RX1 function|
|:----|:----|
|ALT 0(default) |RCININT|
|ALT 1|RX1/TX1|
## Loading Firmware
Initial firmware load can be done with DFU by plugging in USB with the
bootloader button pressed. Then you should load the "with_bl.hex"
firmware, using your favourite DFU loading tool.
Once the initial firmware is loaded you can update the firmware using
any ArduPilot ground station software. Updates should be done with the
*.apj firmware files.

Binary file not shown.

After

Width:  |  Height:  |  Size: 294 KiB

View File

@ -0,0 +1 @@
include ../MambaF405US-I2C/hwdef-bl.dat

View File

@ -0,0 +1,17 @@
# MambaF405 2022
include ../MambaF405US-I2C/hwdef.dat
undef PA9 PA8 PC9 PC8 PB3 PB11
PA9 TIM1_CH2 TIM1 PWM(1) GPIO(50) BIDIR
PA8 TIM1_CH1 TIM1 PWM(2) GPIO(51)
PC9 TIM8_CH4 TIM8 PWM(3) GPIO(52) BIDIR
PC8 TIM8_CH3 TIM8 PWM(4) GPIO(53)
PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54)
PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55)
# LED strip
PB3 TIM2_CH2 TIM2 PWM(7) GPIO(56)
PB11 USART3_RX USART3 NODMA

View File

@ -50,11 +50,11 @@ PB11 USART3_RX USART3
# UART4
PA0 UART4_TX UART4
PA1 UART4_RX UART4
PA1 UART4_RX UART4 NODMA
# UART5
PC12 UART5_TX UART5
PD2 UART5_RX UART5
PD2 UART5_RX UART5 NODMA
# USART6
PC6 USART6_TX USART6
@ -147,7 +147,7 @@ define HAL_BATT_VOLT_SCALE 11
define HAL_BATT_CURR_SCALE 39
# Analog RSSI pin (also could be used as analog airspeed input)
define BOARD_RSSI_ANA_PIN 1
define BOARD_RSSI_ANA_PIN 12
# Setup for OSD
define OSD_ENABLED 1