HAL_ChibiOS: Added support for CUAV-7-Nano flight controller

This commit is contained in:
cuav-chen2 2024-07-03 10:12:28 +08:00 committed by Randy Mackay
parent 3554e6eba9
commit 123eeae2fb
5 changed files with 477 additions and 0 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 45 KiB

View File

@ -0,0 +1,80 @@
# CUAV-7-Nano Flight Controller
The CUAV-7-Nano flight controller produced by [CUAV](https://www.cuav.net).
## Features
- STM32H753 microcontroller
- 2 IMUs: IIM42652 and BMI088
- builtin IST8310 magnetometer
- 2 barometers: BMP581 and ICP20100
- microSD card slot
- USB-TypeC port
- 1 ETH network interface
- 5 UARTs plus USB
- 14 PWM outputs
- 3 I2C ports
- 3 CAN ports (two of which share a CAN bus and one is an independent CAN bus)
- Analog RSSI input
- 3.3V/5V configurable PWM ouput voltage
## Pinout
![CUAV-7-Nano_interface_definition.png](CUAV-7-Nano-pinout.png)
## UART Mapping
- SERIAL0 -> USB
- SERIAL1 -> UART7 (TELEM1)
- SERIAL2 -> UART5 (TELEM2)
- SERIAL3 -> USART1 (GPS&SAFETY)
- SERIAL4 -> UART8 (GPS2)
- SERIAL5 -> USART3 (FMU DEBUG)
The TELEM1 and TELEM2 ports have RTS/CTS pins, the other UARTs do not have RTS/CTS. All have full DMA capability.
## RC Input
RC input is configured on the RCIN pin, at one end of the servo rail, marked RCIN in the above diagram. All ArduPilot supported unidirectional RC protocols can be input here including PPM. For bi-directional or half-duplex protocols, such as CRSF/ELRS a full UART will have to be used.
## PWM Output
The CUAV-7-Nano flight controller supports up to 14 PWM outputs.
The 14 PWM outputs are in 6 groups:
- PWM 1-4 in group1 (TIM5)
- PWM 5 and 6 in group2 (TIM4)
- PWM 7 and 8 in group3 (TIM1)
- PWM 9, 10 and 11 in group4 (TIM8)
- PWM 12 in group5 (TIM15)
- PWM 13 and 14 in group6 (TIM12)
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. Outputs 1-4 support BDShot.
First first 8 PWM outputs of CUAV-7-Nano flight controller support switching between 3.3V voltage and 5V voltage output. It can be switched to 5V by setting GPIO 80 high by setting up a Voltage-Level Translator to control it.
## Battery Monitoring
The board has a dedicated power monitor ports on 6 pin connectors(POWER A). The correct battery setting parameters are dependent on the type of power brick which is connected.
## Compass
The CUAV-7-Nano has an IST8310 builtin compass, but due to interference the board is usually used with an external I2C compass as part of a GPS/Compass combination.
## Analog inputs
The CUAV-7-Nano has 6 analog inputs.
- ADC Pin9 -> Battery Voltage
- ADC Pin8 -> Battery Current Sensor
- ADC Pin5 -> Vdd 5V supply sense
- ADC Pin13 -> ADC 3.3V Sense
- ADC Pin12 -> ADC 6.6V Sense
- ADC Pin10 -> RSSI voltage monitoring
## Loading Firmware
Firmware for these boards can be found at https://firmware.ardupilot.org in sub-folders labeled "CUAV-7-Nano".
The board comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of *.apj firmware files with any ArduPilot compatible ground station.

View File

@ -0,0 +1,2 @@
INS_ACCEL_FILTER 10
CAN_P1_DRIVER 1

View File

@ -0,0 +1,101 @@
# hw definition file for processing by chibios_hwdef.py
# for CUAV-7-Nano board
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# crystal frequency
OSCILLATOR_HZ 16000000
# board ID for firmware load
APJ_BOARD_ID 7000
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
FLASH_BOOTLOADER_LOAD_KB 128
# flash size
FLASH_SIZE_KB 2048
env OPTIMIZE -Os
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 UART5 USART3
# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA9 VBUS INPUT OPENDRAIN
# pins for SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# CS pins
PI9 ICM42652_CS CS
PH5 BMI088_A_CS CS
PG2 BMI088_G_CS CS
PD15 BMP581_CS CS
PG7 FRAM_CS CS
# telem1
PE8 UART7_TX UART7
PF6 UART7_RX UART7
# telem2
PC12 UART5_TX UART5
PD2 UART5_RX UART5
# debug uart
PD8 USART3_TX USART3
PD9 USART3_RX USART3
# armed indication
PE7 nARMED OUTPUT HIGH
# start peripheral power off
PG4 VDD_5V_PERIPH_EN OUTPUT HIGH
PG10 VDD_5V_HIPOWER_EN OUTPUT HIGH
# LEDs
PE3 LED_RED OUTPUT LOW # red
PE4 LED_ACTIVITY OUTPUT LOW # green
PE5 LED_BOOTLOADER OUTPUT LOW # blue
define HAL_LED_ON 0
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable DFU by default
ENABLE_DFU_BOOT 1
# support flashing from SD card:
# power enable pins
PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH
# FATFS support:
define CH_CFG_USE_MEMCORE 1
define CH_CFG_USE_HEAP 1
define CH_CFG_USE_SEMAPHORES 0
define CH_CFG_USE_MUTEXES 1
define CH_CFG_USE_DYNAMIC 1
define CH_CFG_USE_WAITEXIT 1
define CH_CFG_USE_REGISTRY 1
# microSD support
PD6 SDMMC2_CK SDMMC2
PD7 SDMMC2_CMD SDMMC2
PB14 SDMMC2_D0 SDMMC2
PB15 SDMMC2_D1 SDMMC2
PG11 SDMMC2_D2 SDMMC2
PB4 SDMMC2_D3 SDMMC2
define FATFS_HAL_DEVICE SDCD2
DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
define AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1

View File

@ -0,0 +1,294 @@
# hw definition file for processing by chibios_hwdef.py
# for CUAV-7-Nano board
# default to all pins low to avoid ESD issues
DEFAULTGPIO OUTPUT LOW PULLDOWN
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# crystal frequency
OSCILLATOR_HZ 16000000
# ChibiOS system timer
STM32_ST_USE_TIMER 2
# board ID for firmware load
APJ_BOARD_ID 7000
# bootloader takes first sector
FLASH_RESERVE_START_KB 128
# to be compatible with the px4 bootloader we need
# to use a different RAM_MAP
env USE_ALT_RAM_MAP 1
# flash size
FLASH_SIZE_KB 2048
# with 2M flash we can afford to optimize for speed
env OPTIMIZE -O2
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART3 OTG2
# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA9 VBUS INPUT OPENDRAIN
# pins for SWD debugging
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# telem1
PE8 UART7_TX UART7
PF6 UART7_RX UART7
PF8 UART7_RTS UART7
PE10 UART7_CTS UART7
# telem2
PC8 UART5_RTS UART5
PC9 UART5_CTS UART5
PC12 UART5_TX UART5
PD2 UART5_RX UART5
# GPS1
PB6 USART1_TX USART1
PB7 USART1_RX USART1
# GPS2
PE0 UART8_RX UART8
PE1 UART8_TX UART8
# debug uart
PD8 USART3_TX USART3
PD9 USART3_RX USART3
# uart6, RX only, RC input, if no IOMCU
PC7 USART6_RX USART6
# ethernet
PC1 ETH_MDC ETH1
PA2 ETH_MDIO ETH1
PC4 ETH_RMII_RXD0 ETH1
PC5 ETH_RMII_RXD1 ETH1
PG13 ETH_RMII_TXD0 ETH1
PG12 ETH_RMII_TXD1 ETH1
PB11 ETH_RMII_TX_EN ETH1
PA7 ETH_RMII_CRS_DV ETH1
PA1 ETH_RMII_REF_CLK ETH1
#PG15 ETH_POWER_EN ETH1
PG15 Ethernet_PWR_EN OUTPUT HIGH # disable power on ethernet
define BOARD_PHY_ID MII_LAN8742A_ID
define BOARD_PHY_RMII
# ADC
PA0 SCALED1_V3V3 ADC1 SCALE(2)
PA4 SCALED2_V3V3 ADC1 SCALE(2)
PB1 VDD_5V_SENS ADC1 SCALE(2)
PC0 RSSI_IN ADC1 SCALE(1)
PF12 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3)
# analog in
PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) ANALOG(9)
PB0 BATT_CURRENT_SENS ADC1 SCALE(1) ANALOG(8)
# pin7 on AD&IO, analog 12
PF3 ADC3_6V6 ADC3 SCALE(2) ANALOG(12)
# pin6 on AD&IO, analog 13
PC3 ADC1_3V3 ADC1 SCALE(1) ANALOG(13)
define HAL_BATT_VOLT_PIN 9
define HAL_BATT_CURR_PIN 8
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0
# SPI1 - IIM42652
PA5 SPI1_SCK SPI1
PB5 SPI1_MOSI SPI1
PG9 SPI1_MISO SPI1
PI9 IIM42652_CS CS
PF2 IIM42652_DRDY INPUT
# SPI2 - BMI088
PI1 SPI2_SCK SPI2
PI2 SPI2_MISO SPI2
PI3 SPI2_MOSI SPI2
PH5 BMI088_A_CS CS
PG2 BMI088_G_CS CS
PG3 BMI088_DRDY_GYR INPUT
PA10 BMI088_DRDY_ACC INPUT
# SPI4 - BMP581
PE12 SPI4_SCK SPI4
PE13 SPI4_MISO SPI4
PE14 SPI4_MOSI SPI4
PD15 BMP581_CS CS
PG1 BMP581_DRDY INPUT
# SPI5 - FRAM
PF7 SPI5_SCK SPI5
PH7 SPI5_MISO SPI5
PF11 SPI5_MOSI SPI5
PG7 FRAM_CS CS
# SPI devices
SPIDEV bmi088_g SPI2 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ
SPIDEV bmi088_a SPI2 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ
SPIDEV iim42652 SPI1 DEVID1 IIM42652_CS MODE3 2*MHZ 8*MHZ
SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
SPIDEV bmp581 SPI4 DEVID1 BMP581_CS MODE3 7.5*MHZ 12*MHZ
# PWM output pins
PI0 TIM5_CH4 TIM5 PWM(1) GPIO(50) BIDIR
PH12 TIM5_CH3 TIM5 PWM(2) GPIO(51)
PH11 TIM5_CH2 TIM5 PWM(3) GPIO(52) BIDIR
PH10 TIM5_CH1 TIM5 PWM(4) GPIO(53)
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
PE11 TIM1_CH2 TIM1 PWM(7) GPIO(56)
PE9 TIM1_CH1 TIM1 PWM(8) GPIO(57)
PI6 TIM8_CH2 TIM8 PWM(9) GPIO(58)
PI7 TIM8_CH3 TIM8 PWM(10) GPIO(59)
PI5 TIM8_CH1 TIM8 PWM(11) GPIO(60)
PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61)
# we need to disable DMA on the last 2 FMU channels
# as timer 12 doesn't have a TIMn_UP DMA option
PH6 TIM12_CH1 TIM12 PWM(13) GPIO(62) NODMA
PH9 TIM12_CH2 TIM12 PWM(14) GPIO(63) NODMA
# CAN bus
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
PB12 CAN2_RX CAN2
PB13 CAN2_TX CAN2
# control for silent (no output) for CAN
PE2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
PI8 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71)
# I2C buses
# I2C1, GPS+MAG
PB9 I2C1_SDA I2C1
PB8 I2C1_SCL I2C1
# I2C2, GPS2+MAG
PF1 I2C2_SCL I2C2
PF0 I2C2_SDA I2C2
# I2C3, IST8310
PA8 I2C3_SCL I2C3
PH8 I2C3_SDA I2C3
# I2C4, ICM20100
PF14 I2C4_SCL I2C4
PF15 I2C4_SDA I2C4
PG5 DRDY1_ICP20100 INPUT
# order of I2C buses
I2C_ORDER I2C3 I2C4 I2C1 I2C2
define HAL_I2C_INTERNAL_MASK 3
# armed indication
PE7 nARMED OUTPUT HIGH
# power enable pins
PC13 VDD_3V3_SD_CARD_EN OUTPUT HIGH
PI11 VDD_3V3_SENSORS1_EN OUTPUT HIGH
PF4 VDD_3V3_SENSORS2_EN OUTPUT HIGH
PH2 VDD_3V3_SENSORS3_EN OUTPUT HIGH
# start peripheral power off, then enable after init
# this prevents a problem with radios that use RTS for
# bootloader hold
PG10 VDD_5V_HIPOWER_EN OUTPUT HIGH
PG4 VDD_5V_PERIPH_EN OUTPUT HIGH
# power sensing
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP
# Pin for PWM Voltage Selection, 0 means 3.3v, 1 means 5v, 3.3v default
PG8 PWM_VOLT_SEL OUTPUT LOW GPIO(80)
define HAL_GPIO_PWM_VOLT_PIN 80
define HAL_GPIO_PWM_VOLT_3v3 0
# microSD support
PD6 SDMMC2_CK SDMMC2
PD7 SDMMC2_CMD SDMMC2
PB14 SDMMC2_D0 SDMMC2
PB15 SDMMC2_D1 SDMMC2
PG11 SDMMC2_D2 SDMMC2
PB4 SDMMC2_D3 SDMMC2
define FATFS_HAL_DEVICE SDCD2
# safety
PD10 LED_SAFETY OUTPUT
PF5 SAFETY_IN INPUT PULLDOWN
# LEDs
PE3 LED_RED OUTPUT GPIO(90) LOW
PE4 LED_GREEN OUTPUT GPIO(91) LOW
PE5 LED_BLUE OUTPUT GPIO(92) LOW
# setup for "pixracer" RGB LEDs
define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 90
define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 91
define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 92
define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1
# ID pins
PG0 HW_VER_REV_DRIVE OUTPUT LOW
# PH3 HW_VER_SENS ADC3 SCALE(1)
# PH4 HW_REV_SENS ADC3 SCALE(1)
# PWM output for buzzer
PF9 TIM14_CH1 TIM14 GPIO(77) ALARM
# RC input
PC6 TIM3_CH1 TIM3 RCININT PULLDOWN LOW
# other I2C devices
# 24LC64T eeprom 64Kbit, address 0x50 on I2C4
BARO BMP581 SPI:bmp581
BARO ICP201XX I2C:1:0x63
# compass
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE
define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
define AP_COMPASS_IST8310_DEFAULT_ROTATION ROTATION_ROLL_180_YAW_90
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_90_YAW_90
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
# IMUs
IMU Invensensev3 SPI:iim42652 ROTATION_ROLL_90_YAW_90
IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_90
define HAL_DEFAULT_INS_FAST_SAMPLE 3
# enable RAMTROM parameter storage
define HAL_STORAGE_SIZE 32768
define HAL_WITH_RAMTRON 1
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1
DMA_PRIORITY TIM5* SDMMC* USART6* ADC* UART* USART* SPI* TIM*
# enable FAT filesystem support (needs a microSD defined via SDMMC)
define HAL_OS_FATFS_IO 1
# enable DFU reboot for installing bootloader
# note that if firmware is build with --secure-bl then DFU is
# disabled
ENABLE_DFU_BOOT 1