Instead of depending on the frequency accumulate() is called, use
AverageIntegralFilter with 10 samples. The data obtained by BMP085 is
too noisy with any value of OVERSAMPLING so use twice the number of
samples as currently used. Besides that now we are sure there's always
10 samples used in the average.
The temperature readings is not subject to white noise so there's no
point in averaging its reading. Moreover since for a normal 50Hz
accumulate() / 10Hz update() it would read temperature only once per
update(), it's pointless to keep averaging and introducing rounding
error.
The temperature doesn't need to be checked as frequent as pressure, too.
The datasheet even suggests on section 3.3, page 10 to enable standard
mode and read the temperature at 1Hz. Here we reduce it to 2Hz
(considering the accumulate() function being called at 50Hz).
We don't need to expose to other libraries how each backend is
implemented. AP_Baro.h is the main header, included by other libraries.
Instead of including each backend in the main header, move them to where
they are needed. Additionally standardize the order and how we include
the headers.
The advantages are:
- Internals of each backend is not exposed outside of the
library
- Faster incremental builds since we don't need to recompile
whoever includes AP_Baro.h because a backend changed
this changes the barometer calculations to floating point. On a MS5611
this is actually about twice as fast as the previous 64 bit
calculations, but gains us more accuracy as we are able to take
advantage of sub-bit precision when we average over 8 samples.
this allows the barometer driver to calibrate and return altitude and
climb rate values. This will be used by the AHRS drift correction code
for vertical velocity
The climb rate uses a 5 point average filter
the averaging array was using 16 bit numbers, but we are storing
numbers with 19 significant bits. That caused overflow at high
altitude, and some very interesting altitude graphs!
Thanks to Michael Oborne for spotting this in a log