Minor changes to follow coding style and improve readability:
- sort headers
- move struct definition to compilation unit rather than header
- Add braces to if, for, etc
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.
Many of our SPI and I2C sensors define the protocol of setting the most
significant bit of the register address in order to perform a read operation.
Thus, enable the use of a "read flag" that is ORed with the register's address.
Since this is an abstraction for general devices, it's a good idea to have zero
as the default value for that flag.
While at it, add documentation to read_registers().
Minlure has an onboard compass (HMC5883L) as slave of MPU-6000, but also
allows the use of an external HMC5883L compass, which should be
connected to the lure's I2C port.
../../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.