HAL_ChibiOS: setup watchdog_reset internal error

This commit is contained in:
Andrew Tridgell 2019-04-20 12:58:48 +10:00
parent d5c2b77573
commit 63d21d995a

View File

@ -28,6 +28,7 @@
#include "hwdef/common/stm32_util.h"
#include "hwdef/common/watchdog.h"
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_InternalError/AP_InternalError.h>
#include <hwdef.h>
@ -208,6 +209,10 @@ static void main_loop()
stm32_watchdog_init();
}
if (hal.util->was_watchdog_reset()) {
AP::internalerror().error(AP_InternalError::error_t::watchdog_reset);
}
while (true) {
g_callbacks->loop();