Skip to content
Snippets Groups Projects
Commit 08b66e18 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

FastSerial: added set_blocking_writes() interface

this allows us to put a serial port into non-blocking mode, so that
writes that don't fit in the transmit buffer are dropped. This will be
used in flight to prevent stray printf() calls from causing large time
delays in the code
parent 36e741b0
No related branches found
No related tags found
No related merge requests found
......@@ -212,6 +212,13 @@ size_t FastSerial::write(uint8_t c)
// wait for room in the tx buffer
i = (_txBuffer->head + 1) & _txBuffer->mask;
// if the port is set into non-blocking mode, then drop the byte
// if there isn't enough room for it in the transmit buffer
if (_nonblocking_writes && i == _txBuffer->tail) {
return 0;
}
while (i == _txBuffer->tail)
;
......
......@@ -160,6 +160,11 @@ public:
return (1<<port) & _serialInitialized;
}
// ask for writes to be blocking or non-blocking
void set_blocking_writes(bool blocking) {
_nonblocking_writes = !blocking;
}
private:
/// Bit mask for initialized ports
......@@ -187,6 +192,10 @@ private:
Buffer * const _txBuffer;
bool _open;
// whether writes to the port should block waiting
// for enough space to appear
bool _nonblocking_writes;
/// Allocates a buffer of the given size
///
/// @param buffer The buffer descriptor for which the buffer will
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment