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 us to use the MS5611 barometer at its full 100Hz sample
rate (80Hz for pressure, 20Hz for temperature). The pressure and
temperature values are averaged between reads without adding any
latency. Previously the driver would throw away values between
readings
This also fixes a race condition in reading from the SPI bus that
could lead to bad values from the barometer
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
Believe it or not, changing / 2^31 to >>31 saved 256 bytes in the "d" segment.
The reason is that GCC version prior to 4.3.5 does not have a count_leading_zeros (clz) assembler macro, so it uses a 256 byte lookup table called _clz
The _clz table gets pulled in if you do 64 bit division.
This tiny change is the only place that we do long long division.
Changing to a shift saves 256 bytes of ram.
* Wire.begin removed from AP_Baro_BMP085::init()
* SPI.begin removed from AP_Baro_MS5611::init()
* SPI.begin removed from AP_InertialSensor_MPU6000::hardware_init()
* Both Wire.begin and SPI.begin added very early in init_ardupilot in
ArduCopter/system.pde and ArduPlane/system.pde