mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: support external watchdog gpio
Co-authored-by: Randy Mackay <rmackay9@yahoo.com> optional support to toggle GPIO pin at 10hz
This commit is contained in:
parent
cce16c9ada
commit
7b60ac7afa
|
@ -764,8 +764,23 @@ void Scheduler::watchdog_pat(void)
|
||||||
{
|
{
|
||||||
stm32_watchdog_pat();
|
stm32_watchdog_pat();
|
||||||
last_watchdog_pat_ms = AP_HAL::millis();
|
last_watchdog_pat_ms = AP_HAL::millis();
|
||||||
|
#if defined(HAL_GPIO_PIN_EXT_WDOG)
|
||||||
|
ext_watchdog_pat(last_watchdog_pat_ms);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if defined(HAL_GPIO_PIN_EXT_WDOG)
|
||||||
|
// toggle the external watchdog gpio pin
|
||||||
|
void Scheduler::ext_watchdog_pat(uint32_t now_ms)
|
||||||
|
{
|
||||||
|
// toggle watchdog GPIO every WDI_OUT_INTERVAL_TIME_MS
|
||||||
|
if ((now_ms - last_ext_watchdog_ms) >= EXT_WDOG_INTERVAL_MS) {
|
||||||
|
palToggleLine(HAL_GPIO_PIN_EXT_WDOG);
|
||||||
|
last_ext_watchdog_ms = now_ms;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
|
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
|
||||||
/*
|
/*
|
||||||
check we have enough stack free on all threads and the ISR stack
|
check we have enough stack free on all threads and the ISR stack
|
||||||
|
|
|
@ -193,5 +193,11 @@ private:
|
||||||
|
|
||||||
// check for free stack space
|
// check for free stack space
|
||||||
void check_stack_free(void);
|
void check_stack_free(void);
|
||||||
|
|
||||||
|
#if defined(HAL_GPIO_PIN_EXT_WDOG)
|
||||||
|
// external watchdog GPIO support
|
||||||
|
void ext_watchdog_pat(uint32_t now_ms);
|
||||||
|
uint32_t last_ext_watchdog_ms;
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue