mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
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:
parent
a361a3aebd
commit
f4023d1b44
@ -761,14 +761,6 @@ static void fast_loop()
|
|||||||
// ------------------------------------
|
// ------------------------------------
|
||||||
check_short_failsafe();
|
check_short_failsafe();
|
||||||
|
|
||||||
// Read Airspeed
|
|
||||||
// -------------
|
|
||||||
if (airspeed.enabled()) {
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
read_airspeed();
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_SENSORS
|
#if HIL_MODE == HIL_MODE_SENSORS
|
||||||
// update hil before AHRS update
|
// update hil before AHRS update
|
||||||
gcs_update();
|
gcs_update();
|
||||||
@ -878,6 +870,14 @@ Serial.println(tempaccel.z, DEC);
|
|||||||
case 2:
|
case 2:
|
||||||
medium_loopCounter++;
|
medium_loopCounter++;
|
||||||
|
|
||||||
|
// Read Airspeed
|
||||||
|
// -------------
|
||||||
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
if (airspeed.enabled()) {
|
||||||
|
read_airspeed();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// Read altitude from sensors
|
// Read altitude from sensors
|
||||||
// ------------------
|
// ------------------
|
||||||
update_alt();
|
update_alt();
|
||||||
|
@ -69,7 +69,7 @@ void AP_Airspeed::read(void)
|
|||||||
if (!_enable) {
|
if (!_enable) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
_airspeed_raw = _filter.apply(_source->read());
|
_airspeed_raw = _source->read();
|
||||||
airspeed_pressure = max((_airspeed_raw - _offset), 0);
|
airspeed_pressure = max((_airspeed_raw - _offset), 0);
|
||||||
_airspeed = sqrt(airspeed_pressure * _ratio);
|
_airspeed = sqrt(airspeed_pressure * _ratio);
|
||||||
}
|
}
|
||||||
|
@ -50,7 +50,6 @@ private:
|
|||||||
AP_Int8 _enable;
|
AP_Int8 _enable;
|
||||||
float _airspeed;
|
float _airspeed;
|
||||||
float _airspeed_raw;
|
float _airspeed_raw;
|
||||||
AverageFilterFloat_Size5 _filter;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user