AP_Baro: the DerivativeFilter now handles duplicate data

this saves a few bytes of memory
This commit is contained in:
Andrew Tridgell 2012-08-08 11:29:53 +10:00
parent 77f3b60b6f
commit a7b9aff79f
2 changed files with 2 additions and 11 deletions

View File

@ -103,15 +103,8 @@ float AP_Baro::get_altitude(void)
// note that this relies on read() being called regularly to get new data // note that this relies on read() being called regularly to get new data
float AP_Baro::get_climb_rate(void) 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 // we use a 7 point derivative filter on the climb rate. This seems
// to produce somewhat reasonable results on real hardware // to produce somewhat reasonable results on real hardware
_climb_rate = _climb_rate_filter.slope() * 1.0e3; return _climb_rate_filter.slope() * 1.0e3;
return _climb_rate;
} }

View File

@ -52,8 +52,6 @@ private:
AP_Float _ground_temperature; AP_Float _ground_temperature;
AP_Float _ground_pressure; AP_Float _ground_pressure;
float _altitude; float _altitude;
float _climb_rate;
uint32_t _last_climb_rate_t;
uint32_t _last_altitude_t; uint32_t _last_altitude_t;
DerivativeFilterFloat_Size7 _climb_rate_filter; DerivativeFilterFloat_Size7 _climb_rate_filter;
}; };