HAL_ChibiOS: enable watchdog in AP_Periph firmwares
This commit is contained in:
parent
e392416942
commit
910129eafc
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user