mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: don't virtual out_of_time_for_writing_messages for DF
This save use some flash against the solution with override
This commit is contained in:
parent
06836b947f
commit
01f94e9aa5
|
@ -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
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue