AP_HAL_ChibiOS: Add a new target Holybro DroneCAN-pmu

This commit is contained in:
jamming 2024-09-04 10:19:37 +10:00 committed by Peter Barker
parent bfcac18eb2
commit 4d3e97533d
5 changed files with 205 additions and 0 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 63 KiB

View File

@ -0,0 +1,42 @@
# Holybro DroneCAN PMU
https://holybro.com/products/dronecan-pm08-power-module-14s-200a
## Features
- ProcessorSTM32F405RG 168MHz 1024KB Flash 196KB RAM
- Voltage input: 7~60.9V (2S~14S)
- Continuous current:200A
- Burst current 400A @ 25℃ 1 sec1000A @ 25℃ < 1 sec
- Max current sensing: 376A
- Voltage accuracy: ±0.1V
- Current accuracy: ±5%
- Temperature accuracy:±1℃
- Power port output: 5.3V/3A each port
- Protocol: DroneCAN
- Operating temperature :-25℃~105℃
- Firmware upgrade: Support
- Calibration: Support
## Interface Type
- Power & CAN Port: Molex CLIK-Mate 2mm 6Pin
- Battery IN/OUT Options:
--XT90 Connectors
--Tinned Wires
--XT90 & Ring Terminals
## Status LED
- Flashing quickly continuously: MCU is in the bootloader stage, waiting for firmware to be flashed
- Flashing quickly for 3 seconds, and then on for 1 second: Waiting for CAN connection
- Flashing slowly (one-second intervals): CAN is successfully connected
## Mechanical Spec
- Size: 45mm×41mm×26mm (not include cable)
- Weight: 185g (include cable)
## Loading Firmware
You can upgrade the *.bin firmware files using the DroneCan GUI tool. *.apj files can also be upgraded using mossionplanner ground station.

View File

@ -0,0 +1,6 @@
# Enable TSYS03
TEMP1_TYPE 4
TEMP1_SRC 3
TEMP1_SRC_ID 1

View File

@ -0,0 +1,43 @@
# hw definition file f405 Holybro CAN PMU
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# crystal frequency
OSCILLATOR_HZ 16000000
# board ID for firmware load
APJ_BOARD_ID 5401
# setup build for a peripheral firmware
env AP_PERIPH 1
FLASH_RESERVE_START_KB 0
FLASH_SIZE_KB 1024
FLASH_BOOTLOADER_LOAD_KB 64
PB0 LED_BOOTLOADER OUTPUT LOW GPIO(0) # blue
define HAL_LED_ON 0
# debug
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# order of UARTs
SERIAL_ORDER USART3
PC10 USART3_TX USART3
PC11 USART3_RX USART3
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PA15 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
define CAN_APP_NODE_NAME "org.ardupilot.f405_HolybroPMU"
# Add CS pins to ensure they are high in bootloader

View File

@ -0,0 +1,114 @@
# hw definition file for f405 Holybro CAN PMU
# 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 2 and 3
STORAGE_FLASH_PAGE 2
define HAL_STORAGE_SIZE 15360
# board ID for firmware load
APJ_BOARD_ID 5401
env AP_PERIPH 1
define STM32_ST_USE_TIMER 5
define CH_CFG_ST_RESOLUTION 32
# enable watchdog
# crystal frequency
OSCILLATOR_HZ 16000000
STDOUT_SERIAL SD3
STDOUT_BAUDRATE 57600
# blue LED0 marked as ACT
PB0 LED OUTPUT HIGH GPIO(90)
define AP_NOTIFY_GPIO_LED_1_ENABLED 1
define AP_NOTIFY_GPIO_LED_1_PIN 90
define HAL_NO_GPIO_IRQ
define SERIAL_BUFFERS_SIZE 512
define PORT_INT_REQUIRED_STACK 64
# debug
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# avoid timer and RCIN threads to save memory
define HAL_NO_RCIN_THREAD
define HAL_USE_RTC FALSE
define DISABLE_SERIAL_ESC_COMM TRUE
define DMA_RESERVE_SIZE 0
define HAL_DEVICE_THREAD_STACK 768
# we setup a small defaults.parm
define AP_PARAM_MAX_EMBEDDED_PARAM 256
# keep ROMFS uncompressed as we don't have enough RAM
# to uncompress the bootloader at runtime
env ROMFS_UNCOMPRESSED True
# ---------------------- CAN bus -------------------------
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PA15 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
# use DNA for node allocation
define CAN_APP_NODE_NAME "org.ardupilot.f405_HolybroPMU"
# ---------------------- UARTs ---------------------------
#
SERIAL_ORDER USART3
# USART3, for debug
PC10 USART3_TX USART3 SPEED_HIGH NODMA
PC11 USART3_RX USART3 SPEED_HIGH NODMA
# ---------------------- I2Cs ---------------------------
#
I2C_ORDER I2C1
# I2C2, for TEMP SENSOR
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
# ------------------ BATTERY Monitor -----------------------
define HAL_PERIPH_ENABLE_BATTERY
define HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE
define HAL_USE_ADC TRUE
define STM32_ADC_USE_ADC1 TRUE
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
# Set the Default Battery Monitor Type to be Analog I/V
define HAL_BATT_MONITOR_DEFAULT 4
define HAL_BATT_VOLT_PIN 10
define HAL_BATT_VOLT_SCALE 18.0
define HAL_BATT_CURR_PIN 11
define HAL_BATT_CURR_SCALE 125
# ACS772-400U Zero-Current Offset
define AP_BATT_CURR_AMP_OFFSET_DEFAULT 0.409
# ------------------ Temperature Sensor -----------------------
define AP_TEMPERATURE_SENSOR_ENABLED 1
define AP_TEMPERATURE_SENSOR_TSYS03_ENABLED 1
define AP_TEMPERATURE_SENSOR_I2C_ADDR_DEFAULT 64
define AP_TEMPERATURE_SENSOR_I2C_BUS_DEFAULT 0