AP_Airspeed: remove airspeed filter and run at 10Hz

this saves on the filter memory, and gives just as good a result
This commit is contained in:
Andrew Tridgell 2012-08-15 12:34:08 +10:00
parent a4b1b9f0a4
commit 47be6d8ad1
3 changed files with 9 additions and 10 deletions

View File

@ -761,14 +761,6 @@ static void fast_loop()
// ------------------------------------
check_short_failsafe();
// Read Airspeed
// -------------
if (airspeed.enabled()) {
#if HIL_MODE != HIL_MODE_ATTITUDE
read_airspeed();
#endif
}
#if HIL_MODE == HIL_MODE_SENSORS
// update hil before AHRS update
gcs_update();
@ -878,6 +870,14 @@ Serial.println(tempaccel.z, DEC);
case 2:
medium_loopCounter++;
// Read Airspeed
// -------------
#if HIL_MODE != HIL_MODE_ATTITUDE
if (airspeed.enabled()) {
read_airspeed();
}
#endif
// Read altitude from sensors
// ------------------
update_alt();

View File

@ -69,7 +69,7 @@ void AP_Airspeed::read(void)
if (!_enable) {
return;
}
_airspeed_raw = _filter.apply(_source->read());
_airspeed_raw = _source->read();
airspeed_pressure = max((_airspeed_raw - _offset), 0);
_airspeed = sqrt(airspeed_pressure * _ratio);
}

View File

@ -50,7 +50,6 @@ private:
AP_Int8 _enable;
float _airspeed;
float _airspeed_raw;
AverageFilterFloat_Size5 _filter;
};