HAL_ChibiOS: enable watchdog in AP_Periph firmwares

This commit is contained in:
Andrew Tridgell 2019-10-20 21:50:04 +11:00
parent e392416942
commit 910129eafc
3 changed files with 9 additions and 0 deletions

View File

@ -19,6 +19,9 @@ env AP_PERIPH 1
STM32_ST_USE_TIMER 5
# enable watchdog
define HAL_WATCHDOG_ENABLED_DEFAULT true
# crystal frequency
OSCILLATOR_HZ 16000000

View File

@ -68,6 +68,9 @@ PB11 USART3_RX USART3 SPEED_HIGH NODMA
# don't enable DMA in UART driver
define HAL_UART_NODMA
# enable watchdog
define HAL_WATCHDOG_ENABLED_DEFAULT true
# enable CAN support
PA11 CAN_RX CAN
PB9 CAN_TX CAN

View File

@ -16,6 +16,9 @@ APJ_BOARD_ID 1000
# setup build for a peripheral firmware
env AP_PERIPH 1
# enable watchdog
define HAL_WATCHDOG_ENABLED_DEFAULT true
# crystal frequency
OSCILLATOR_HZ 8000000