Due to the way the headers are organized changing a single change in an
inertial sensor driver would trigger a rebuild for most of the files in
the project. Time could be saved by using ccache (since most of the
things didn't change) but we can do better, i.e. re-organize the headers
so we don't have to re-build everything.
With this patch only AP_InertialSensor/AP_InertialSensor.h is exposed to
most users. There are some corner cases to integrate with some example
code, but most of the places now depend only on this header and this
header doesn't depend on the specific backends.
Now changing a single header, e.g. AP_InertialSensor_L3G4200D.h triggers
a rebuild only of these files:
$ waf copter
'copter' finished successfully (0.000s)
Waf: Entering directory `/home/lucas/p/dronecode/ardupilot/build/minlure'
[ 80/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor.cpp
[ 84/370] Compiling libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp
[310/370] Linking build/minlure/ArduCopter/libArduCopter_libs.a
[370/370] Linking build/minlure/bin/arducopter
Waf: Leaving directory `/home/lucas/p/dronecode/ardupilot/build/minlure'
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.