AP_HAL: Ensure scheduler does not log if there is no logger

This commit is contained in:
Stephen Dade 2019-11-14 15:58:38 +11:00 committed by Andrew Tridgell
parent 08e18ccdfe
commit e1e7c6ea8a

View File

@ -352,6 +352,7 @@ 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;
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,
@ -364,6 +365,7 @@ void Scheduler::_monitor_thread(void *arg)
pd.spi_count,
pd.i2c_count);
}
}
if (loop_delay >= 500) {
// at 500ms we declare an internal error
AP::internalerror().error(AP_InternalError::error_t::main_loop_stuck);