diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 90d7007482..66c811847e 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -352,17 +352,19 @@ void Scheduler::_monitor_thread(void *arg) // the main loop has been stuck for at least // 200ms. Starting logging the main loop state const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; - AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIIHHHII", - AP_HAL::micros64(), - loop_delay, - pd.scheduler_task, - pd.internal_errors, - pd.internal_error_count, - pd.last_mavlink_msgid, - pd.last_mavlink_cmd, - pd.semaphore_line, - pd.spi_count, - pd.i2c_count); + if (AP_Logger::get_singleton()) { + AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIIHHHII", + AP_HAL::micros64(), + loop_delay, + pd.scheduler_task, + pd.internal_errors, + pd.internal_error_count, + pd.last_mavlink_msgid, + pd.last_mavlink_cmd, + pd.semaphore_line, + pd.spi_count, + pd.i2c_count); + } } if (loop_delay >= 500) { // at 500ms we declare an internal error