mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_BoardConfig: allow enable of watchdog in hwdef.dat
this will be used for AP_Periph
This commit is contained in:
parent
40431100a9
commit
e392416942
@ -29,6 +29,10 @@
|
|||||||
#include <AP_Radio/AP_Radio.h>
|
#include <AP_Radio/AP_Radio.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef HAL_WATCHDOG_ENABLED_DEFAULT
|
||||||
|
#define HAL_WATCHDOG_ENABLED_DEFAULT false
|
||||||
|
#endif
|
||||||
|
|
||||||
extern "C" typedef int (*main_fn_t)(int argc, char **);
|
extern "C" typedef int (*main_fn_t)(int argc, char **);
|
||||||
|
|
||||||
class AP_BoardConfig {
|
class AP_BoardConfig {
|
||||||
@ -162,7 +166,7 @@ public:
|
|||||||
|
|
||||||
// return true if watchdog enabled
|
// return true if watchdog enabled
|
||||||
static bool watchdog_enabled(void) {
|
static bool watchdog_enabled(void) {
|
||||||
return _singleton?(_singleton->_options & BOARD_OPTION_WATCHDOG)!=0:false;
|
return _singleton?(_singleton->_options & BOARD_OPTION_WATCHDOG)!=0:HAL_WATCHDOG_ENABLED_DEFAULT;
|
||||||
}
|
}
|
||||||
|
|
||||||
// handle press of safety button. Return true if safety state
|
// handle press of safety button. Return true if safety state
|
||||||
|
Loading…
Reference in New Issue
Block a user