hwdef: added AR-F407SmartBat
balance plug DroneCAN periph node
This commit is contained in:
parent
65537bdaca
commit
e1f3cb9f71
41
libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef-bl.dat
Normal file
41
libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef-bl.dat
Normal file
@ -0,0 +1,41 @@
|
||||
# hw definition file ARACE SmartBat CAN node
|
||||
|
||||
# MCU class and specific type
|
||||
MCU CKS32F4xx CKS32F407xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1134
|
||||
|
||||
# CKS32F407 does not work in bootloader with normal optimisation
|
||||
env OPTIMIZE -Og
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
FLASH_RESERVE_START_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 64
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# ---------------------------------------------
|
||||
PC12 LED_BOOTLOADER OUTPUT LOW # green
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH
|
||||
|
||||
CAN_ORDER 1
|
||||
|
||||
define HAL_USE_SERIAL FALSE
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define SERIAL_BUFFERS_SIZE 32
|
||||
define HAL_USE_EMPTY_IO TRUE
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
63
libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef.dat
Normal file
63
libraries/AP_HAL_ChibiOS/hwdef/AR-F407SmartBat/hwdef.dat
Normal file
@ -0,0 +1,63 @@
|
||||
# hw definition file for ARACE SmartBat
|
||||
|
||||
# MCU class and specific type
|
||||
MCU CKS32F4xx CKS32F407xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1134
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
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
|
||||
|
||||
# activity LED
|
||||
PC12 LED OUTPUT LOW # green
|
||||
define HAL_LED_ON 0
|
||||
|
||||
# enable CAN support
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW HIGH
|
||||
|
||||
CAN_ORDER 1
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_NO_LOGGING
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
SERIAL_ORDER USART1
|
||||
|
||||
# USART1 for debug
|
||||
PA9 USART1_TX USART1 SPEED_HIGH
|
||||
PA10 USART1_RX USART1 SPEED_HIGH
|
||||
|
||||
# ADC inputs, scale 10 is used so voltages
|
||||
# stay in 3.3v max range with 6S
|
||||
PC0 CELL1 ADC1 SCALE(10) ANALOG(1)
|
||||
PC1 CELL2 ADC1 SCALE(10) ANALOG(2)
|
||||
PC2 CELL3 ADC1 SCALE(10) ANALOG(3)
|
||||
PC3 CELL4 ADC1 SCALE(10) ANALOG(4)
|
||||
PA0 CELL5 ADC1 SCALE(10) ANALOG(5)
|
||||
PA1 CELL6 ADC1 SCALE(10) ANALOG(6)
|
||||
|
||||
# setup as a battery balance plug monitor
|
||||
define HAL_PERIPH_ENABLE_BATTERY_BALANCE
|
||||
define AP_PERIPH_BATTERY_BALANCE_NUMCELLS_DEFAULT 6
|
||||
define AP_PERIPH_BATTERY_BALANCE_RATE_DEFAULT 2
|
||||
define AP_PERIPH_BATTERY_BALANCE_CELL1_PIN_DEFAULT 1
|
||||
define AP_PERIPH_BATTERY_BALANCE_ID_DEFAULT 0
|
||||
|
Loading…
Reference in New Issue
Block a user