mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Baro - removed unnecessary 2 element average filtering of pressure (there is a 4 or 5 element average filter in arducopter code itself, two places is messy)
- also removed unused _offset_press variable
This commit is contained in:
parent
bed667c62e
commit
f3eb15167c
@ -172,8 +172,6 @@ void AP_Baro_BMP085::ReadPress()
|
||||
}
|
||||
|
||||
RawPress = (((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | ((uint32_t)buf[2])) >> (8 - OVERSAMPLING);
|
||||
|
||||
RawPress = _press_filter.apply(RawPress);
|
||||
}
|
||||
|
||||
// Send Command to Read Temperature
|
||||
|
@ -26,7 +26,6 @@ class AP_Baro_BMP085 : public AP_Baro
|
||||
|
||||
private:
|
||||
int32_t RawPress;
|
||||
int32_t _offset_press;
|
||||
int32_t RawTemp;
|
||||
int16_t Temp;
|
||||
uint32_t Press;
|
||||
@ -39,7 +38,6 @@ class AP_Baro_BMP085 : public AP_Baro
|
||||
int16_t ac1, ac2, ac3, b1, b2, mb, mc, md;
|
||||
uint16_t ac4, ac5, ac6;
|
||||
|
||||
AverageFilterInt32_Size2 _press_filter;
|
||||
AverageFilterInt16_Size4 _temp_filter;
|
||||
|
||||
uint32_t _retry_time;
|
||||
|
Loading…
Reference in New Issue
Block a user