This allows each sensor to be uniquely identified in the system by using
either the index inside the backend or for those that use the Device
interface, to use the bus type, location, and device id.
We leave 16-bit for each sensor to be able to change its own
identification in future, which allows them to be changed in an
incompatible manner forcing a re-calibration.
The PSTR is already define as a NOP for all supported platforms. It's
only needed for AVR so here we remove all the uses throughout the
codebase.
This was automated with a simple python script so it also converts
places which spans to multiple lines, removing the matching parentheses.
AVR-specific places were not changed.
These changes are for enabling unified accelerometer vibration and clipping
calculation. For that, we need the values "rotated and corrected" before they
are filtered and the calculation must be called as soon as a new sample arrives
as it takes the sample rate into account.
Thus, move code that applies "corrections" to be executed as soon as accel data
arrive and call _publish_accel() passing rotate_and_correct parameter as false.
Also, do the same for gyro so we can keep it consistent.
This commit changes the way libraries headers are included in source files:
- If the header is in the same directory the source belongs to, so the
notation '#include ""' is used with the path relative to the directory
containing the source.
- If the header is outside the directory containing the source, then we use
the notation '#include <>' with the path relative to libraries folder.
Some of the advantages of such approach:
- Only one search path for libraries headers.
- OSs like Windows may have a better lookup time.
The main thread would always be blocked on the semaphore to read the
data from accelerometer and gyroscope. Especially if we have a slow
update of these values in _accumulate() due to the I2C transfer function
taking too much time: the timer thread would never give up the CPU,
causing starvation on the main thread.
This fixes the issue by reducing the critical region using a flip-buffer
so _accumulate() can work on its own copy of the data. Now that the
critical region is smaller, also avoid the semaphore and use a spinlock
instead.