AP_Baro: BMP085: change oversampling in BMP085 without EOC

If we don't have EOC pin and assuming the accumulate() function is
called at 50Hz (or higher) we would take very few samples to accumulate
before the update is called. That's because since we have to wait 26ms
to get a sample and we calling accumulate() every 20ms, half of the
times it will return without getting anything.  So we will
be using 2 or 3 samples only to average.

If we don't have EOC, use OVERSAMPLING=2 which gives us more noise, but
that we can filter out by using measurements to average. When we have
EOC we don't need it because most of the time the conversion will take
less than 20ms: I'm getting 16ms on most of them while bench-testing.
This commit is contained in:
Lucas De Marchi 2015-07-11 16:37:22 -03:00
parent 37e2f6c52e
commit 56fa1b6214

View File

@ -29,9 +29,10 @@ extern const AP_HAL::HAL &hal;
#ifndef BMP085_EOC
#define BMP085_EOC -1
#endif
#define OVERSAMPLING BMP085_OVERSAMPLING_ULTRAHIGHRES
#else
#define OVERSAMPLING BMP085_OVERSAMPLING_HIGHRES
#endif
AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
: AP_Baro_Backend(baro)