ardupilot/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.h
Andrew Tridgell cec6f0e3d4 HAL_ChibiOS: implement scheduler->expect_delay_ms()
# Conflicts:
#	libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp
#	libraries/AP_HAL_ChibiOS/Scheduler.h
2019-04-20 13:57:23 +10:00

36 lines
529 B
C

#ifdef __cplusplus
extern "C" {
#endif
/*
setup the watchdog
*/
void stm32_watchdog_init(void);
/*
pat the dog, to prevent a reset. If not called for 1s
after stm32_watchdog_init() then MCU will reset
*/
void stm32_watchdog_pat(void);
/*
return true if reboot was from a watchdog reset
*/
bool stm32_was_watchdog_reset(void);
/*
save the reset reason code
*/
void stm32_watchdog_save_reason(void);
/*
clear reset reason code
*/
void stm32_watchdog_clear_reason(void);
#ifdef __cplusplus
}
#endif