DataFlash: force messagewriters to completion

Setting a dataflash-file buffer size of less than or equal to 2kiB would
cause the startup-messagewriter to never push any messages other than
FMT out to the logs.

This is a combination of the return values of
critical_message_reserved_space and
non_messagewriter_message_reserved_space

This patch forces the startup messages out to the logs by ignoring the
space constraints every 100ms
This commit is contained in:
Peter Barker 2018-08-15 11:36:09 +10:00 committed by Peter Barker
parent fa5757f618
commit fa7ba7ddbc
2 changed files with 6 additions and 1 deletions

View File

@ -554,11 +554,15 @@ bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size,
// writing format messages out. It can always get back to us
// with more messages later, so let's leave room for other
// things:
if (space < non_messagewriter_message_reserved_space()) {
const uint32_t now = AP_HAL::millis();
const bool must_dribble = (now - last_messagewrite_message_sent) > 100;
if (!must_dribble &&
space < non_messagewriter_message_reserved_space()) {
// this message isn't dropped, it will be sent again...
semaphore->give();
return false;
}
last_messagewrite_message_sent = now;
} else {
// we reserve some amount of space for critical messages:
if (!is_critical && space < critical_message_reserved_space()) {

View File

@ -136,6 +136,7 @@ private:
}
return ret;
};
uint32_t last_messagewrite_message_sent;
// free-space checks; filling up SD cards under NuttX leads to
// corrupt filesystems which cause loss of data, failure to gather