AP_HAL_ChibiOS: add CBUnmanned CBU-H7-LC-Stamp

This commit is contained in:
Andy Piper 2024-11-21 11:56:54 -08:00
parent fb2e406ab3
commit 4e3d0a2e9d
3 changed files with 458 additions and 0 deletions

View File

@ -0,0 +1,80 @@
# hw definition file for processing by chibios_hwdef.py
# for the CBUnmanned H743 Stamp Low Cost hardware
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# crystal frequency
OSCILLATOR_HZ 16000000
# board ID for firmware load
APJ_BOARD_ID AP_HW_CBU_StampH743_LC
# 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 UART1 UART2
# 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
PE9 IMU1_CS CS
PE4 SP4_CS1 CS
PD6 USART2_RX USART2
PD5 USART2_TX USART2
PB6 USART1_TX USART1
PA10 USART1_RX USART1
PE3 LED_ACTIVITY OUTPUT HIGH
define HAL_LED_ON 1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable DFU by default
ENABLE_DFU_BOOT 1
# support flashing from SD card
# 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
PC1 SDMMC2_CK SDMMC2
PD7 SDMMC2_CMD SDMMC2
PB14 SDMMC2_D0 SDMMC2
PB15 SDMMC2_D1 SDMMC2
PB3 SDMMC2_D2 SDMMC2
PB4 SDMMC2_D3 SDMMC2
define FATFS_HAL_DEVICE SDCD2
DMA_PRIORITY SDMMC* 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,191 @@
# hw definition file for processing by chibios_hwdef.py
# for the CBUnmanned H743 Stamp Low Cost hardware
# 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 12
define CH_CFG_ST_RESOLUTION 16
MCU_CLOCKRATE_MHZ 480
# board ID for firmware load
APJ_BOARD_ID AP_HW_CBU_StampH743_LC
FLASH_RESERVE_START_KB 128
# flash size
FLASH_SIZE_KB 2048
env OPTIMIZE -Os
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 UART7 UART8 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
PB6 USART1_TX USART1 NODMA
PA10 USART1_RX USART1 NODMA
PD6 USART2_RX USART2
PD5 USART2_TX USART2
# GPS 1
PC10 USART3_TX USART3
PD9 USART3_RX USART3
# GPS 2
PD1 UART4_TX UART4
PC11 UART4_RX UART4
PC12 UART5_TX UART5
PD2 UART5_RX UART5
# RCIN
PC6 USART6_TX USART6
PC7 USART6_RX USART6
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
define DEFAULT_SERIAL6_BAUD 115
PA15 UART7_TX UART7
PE7 UART7_RX UART7
PE1 UART8_TX UART8 NODMA
PE0 UART8_RX UART8 NODMA
# ADC
PC4 BATT_CURRENT_SENS ADC1 SCALE(1) # Current INP4
PA4 BATT_VOLTAGE_SENS ADC1 SCALE(1) # Voltage
# PB1 SPARE_SENS ADC1 SCALE(1) # Spare
# define default battery setup
define HAL_BATT_MONITOR_DEFAULT 4
define HAL_BATT_VOLT_PIN 18
define HAL_BATT_CURR_PIN 4
define HAL_BATT_VOLT_SCALE 11.1
define HAL_BATT_CURR_SCALE 64
# IMU1 ICM-42760-P
PE9 IMU1_CS CS
PB0 IMU1_DRDY INPUT
# SPI4 - External
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
PD4 SP4_DRDY INPUT
PE4 SP4_CS1 CS
# SPI6 - IMUs
PA5 SPI6_SCK SPI6
PA6 SPI6_MISO SPI6
PB5 SPI6_MOSI SPI6
# PWM output pins
PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50) BIDIR
PA1 TIM5_CH2 TIM5 PWM(2) GPIO(51)
PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52) BIDIR
PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53)
PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54) BIDIR
PB7 TIM4_CH2 TIM4 PWM(6) GPIO(55)
PD14 TIM4_CH3 TIM4 PWM(7) GPIO(56) BIDIR
PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57)
PC8 TIM3_CH3 TIM3 PWM(9) GPIO(58)
PB1 TIM3_CH4 TIM3 PWM(10) GPIO(59)
PA7 TIM14_CH1 TIM14 GPIO(61) ALARM
# CAN bus
PD0 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PB12 CAN2_RX CAN2
PB13 CAN2_TX CAN2
# I2C buses
# I2C2 - BMP280
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# I2C3 - GPS1 external compass
PA8 I2C3_SCL I2C3
PC9 I2C3_SDA I2C3
# I2C4 - GPS2 external compass
PB8 I2C4_SCL I2C4
PD13 I2C4_SDA I2C4
# order of I2C buses
I2C_ORDER I2C2 I2C3 I2C4
define HAL_I2C_INTERNAL_MASK 1
# microSD support
PC1 SDMMC2_CK SDMMC2
PD7 SDMMC2_CMD SDMMC2
PB14 SDMMC2_D0 SDMMC2
PB15 SDMMC2_D1 SDMMC2
PB3 SDMMC2_D2 SDMMC2
PB4 SDMMC2_D3 SDMMC2
define FATFS_HAL_DEVICE SDCD2
# safety
PD3 SAFETY_IN INPUT PULLDOWN
# LED
PE3 LED_RED OUTPUT HIGH GPIO(90)
define AP_NOTIFY_GPIO_LED_1_ENABLED 1
define AP_NOTIFY_GPIO_LED_1_PIN 90
define HAL_GPIO_LED_ON 1
# barometers
BARO BMP280 I2C:0:0x76
# compass
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
# IMUs
SPIDEV icm42670 SPI6 DEVID3 IMU1_CS MODE3 2*MHZ 8*MHZ
IMU Invensensev3 SPI:icm42670 ROTATION_PITCH_180_YAW_270
define HAL_DEFAULT_INS_FAST_SAMPLE 7
# use last 2 pages for flash storage
# H743 has 16 pages of 128k each
define HAL_STORAGE_SIZE 32768
STORAGE_FLASH_PAGE 14
DMA_PRIORITY SDMMC* TIM* SPI6*
DMA_NOSHARE TIM2* TIM4* TIM5*
# 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
# build ABIN for flash-from-bootloader support:
env BUILD_ABIN True
# ethernet consumes a big chunk of flash
define AP_BATTERY_SCRIPTING_ENABLED 1

