mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_ChibiOS: check all memory at 10Hz
This commit is contained in:
parent
95a823a702
commit
8f682c0782
@ -366,6 +366,10 @@ void Scheduler::_monitor_thread(void *arg)
|
|||||||
if (using_watchdog) {
|
if (using_watchdog) {
|
||||||
stm32_watchdog_save((uint32_t *)&hal.util->persistent_data, (sizeof(hal.util->persistent_data)+3)/4);
|
stm32_watchdog_save((uint32_t *)&hal.util->persistent_data, (sizeof(hal.util->persistent_data)+3)/4);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// if running memory guard then check all allocations
|
||||||
|
malloc_check(nullptr);
|
||||||
|
|
||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
uint32_t loop_delay = now - sched->last_watchdog_pat_ms;
|
uint32_t loop_delay = now - sched->last_watchdog_pat_ms;
|
||||||
if (loop_delay >= 200) {
|
if (loop_delay >= 200) {
|
||||||
|
Loading…
Reference in New Issue
Block a user