HAL_ChibiOS: log mavlink IDs and semaphore lines for watchdog

this gives a better chance of tracking down a hang
This commit is contained in:
Andrew Tridgell 2019-05-11 18:19:25 +10:00
parent c786674442
commit 8d0bca6ba9
2 changed files with 10 additions and 4 deletions

View File

@ -214,11 +214,14 @@ static void main_loop()
if (hal.util->was_watchdog_reset()) {
AP::internalerror().error(AP_InternalError::error_t::watchdog_reset);
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
AP::logger().Write("WDOG", "TimeUS,Task,IErr,IErrCnt", "QbII",
AP::logger().Write("WDOG", "TimeUS,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine", "QbIIHHH",
AP_HAL::micros64(),
pd.scheduler_task,
pd.internal_errors,
pd.internal_error_count);
pd.internal_error_count,
pd.last_mavlink_msgid,
pd.last_mavlink_cmd,
pd.semaphore_line);
}
#endif

View File

@ -351,12 +351,15 @@ void Scheduler::_monitor_thread(void *arg)
// the main loop has been stuck for at least
// 200ms. Starting logging the main loop state
AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt", "QIbII",
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine", "QIbIIHHH",
AP_HAL::micros64(),
loop_delay,
pd.scheduler_task,
pd.internal_errors,
pd.internal_error_count);
pd.internal_error_count,
pd.last_mavlink_msgid,
pd.last_mavlink_cmd,
pd.semaphore_line);
}
if (loop_delay >= 500) {
// at 500ms we declare an internal error