diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index 0b60c8ba57..d29b8aeaf3 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -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 diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index b934bed4eb..b676f5482d 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -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