View File

@ -0,0 +1,187 @@
# H743 Stamp Flight Controller (& Low Cost)
CBUnmanned H743 Stamp
The [CBUnmanned H743 Stamp](https://cbunmanned.com/store) is a flight controller loosely based on the FMUv6 standards & is designed for low volume OEMs as a drop in way to add ArduPilot to their custom hardware builds. It is a part of CBUnmanned's wider ["Stamp" Eco-System](https://cbunmanned.com/), which brings together all the typical avionics hardware into a neat custom carrier PCB. Mounting footprints and symbols are available along with examples of basic usage on the [Wiki](https://wiki.cbunmanned.com/).
A "Low Cost" version is available with a limited feature set.
| Full Featured Stamp | Low Cost Stamp |
|--|--|
|![](https://wiki.cbunmanned.com/~gitbook/image?url=https%3A%2F%2F1886089318-files.gitbook.io%2F%7E%2Ffiles%2Fv0%2Fb%2Fgitbook-x-prod.appspot.com%2Fo%2Fspaces%252FolH18CdGEWKpuo9G8NHx%252Fuploads%252FqI2QAAVk2RxHplEJavxV%252FH743%2520Side.png%3Falt%3Dmedia%26token%3Db3444773-b155-46d4-98e5-9502bf50b538&width=768&dpr=4&quality=100&sign=d9afa711&sv=1)| ![](https://wiki.cbunmanned.com/~gitbook/image?url=https%3A%2F%2F1886089318-files.gitbook.io%2F%7E%2Ffiles%2Fv0%2Fb%2Fgitbook-x-prod.appspot.com%2Fo%2Fspaces%252FolH18CdGEWKpuo9G8NHx%252Fuploads%252Fy8KdecctQiPiTOfzhqXt%252FH7-LC-Side.png%3Falt%3Dmedia%26token%3D63434aee-4991-493e-88e7-144312333883&width=768&dpr=4&quality=100&sign=6bdaef1&sv=1)|
###
Features
- Class leading H7 SOC.
- Direct solder mounting or optional 1.27mm header.
- All complicated/supporting circuitry is on-board, just power with 5v.
- From Just 22mm x 24.25mm
| Item | Full Featured Stamp | Low Cost Stamp |
|--|--|--|
| Dimensions | 22mm x 24mm | 23mm x 25mm |
| Weight | 3g | 3g |
| **Processor** | STM32H743IIK6 | STM32H743VIH6 |
| | 480MHz | 480MHz |
| | 2Mb Flash | 2Mb Flash |
| | 1Mb RAM | 1Mb RAM |
| **Sensors** | | |
| IMU 1 | Ivensense ICM-42688 | Ivensense ICM-42670 |
| IMU 2 | Ivensense ICM-42688 | Not Fitted |
| IMU 3 | Ivensense ICM-42670 | Not Fitted |
| Barometer | BMP280 | BMP280 |
| Compass | BMM150 | Not Fitted |
| Micro SD Card | Yes | Yes |
| **IO** | | |
| PWM |10 | 10 |
| CAN | 2 | 2 |
| UART | 8 (3 with flow control) | 8 (None with flow control) |
| I2C | 2 | 2 |
| External SPI | 1 (With custom FW build) | 1 (With custom FW build) |
| Ethernet | Yes | No |
| Safety Button | Yes | Yes |
| Analog | 2 | 2 |
| Buzzer (PWM 11) |Yes |Yes |
| USB |Yes |Yes |
| **Power** | | |
| Input Voltage | 5v | 5v |
| Typical Current Consumption | 0.4 A | 0.4 A |
| Independent Power Domains | 6 Separate Power Domains | No |
####
**UART Mapping**
Ardupilot -> STM32
- SERIAL0 -> USB
- SERIAL1 -> USART1
- SERIAL2 -> USART2 (With RTS/CTS)*
- SERIAL3 -> USART3
- SERIAL4 -> UART4
- SERIAL5 -> UART5 (With RTS/CTS)*
- SERIAL6 -> USART6 (Sbus In / IO coprocessor if fitted)
- SERIAL7 -> UART7 (With RTS/CTS)*
- SERIAL8 -> UART8
*Serial 2, 5 & 7 have RTS/CTS pins (not available on the low cost version), the other UARTs do not have RTS/CTS.
GPS 1 & 2 are on Serial 3 & 4 respectively.
####
**RC Input**
RC input is configured on the USART 6 Rx Pin. This pin allows all RC protocols compatible with direct connection to a H7 IC (SBus, CRSF etc), PPM is NOT supported.
USART 6 Tx is available for use with bi directional protocols.
An optional IOMCU can be connected to this serial port, a compatible custom build of the firmware required.
####
**CAN Ports**
2 CAN buses are available, each with a built in 120 ohm termination resistor.
####
**I2C**
I2C 1 - Internal for BMM150 Compass (not available on the low cost version)
I2C 2 - Internal for BMP280 Barometer
I2C 3 - External With internal 2.2k Pull Up
I2C 4 - External With internal 2.2k Pull Up
####
**SPI**
SPI 4 is available for use with external sensors alongside a Chip Select and Data Ready pin, compatible custom build of the firmware required.
####
**PWM Output**
The Stamp supports up to 10 PWM outputs with D-Shot.
The PWM outputs are in 3 groups:
- PWM 1 - 4 in group 1
- PWM 5 - 8 in group 2
- PWM 9 & 10 in group 3
Channels within the same group need to use the same output rate. If any channel in a group uses D-Shot then all channels in the group need to use D-Shot.
BiDirectional DShot available on the first 8 outputs.
A buzzer alarm signal is available on PWM 11.
####
**Analog Inputs**
The board has two ADC input channels for Voltage (0-3.3v) and Current (0-3.3v) measurement. Settings are dependent on the external hardware used.
####
**Ethernet**
Ethernet is available on 4 output pads and has internal magnetics supporting direct connection to external equipment, without the need for a large RJ45 connector. (Not available on the low cost version).
####
**Compass**
The H743 Stamp has a built in compass, the BMM150. Due to potential interference the board is usually used with an external I2C or CAN compass as part of a GPS/Compass combination. (Not available on the low cost version).
####
**USB**
USB Signals D+ & D- are available to route to a suitable connector for your project.
####
**Safety Button**
Optional, if it is not fitted remove the check from arming mask. To activate short this pad to 3.3v with a momentary push button (Press & Hold)
####
**Power**
A regulated 3.3v output is available from the stamp for use with the safety button. WARNING! This is shared with the main IC - Do NOT use for accessories. Keep current draw under 0.1A!
The Stamp requires a stable 5v supply input of at least 1.5A. This directly powers the 5v components and supplies the 3.3v LDOs with power. Typical idle usage is 0.35A @ 5v.
###
**Loading Firmware**
The board comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of *.apj firmware files with any ArduPilot compatible ground station.
A built in button can be used to activate DFU Mode by pressing during power up. The DFU Activate pin is broken out to allow remote mounting of this button if required.
For the full featured please use firmware "CBU-H7-Stamp"
For the low cost please use "CBU-H7-Stamp-LC"