From 936eb89edbb07fbb921434d7f58d46305c81f4ca Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Tue, 8 Oct 2024 09:53:55 +0200 Subject: [PATCH] logger: fixed watchdog not logging, increased cycle trigger (#23769) --- src/modules/logger/logger.cpp | 13 ++++++++++++- src/modules/logger/watchdog.cpp | 8 +++++--- src/modules/logger/watchdog.h | 2 ++ 3 files changed, 19 insertions(+), 4 deletions(-) diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index 8d897a103a..ff5221d8b6 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -1615,6 +1615,11 @@ void Logger::initialize_load_output(PrintLoadReason reason) { // If already in progress, don't try to start again if (_next_load_print != 0) { + // To never miss watchdog triggers due to load measuring in progress, overwrite the measurement reason + if (reason == PrintLoadReason::Watchdog) { + _print_load_reason = reason; + } + return; } @@ -1635,7 +1640,13 @@ void Logger::write_load_output() _writer.set_need_reliable_transfer(true, _print_load_reason != PrintLoadReason::Watchdog); if (_print_load_reason == PrintLoadReason::Watchdog) { - PX4_ERR("Writing watchdog data"); // this is just that we see it easily in the log + // This is just that we see it easily in the log + PX4_ERR("Writing watchdog data..."); +#ifdef __PX4_NUTTX + bool cycle_trigger = _timer_callback_data.watchdog_data.triggered_by_cycle_delay; + bool ready_trigger = _timer_callback_data.watchdog_data.triggered_by_ready_delay; + PX4_ERR("Watchdog triggers - cycle trigger: %d, ready trigger: %d", cycle_trigger, ready_trigger); +#endif write_perf_data(PrintLoadReason::Watchdog); } diff --git a/src/modules/logger/watchdog.cpp b/src/modules/logger/watchdog.cpp index aa04bd0f6e..6816fa042c 100644 --- a/src/modules/logger/watchdog.cpp +++ b/src/modules/logger/watchdog.cpp @@ -129,10 +129,10 @@ bool watchdog_update(watchdog_data_t &watchdog_data, bool semaphore_value_satura watchdog_data.sem_counter_saturated_start = now; } - if (watchdog_data.manual_watchdog_trigger - || now > watchdog_data.sem_counter_saturated_start + 3_s - || now > watchdog_data.ready_to_run_timestamp + 1_s) { + bool cycle_trigger = now > watchdog_data.sem_counter_saturated_start + 5_s; + bool ready_trigger = now > watchdog_data.ready_to_run_timestamp + 1_s; + if (watchdog_data.manual_watchdog_trigger || cycle_trigger || ready_trigger) { sched_param param{}; // Get the current priorities @@ -153,6 +153,8 @@ bool watchdog_update(watchdog_data_t &watchdog_data, bool semaphore_value_satura sched_setparam(log_writer_task.tcb->pid, ¶m); + watchdog_data.triggered_by_cycle_delay = cycle_trigger; + watchdog_data.triggered_by_ready_delay = ready_trigger; watchdog_data.trigger_time = now; return true; } diff --git a/src/modules/logger/watchdog.h b/src/modules/logger/watchdog.h index 0ccfe0e4a9..aebd23ff14 100644 --- a/src/modules/logger/watchdog.h +++ b/src/modules/logger/watchdog.h @@ -56,6 +56,8 @@ struct watchdog_data_t { int logger_main_priority = 0; hrt_abstime trigger_time = 0; ///< timestamp when it was triggered bool manual_watchdog_trigger = false; + bool triggered_by_cycle_delay = false; + bool triggered_by_ready_delay = false; #endif /* __PX4_NUTTX */ };