AP_HAL_ChibiOS: add HEEWING-F405 flight controller

add bi-directional dshot
add back in features.
juggle DMA allocations to allow CRSF to work correctly
disable dshot on PWM 10 as it is not used
do not enable quadplane by default
do not disable arming checks
run ICM42688 at 1Mhz for low speed to avoid gyro noise
add HEEWING README and picture
This commit is contained in:
HelloLeFei 2023-06-29 12:55:08 +08:00 committed by Peter Barker
parent 0d9f0c8dd6
commit 8ec404c6fc
5 changed files with 329 additions and 0 deletions

View File

@ -0,0 +1,88 @@
# HEEWING F405 Flight Controller
https://www.heewing.com/pages/t1-ranger-vtol-pnp-manual
The HEEWING F405 is a flight controller produced by [HEEWING](https://www.heewing.com/pages/t1-ranger-vtol-pnp-manual) that is incorporated into their Ranger-T1 VTOL RTF airframe.
## Features
- STM32F405 microcontroller
- ICM42688 IMU
- SLP06 barometer
- NO dataflash
- MAX7456 OSD
- 4 UARTs
- 9 PWM outputs
### HEEWING F405 Pinout
![HEEWING F405 Board](heewingf405.jpg "HEEWING F405")
## 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.
- SERIAL0 -> USB
- SERIAL1 -> UART3 (UART1 on casing, DMA-enabled)
- SERIAL2 -> UART1 (UART2 on casing, DMA-enabled)
- SERIAL5 -> UART5 (GPS)
- SERIAL6 -> UART2 (RCIN RX-only or RX/TX with BRD_ALT_CONFIG=1, DMA-enabled)
## RC Input
RC input is configured on the RCIN connector (UART2_RX) pin. It supports all serial RC protocols. It can be configured for two-way protocols (e.g. CRSF) by setting BRD_ALT_CONFIG=1
## FrSky Telemetry
FrSky Telemetry can be supported using the transmit pin on a spare serial ports SERIAL1 and SERIAL2.
## OSD Support
The HEEWING F405 supports OSD using OSD_TYPE 1 (MAX7456 driver).
## PWM Output
The HEEWING F405 supports up to 9 PWM outputs. M1-M2, M5-M6 and M9 support bi-directional dshot. All outputs support dshot although M3-4 are not recommended for this purpose as they share resources with I2C.
The PWM is in 4 groups:
- PWM 1 and 2 in group1
- PWM 3 and 4 in group2
- PWM 5 and 6 in group3
- PWM 7-9 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 and current sensor. The current
sensor can read up to 130 Amps. The voltage sensor can handle up to 6S
LiPo batteries.
The correct battery setting parameters are:
- BATT_MONITOR 4
- BATT_VOLT_PIN 10
- BATT_CURR_PIN 11
- BATT_VOLT_MULT 7.71
- BATT_AMP_PERVLT 26.67
## Compass
The HEEWING F405 does not have a builtin compass, but you can attach an external compass using the GPS port. The RTF kit comes pre-supplied with a GPS and compass.
## 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.
Note that this hardware has problems going into DFU mode if a GPS is connected and powered - please disconnect your GPS when flashing for the first time.
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.

View File

@ -0,0 +1,4 @@
ALT_HOLD_RTL,5000
ARMING_RUDDER,2
# GPS RX DMA conflicts with CRSF and I2C1
GPS_DRV_OPTIONS,4

Binary file not shown.

After

Width:  |  Height:  |  Size: 72 KiB

View File

@ -0,0 +1,41 @@
# hw definition file for HEEWING-F405
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# crystal frequency
OSCILLATOR_HZ 8000000
# board ID for firmware load
APJ_BOARD_ID 1119
FLASH_RESERVE_START_KB 0
FLASH_SIZE_KB 1024
FLASH_BOOTLOADER_LOAD_KB 64
PC13 LED_BOOTLOADER OUTPUT LOW GPIO(0)
PC15 LED_ACTIVITY OUTPUT LOW GPIO(1) # optional
define HAL_LED_ON 0
# order of UARTs
SERIAL_ORDER OTG1 USART1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PA9 USART1_TX USART1
PA10 USART1_RX USART1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
# Add CS pins to ensure they are high in bootloader
PA4 IMU_CS CS
PC4 OSD_CS CS
PC14 FLASH_CS CS
#PC1 SDCARD_CS CS
# Turn on switched supply and camera switch/output during bootloader to match default
#PA4 PINIO1 OUTPUT LOW
#PB5 PINIO2 OUTPUT LOW

View File

@ -0,0 +1,196 @@
# hw definition file for MATEK M9N-F405
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# bootloader starts firmware at 64k
FLASH_RESERVE_START_KB 64
FLASH_SIZE_KB 1024
# store parameters in pages 1 and 2
STORAGE_FLASH_PAGE 1
define HAL_STORAGE_SIZE 15360
# board ID for firmware load
APJ_BOARD_ID 1119
define STM32_ST_USE_TIMER 5
define CH_CFG_ST_RESOLUTION 32
# crystal frequency
OSCILLATOR_HZ 8000000
# --------------------- LED -----------------------
PC13 LED0 OUTPUT LOW GPIO(90) # blue marked as ACT
PC15 LED1 OUTPUT LOW GPIO(91) # green marked as B/E
define HAL_GPIO_A_LED_PIN 91
define HAL_GPIO_B_LED_PIN 90
define HAL_GPIO_LED_OFF 1
# --------------------- PWM -----------------------
PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50) BIDIR
PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51)
PB1 TIM3_CH4 TIM3 PWM(3) GPIO(52) # UP shared with I2C2_RX, dshot not advised
PB0 TIM3_CH3 TIM3 PWM(4) GPIO(53) # UP shared with I2C2_RX, dshot not advised
PC9 TIM8_CH4 TIM8 PWM(5) GPIO(54) BIDIR
PC8 TIM8_CH3 TIM8 PWM(6) GPIO(55)
PB15 TIM1_CH3N TIM1 PWM(7) GPIO(56)
PB14 TIM1_CH2N TIM1 PWM(8) GPIO(57)
PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) BIDIR
PA15 TIM2_CH1 TIM2 PWM(10) GPIO(59) NODMA # no output
define STM32_PWM_USE_ADVANCED TRUE
# Beeper
#PA7 TIM3_CH2 TIM3 GPIO(32) ALARM
# GPIOs
#PA4 PINIO1 OUTPUT GPIO(81) LOW
#PB5 PINIO2 OUTPUT GPIO(82) LOW
# --------------------- SPI1 -----------------------
PB3 SPI1_SCK SPI1
PB4 SPI1_MISO SPI1
PB5 SPI1_MOSI SPI1
PA4 IMU_CS CS
# --------------------- SPI2 -----------------------
PB13 SPI2_SCK SPI2
PC2 SPI2_MISO SPI2
PC3 SPI2_MOSI SPI2
PC4 OSD_CS CS
# -------------------- I2C bus --------------------
I2C_ORDER I2C1 I2C2
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# --------------------- UARTs ---------------------------
SERIAL_ORDER OTG1 USART3 USART1 UART5 UART4 USART6 USART2
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
# USART1 (labelled UART2 on casing)
PA9 USART1_TX USART1
PA10 USART1_RX USART1
# USART2 - RCIN with inverter / CRSF (4-pin RCIN connector)
PA2 USART2_TX USART2
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN
# alternative with PA3 as USART2_RX
PA3 USART2_RX USART2 ALT(1)
# USART3 - (labelled UART1 on casing)
PC10 USART3_TX USART3
PC11 USART3_RX USART3
# UART4 - (NC)
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA
# UART5 - (GPS)
PC12 UART5_TX UART5
PD2 UART5_RX UART5 NODMA
# USART6 - (NC)
PC6 USART6_TX USART6 NODMA
PC7 USART6_RX USART6 NODMA
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# ------------------- DMA assignment -------------------
DMA_PRIORITY ADC1 SPI1* SPI2* USART2*
# ------------------- IMU ICM42605 ---------------------
SPIDEV icm42688 SPI1 DEVID1 IMU_CS MODE3 1*MHZ 8*MHZ
IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180_YAW_90
define HAL_DEFAULT_INS_FAST_SAMPLE 1
# ------------------ OSD AT7456E ----------------------
SPIDEV osd SPI2 DEVID2 OSD_CS MODE0 10*MHZ 10*MHZ
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
# ----------------- I2C compass & Baro -----------------
# no built-in compass, but probe the i2c bus for all possible
# external compass types
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
# built-in barometer
BARO SPL06 I2C:0:0x77
# --------------------- ADC ---------------------------
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
// RSSI_ADC_PIN ADC1 SCALE(1)
//PC0 PRESSURE_SENS ADC1 SCALE(1)
define HAL_BATT_MONITOR_DEFAULT 4
define HAL_BATT_VOLT_PIN 10
define HAL_BATT_VOLT_SCALE 7.71
define HAL_BATT_CURR_PIN 11
define HAL_BATT_CURR_SCALE 26.7
#define BOARD_RSSI_ANA_PIN 8
#define HAL_DEFAULT_AIRSPEED_PIN 10
# reduce max size of embedded params for apj_tool.py
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
define HAL_WITH_DSP FALSE
define HAL_GYROFFT_ENABLED 0
# --------------------- save flash ----------------------
define AP_BATTMON_SMBUS_ENABLE 0
include ../include/minimal.inc
include ../include/save_some_flash.inc
# features that users are likely to want
define AP_TRAMP_ENABLED 1
define HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED 1
# features that users are unlikely to want
define AC_OAPATHPLANNER_ENABLED 0
define AC_PRECLAND_ENABLED 0
define AP_ICENGINE_ENABLED 0
define AP_OPTICALFLOW_ENABLED 0
define HAL_GENERATOR_ENABLED 0
define HAL_SPRAYER_ENABLED 0
define PRECISION_LANDING 0
define GRIPPER_ENABLED 0
define HAL_HOTT_TELEM_ENABLED 0
define HAL_NMEA_OUTPUT_ENABLED 0
define HAL_BUTTON_ENABLED 0
define HAL_OREO_LED_ENABLED 0
define AP_OPTICALFLOW_ENABLED 0
define AP_ICENGINE_ENABLED 0
define AP_RANGEFINDER_ENABLED 0
define AP_RPM_EFI_ENABLED 0
define AP_RPM_PIN_ENABLED 0
define AP_RPM_GENERATOR_ENABLED 0
define HAL_PARACHUTE_ENABLED 0
AUTOBUILD_TARGETS Plane