ardupilot/libraries/AP_HAL_ChibiOS/hwdef/CubeNode/hwdef-bl.dat

53 lines
976 B
Plaintext

# hw definition file for processing by chibios_hwdef.py
# MCU class and specific type
MCU STM32H7xx STM32H757xx
define CORE_CM7
define SMPS_PWR
# board ID for firmware load
APJ_BOARD_ID 1079
FLASH_SIZE_KB 2048
# setup build for a peripheral firmware
env AP_PERIPH 1
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
# the H757 has 128k sectors, assign 2 sectors for BL
FLASH_BOOTLOADER_LOAD_KB 256
# crystal frequency
OSCILLATOR_HZ 24000000
# CAN1
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
# CAN2
#PB5 CAN2_RX CAN2
#PB6 CAN2_TX CAN2
# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
# SERIAL
PE7 UART7_RX UART7
PE8 UART7_TX UART7
SERIAL_ORDER OTG1 UART7
# CAN Common
PG1 SLEEPCAN OUTPUT PUSHPULL SPEED_LOW LOW
PG0 SHUTDOWNCAN OUTPUT PUSHPULL SPEED_LOW LOW
# These are the pins for SWD debugging with a STlinkv2 or black-magic probe.
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD