mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_Baro: BMP085: don't average temperature in BMP085
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).
This commit is contained in:
parent
c5c52076ca
commit
8da5275b03
@ -106,7 +106,7 @@ void AP_Baro_BMP085::accumulate(void)
|
||||
}
|
||||
|
||||
_state++;
|
||||
if (_state == 5) {
|
||||
if (_state == 25) {
|
||||
_state = 0;
|
||||
_cmd_read_temp();
|
||||
} else {
|
||||
@ -128,11 +128,10 @@ void AP_Baro_BMP085::update(void)
|
||||
return;
|
||||
}
|
||||
|
||||
float temperature = 0.1f * _temp_sum / _count;
|
||||
float temperature = 0.1f * _temp;
|
||||
float pressure = _press_sum / _count;
|
||||
|
||||
_count = 0;
|
||||
_temp_sum = 0;
|
||||
_press_sum = 0;
|
||||
|
||||
_copy_to_frontend(_instance, pressure, temperature);
|
||||
@ -198,7 +197,7 @@ void AP_Baro_BMP085::_calculate()
|
||||
x1 = ((int32_t)_raw_temp - ac6) * ac5 >> 15;
|
||||
x2 = ((int32_t) mc << 11) / (x1 + md);
|
||||
b5 = x1 + x2;
|
||||
_temp_sum += (b5 + 8) >> 4;
|
||||
_temp = (b5 + 8) >> 4;
|
||||
|
||||
// Pressure calculations
|
||||
b6 = b5 - 4000;
|
||||
@ -224,7 +223,6 @@ void AP_Baro_BMP085::_calculate()
|
||||
|
||||
_count++;
|
||||
if (_count == 254) {
|
||||
_temp_sum *= 0.5f;
|
||||
_press_sum *= 0.5f;
|
||||
_count /= 2;
|
||||
}
|
||||
|
@ -28,8 +28,6 @@ private:
|
||||
AP_HAL::DigitalSource *_eoc;
|
||||
|
||||
uint8_t _instance;
|
||||
float _temp_sum;
|
||||
float _press_sum;
|
||||
uint8_t _count;
|
||||
|
||||
// Boards with no EOC pin: use times instead
|
||||
@ -46,4 +44,6 @@ private:
|
||||
uint32_t _retry_time;
|
||||
int32_t _raw_pressure;
|
||||
int32_t _raw_temp;
|
||||
int32_t _temp;
|
||||
float _press_sum;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user