HAL_ChibiOS: use BRD_OPTIONS to enable watchdog

# Conflicts:
#	libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp
This commit is contained in:
Andrew Tridgell 2019-04-20 13:54:14 +10:00
parent 348506b3c4
commit 5823a6b963
1 changed files with 8 additions and 2 deletions

View File

@ -27,6 +27,7 @@
#include "hwdef/common/usbcfg.h"
#include "hwdef/common/stm32_util.h"
#include "hwdef/common/watchdog.h"
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <hwdef.h>
@ -189,7 +190,10 @@ static THD_FUNCTION(main_loop,arg)
chThdSetPriority(APM_MAIN_PRIORITY);
// setup watchdog to reset if main loop stops
stm32_watchdog_init();
bool using_watchdog = AP_BoardConfig::watchdog_enabled();
if (using_watchdog) {
stm32_watchdog_init();
}
while (true) {
g_callbacks->loop();
@ -205,7 +209,9 @@ static THD_FUNCTION(main_loop,arg)
if (!schedulerInstance.check_called_boost()) {
hal.scheduler->delay_microseconds(250);
}
stm32_watchdog_pat();
if (using_watchdog) {
stm32_watchdog_pat();
}
}
thread_running = false;
}