AP_HAL_ChibiOS: send statustext at regular intervals after watchdog reset

This commit is contained in:
Peter Barker 2020-03-25 22:07:49 +11:00 committed by Peter Barker
parent fed8ecc3b0
commit 9ba2aecbb8

View File

@ -166,8 +166,6 @@ thread_t* get_main_thread()
static AP_HAL::HAL::Callbacks* g_callbacks; static AP_HAL::HAL::Callbacks* g_callbacks;
static AP_HAL::Util::PersistentData last_persistent_data;
static void main_loop() static void main_loop()
{ {
daemon_task = chThdGetSelfX(); daemon_task = chThdGetSelfX();
@ -207,7 +205,7 @@ static void main_loop()
if (stm32_was_watchdog_reset()) { if (stm32_was_watchdog_reset()) {
// load saved watchdog data // load saved watchdog data
stm32_watchdog_load((uint32_t *)&utilInstance.persistent_data, (sizeof(utilInstance.persistent_data)+3)/4); stm32_watchdog_load((uint32_t *)&utilInstance.persistent_data, (sizeof(utilInstance.persistent_data)+3)/4);
last_persistent_data = utilInstance.persistent_data; utilInstance.last_persistent_data = utilInstance.persistent_data;
} }
schedulerInstance.hal_initialized(); schedulerInstance.hal_initialized();
@ -225,7 +223,7 @@ static void main_loop()
#ifndef HAL_NO_LOGGING #ifndef HAL_NO_LOGGING
if (hal.util->was_watchdog_reset()) { if (hal.util->was_watchdog_reset()) {
AP::internalerror().error(AP_InternalError::error_t::watchdog_reset); AP::internalerror().error(AP_InternalError::error_t::watchdog_reset);
const AP_HAL::Util::PersistentData &pd = last_persistent_data; const AP_HAL::Util::PersistentData &pd = hal.util->last_persistent_data;
AP::logger().WriteCritical("WDOG", "TimeUS,Tsk,IE,IEC,MvMsg,MvCmd,SmLn,FL,FT,FA,FP,ICSR,LR", "QbIIHHHHHIBII", AP::logger().WriteCritical("WDOG", "TimeUS,Tsk,IE,IEC,MvMsg,MvCmd,SmLn,FL,FT,FA,FP,ICSR,LR", "QbIIHHHHHIBII",
AP_HAL::micros64(), AP_HAL::micros64(),
pd.scheduler_task, pd.scheduler_task,