AP_Logger: tidy running of LoggerMessageWriter sub-writers

... use the fact these all have a common base class to reduce effectively duplicate code.

Also un-virtualise and const a function which wasn't overridden and can be const
This commit is contained in:
Peter Barker 2024-06-14 17:56:22 +10:00 committed by Peter Barker
parent 12197b2d60
commit b5b42f9446
2 changed files with 16 additions and 26 deletions

View File

@ -177,40 +177,30 @@ void LoggerMessageWriter_DFLogStart::process()
stage = Stage::RUNNING_SUBWRITERS;
FALLTHROUGH;
case Stage::RUNNING_SUBWRITERS:
if (!_writesysinfo.finished()) {
_writesysinfo.process();
if (!_writesysinfo.finished()) {
return;
}
}
case Stage::RUNNING_SUBWRITERS: {
LoggerMessageWriter *subwriters[] {
&_writesysinfo,
#if AP_MISSION_ENABLED
if (!_writeentiremission.finished()) {
_writeentiremission.process();
if (!_writeentiremission.finished()) {
return;
}
}
&_writeentiremission,
#endif
#if HAL_LOGGER_RALLY_ENABLED
if (!_writeallrallypoints.finished()) {
_writeallrallypoints.process();
if (!_writeallrallypoints.finished()) {
return;
}
}
&_writeallrallypoints,
#endif
#if HAL_LOGGER_FENCE_ENABLED
if (!_writeallpolyfence.finished()) {
_writeallpolyfence.process();
if (!_writeallpolyfence.finished()) {
&_writeallpolyfence,
#endif
};
for (auto *sw : subwriters) {
if (!sw->finished()) {
sw->process();
if (!sw->finished()) {
return;
}
}
#endif
}
stage = Stage::VEHICLE_MESSAGES;
FALLTHROUGH;
}
case Stage::VEHICLE_MESSAGES:
// we guarantee 200 bytes of space for the vehicle startup
// messages. This allows them to be simple functions rather

View File

@ -8,7 +8,7 @@ public:
virtual void reset() = 0;
virtual void process() = 0;
virtual bool finished() { return _finished; }
bool finished() const { return _finished; }
virtual void set_logger_backend(class AP_Logger_Backend *backend) {
_logger_backend = backend;