mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: the DerivativeFilter now handles duplicate data
this saves a few bytes of memory
This commit is contained in:
parent
fb90d16092
commit
b0e403e6fb
|
@ -103,15 +103,8 @@ float AP_Baro::get_altitude(void)
|
|||
// note that this relies on read() being called regularly to get new data
|
||||
float AP_Baro::get_climb_rate(void)
|
||||
{
|
||||
if (_last_climb_rate_t == _last_altitude_t) {
|
||||
// no new information
|
||||
return _climb_rate;
|
||||
}
|
||||
_last_climb_rate_t = _last_altitude_t;
|
||||
|
||||
// we use a 7 point derivative filter on the climb rate. This seems
|
||||
// to produce somewhat reasonable results on real hardware
|
||||
_climb_rate = _climb_rate_filter.slope() * 1.0e3;
|
||||
|
||||
return _climb_rate;
|
||||
return _climb_rate_filter.slope() * 1.0e3;
|
||||
}
|
||||
|
||||
|
|
|
@ -52,8 +52,6 @@ private:
|
|||
AP_Float _ground_temperature;
|
||||
AP_Float _ground_pressure;
|
||||
float _altitude;
|
||||
float _climb_rate;
|
||||
uint32_t _last_climb_rate_t;
|
||||
uint32_t _last_altitude_t;
|
||||
DerivativeFilterFloat_Size7 _climb_rate_filter;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue