By opening with O_CLOEXEC we make sure we don't leak the file descriptor
when we are exec'ing or calling out subprograms. Right now we currently
don't do it so there's no harm, but it's good practice in Linux to have
it.
RC_Channel: To nullptr from NULL.
AC_Fence: To nullptr from NULL.
AC_Avoidance: To nullptr from NULL.
AC_PrecLand: To nullptr from NULL.
DataFlash: To nullptr from NULL.
SITL: To nullptr from NULL.
GCS_MAVLink: To nullptr from NULL.
DataFlash: To nullptr from NULL.
AP_Compass: To nullptr from NULL.
Global: To nullptr from NULL.
Global: To nullptr from NULL.
Sometimes (like in DataFlash) the size of the ring buffer will be
determined in run time and the object can have size zero until proper
initialization. When this was the case, an underflow in ::get_size would
mess with the initializing algorithm.
Another issue was that the 'new' operator could fail what was not being
handled. Now, we only set the size member after we are sure 'new'
successfully allocated memory.
Volatile will provide protection to sequence re-ordering and guarantee
the variable is fetched from memory, but it won't provide the memory
barrier needed to ensure that no re-ordering (by either the compiler or
the CPU) will happen among other threads of execution
accessing the same variables.
For more info about this effect can be found on articles about
std::memory_order.
When using reserved(), the reserved memory cannot be read before it's
written, therefore we cannot update 'tail' until the caller of
reserved() is done writing.
To solve that, a method called 'commit()' was added so the caller can
inform that is done with the memory usage and is safe to update 'tail'.
The caller also has to inform the length that was actually written.
This solution was developed to work considering the usage context of
this class: 1 reader and 1 writer **only**.
Adds a method called `reserve()`, that will take a ByteBuffer::IoVec
array of at least two elements, and return the number of elements
filled out. 0 will be returned if `len` is over the total space of
the buffer; 1 will be returned if there's enough contiguous bytes in
the buffer; 2 will be returned if there are two non-contiguous blocks
of memory.
This method is suitable to be used with POSIX system calls such as
readv(), and is an optimization to not require temporary memory copies
while reading from a file descriptor.
Also modify the write() method to use reserve(), so that similar checks
are performed only in one place.
Modify ByteBuffer class to have a `peekiovec()` method, that takes in a
`struct IoVec` array (similar to `struct iovec` from POSIX), and a
number of bytes, and returns the number of elements from this array
that have been filled out. It is either 0 (buffer is empty), 1
(there's enough contiguous bytes to read that amount) or 2 (ring buffer
is wrapping around).
This enables using scatter-gather I/O (i.e. writev()), removing calls
to memcpy(). That's one call when no wrap-around is happening, and
two calls if it is.
Also, rewrite `ByteBuffer::peekbytes()` to use `peekiovec()`, so that
some of the checks performed by the former are not replicated in the
latter.
../../libraries/AP_HAL/examples/Printf/Printf.cpp:63:17: warning: comparison between signed and unsigned integer expressions [-Wsign-compare]
if (ret != strlen(float_tests[i].result)) {
^
...
ardupilot/modules/gtest/include/gtest/gtest.h:1448:16: warning: comparison between signed and unsigned integer expressions [-Wsign-compare]
if (expected == actual) {
^
And similar ones.
This is very similar to std::unique_ptr, but doesn't require including
the <memory> header which pulls lots of c++ headers and cause problems
with nuttx headers. It's header-only. It contains an explanation on what
it solves, how to use and unit tests.
Fix warning that reveals a real bug:
In file included from libraries/AP_HAL_Linux/UARTDriver.cpp:25:0:
libraries/AP_HAL_Linux/UARTDriver.cpp: In member function 'virtual bool Linux::UARTDriver::tx_pending()':
libraries/AP_HAL/utility/RingBuffer.h:21:35: warning: logical not is only applied to the left hand side of comparison [-Wlogical-not-parentheses]
#define BUF_EMPTY(buf) buf##_head == buf##_tail
^
libraries/AP_HAL_Linux/UARTDriver.cpp:355:13: note: in expansion of macro 'BUF_EMPTY'
return !BUF_EMPTY(_writebuf);
The problem is when there's a ! operator: without the parenthesis we would actually be doing
return !_write_buf_head == _write_buf_tail
which is not what we want.