diff --git a/libraries/AP_Logger/LoggerMessageWriter.cpp b/libraries/AP_Logger/LoggerMessageWriter.cpp index 35fde7f01b..3918fc6226 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.cpp +++ b/libraries/AP_Logger/LoggerMessageWriter.cpp @@ -71,7 +71,7 @@ void LoggerMessageWriter_DFLogStart::reset() ap = AP_Param::first(&token, &type, ¶m_default); } -bool LoggerMessageWriter_DFLogStart::out_of_time_for_writing_messages() const +bool LoggerMessageWriter_DFLogStart::out_of_time_for_writing_messages_df() const { if (stage == Stage::FORMATS) { // write out the FMT messages as fast as we can @@ -99,7 +99,7 @@ bool LoggerMessageWriter_DFLogStart::check_process_limit(uint32_t start_us) void LoggerMessageWriter_DFLogStart::process() { - if (out_of_time_for_writing_messages()) { + if (out_of_time_for_writing_messages_df()) { return; } // allow any stage to run for max 1ms, to prevent a long loop on arming diff --git a/libraries/AP_Logger/LoggerMessageWriter.h b/libraries/AP_Logger/LoggerMessageWriter.h index c8fdd9ad72..2e28503676 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.h +++ b/libraries/AP_Logger/LoggerMessageWriter.h @@ -14,7 +14,7 @@ public: _logger_backend = backend; } - virtual bool out_of_time_for_writing_messages() const; + bool out_of_time_for_writing_messages() const; protected: bool _finished = false; @@ -124,7 +124,7 @@ public: #endif } - bool out_of_time_for_writing_messages() const override final; + bool out_of_time_for_writing_messages_df() const; void reset() override; void process() override;