AP_Baro: BMP085: use a moving average of 10 samples in BMP085

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.
This commit is contained in:
Lucas De Marchi 2015-07-12 22:40:36 -03:00
parent 18f1f8bea8
commit 3c7d80a270
2 changed files with 9 additions and 14 deletions

View File

@ -121,19 +121,16 @@ void AP_Baro_BMP085::accumulate(void)
*/
void AP_Baro_BMP085::update(void)
{
if (_count == 0 && _data_ready()) {
if (!_has_sample && _data_ready()) {
accumulate();
}
if (_count == 0) {
if (!_has_sample) {
return;
}
float temperature = 0.1f * _temp;
float pressure = _press_sum / _count;
_count = 0;
_press_sum = 0;
float pressure = _pressure_filter.getf();
_copy_to_frontend(_instance, pressure, temperature);
}
@ -219,13 +216,10 @@ void AP_Baro_BMP085::_calculate()
x1 = (p >> 8) * (p >> 8);
x1 = (x1 * 3038) >> 16;
x2 = (-7357 * p) >> 16;
_press_sum += p + ((x1 + x2 + 3791) >> 4);
p += ((x1 + x2 + 3791) >> 4);
_count++;
if (_count == 254) {
_press_sum *= 0.5f;
_count /= 2;
}
_pressure_filter.apply(p);
_has_sample = true;
}
bool AP_Baro_BMP085::_data_ready()

View File

@ -4,6 +4,7 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/utility/OwnPtr.h>
#include <Filter/Filter.h>
#include "AP_Baro_Backend.h"
@ -28,7 +29,7 @@ private:
AP_HAL::DigitalSource *_eoc;
uint8_t _instance;
uint8_t _count;
bool _has_sample;
// Boards with no EOC pin: use times instead
uint32_t _last_press_read_command_time;
@ -45,5 +46,5 @@ private:
int32_t _raw_pressure;
int32_t _raw_temp;
int32_t _temp;
float _press_sum;
AverageIntegralFilter<int32_t, int32_t, 10> _pressure_filter;
};