mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
DataFlash: leave room in buffer for non-startup messages
This commit is contained in:
parent
63a45000b4
commit
8f1471c137
@ -354,10 +354,22 @@ bool DataFlash_File::WritePrioritisedBlock(const void *pBuffer, uint16_t size, b
|
||||
uint16_t _head;
|
||||
uint16_t space = BUF_SPACE(_writebuf);
|
||||
|
||||
// we reserve some amount of space for critical messages:
|
||||
if (!is_critical && space < critical_message_reserved_space()) {
|
||||
_dropped++;
|
||||
return false;
|
||||
if (_writing_startup_messages &&
|
||||
_front._startup_messagewriter.fmt_done()) {
|
||||
// the state machine has called us, and it has finished
|
||||
// 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()) {
|
||||
// this message isn't dropped, it will be sent again...
|
||||
return false;
|
||||
}
|
||||
} else {
|
||||
// we reserve some amount of space for critical messages:
|
||||
if (!is_critical && space < critical_message_reserved_space()) {
|
||||
_dropped++;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// if no room for entire message - drop it:
|
||||
|
@ -115,6 +115,10 @@ private:
|
||||
// possibly make this a proportional to buffer size?
|
||||
return 1024;
|
||||
};
|
||||
uint16_t non_messagewriter_message_reserved_space() const {
|
||||
// possibly make this a proportional to buffer size?
|
||||
return 1024;
|
||||
};
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||
// performance counters
|
||||
|
Loading…
Reference in New Issue
Block a user