ardupilot/libraries/AP_HAL_ChibiOS/hwdef/HereCommon/hwdef-bl.inc

64 lines
1.1 KiB
PHP
Raw Normal View History

2021-08-17 04:36:20 -03:00
# hw definition file for processing by chibios_hwdef.py
# for H757
# MCU class and specific type
MCU STM32H7xx STM32H757xx
define CORE_CM7
define SMPS_PWR
# setup build for a peripheral firmware
env AP_PERIPH 1
FLASH_SIZE_KB 2048
# the location where the bootloader will put the firmware
# the H743 has 128k sectors
FLASH_BOOTLOADER_LOAD_KB 256
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# crystal frequency
OSCILLATOR_HZ 24000000
PB14 USART1_TX USART1
PB15 USART1_RX USART1
PA0 USART2_CTS USART2
PA1 USART2_RTS USART2
PA2 USART2_TX USART2
PA3 USART2_RX USART2
PD9 USART3_RX USART3
PD8 USART3_TX USART3
SERIAL_ORDER OTG1 USART1 USART2 USART3
PA4 MCU_DCD OUTPUT LOW
PA5 MCU_DTR OUTPUT LOW
PA6 MCU_POW_ON OUTPUT HIGH
PA7 MCU_IO_2 OUTPUT LOW
# now we define the pins that USB is connected on
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define USB_USE_WAIT TRUE
define HAL_USE_USB_MSD TRUE
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PB3 LED_BOOTLOADER OUTPUT HIGH
PB4 LED OUTPUT HIGH
PB13 LED_2 OUTPUT HIGH
define HAL_LED_ON 0
# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PC7 SLEEPCAN OUTPUT PUSHPULL SPEED_LOW LOW