From 0ef66659cec28bb51fc87d94e3a556bd9002ccbb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 28 Apr 2020 16:54:56 +1000 Subject: [PATCH] HAL_ChibiOS: log WDOG message once a second this copes with delayed mounting of the microSD, making it much more likely we log the critical data --- .../AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp | 16 ----------- libraries/AP_HAL_ChibiOS/Scheduler.cpp | 27 +++++++++++++++++++ 2 files changed, 27 insertions(+), 16 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index 647420fcba..5c5c701da2 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -223,22 +223,6 @@ static void main_loop() #ifndef HAL_NO_LOGGING if (hal.util->was_watchdog_reset()) { AP::internalerror().error(AP_InternalError::error_t::watchdog_reset); - 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,TN", "QbIIHHHHHIBIIn", - AP_HAL::micros64(), - pd.scheduler_task, - pd.internal_errors, - pd.internal_error_count, - pd.last_mavlink_msgid, - pd.last_mavlink_cmd, - pd.semaphore_line, - pd.fault_line, - pd.fault_type, - pd.fault_addr, - pd.fault_thd_prio, - pd.fault_icsr, - pd.fault_lr, - pd.thread_name4); } #endif // HAL_NO_LOGGING #endif // IOMCU_FW diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 20e790a167..d8819f0ce8 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -352,6 +352,9 @@ void Scheduler::_monitor_thread(void *arg) sched->delay(100); } bool using_watchdog = AP_BoardConfig::watchdog_enabled(); +#ifndef HAL_NO_LOGGING + uint8_t log_wd_counter = 0; +#endif while (true) { sched->delay(100); @@ -382,6 +385,30 @@ void Scheduler::_monitor_thread(void *arg) // at 500ms we declare an internal error AP::internalerror().error(AP_InternalError::error_t::main_loop_stuck); } + +#ifndef HAL_NO_LOGGING + if (log_wd_counter++ == 10 && hal.util->was_watchdog_reset()) { + log_wd_counter = 0; + // log watchdog message once a second + 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,TN", "QbIIHHHHHIBIIn", + AP_HAL::micros64(), + pd.scheduler_task, + pd.internal_errors, + pd.internal_error_count, + pd.last_mavlink_msgid, + pd.last_mavlink_cmd, + pd.semaphore_line, + pd.fault_line, + pd.fault_type, + pd.fault_addr, + pd.fault_thd_prio, + pd.fault_icsr, + pd.fault_lr, + pd.thread_name4); + } +#endif // HAL_NO_LOGGING + } } #endif // HAL_NO_MONITOR_THREAD