airspeed: smooth the airspeed value a bit more

the value is very noisy in my tests. A bit more smoothing may help
This commit is contained in:
Andrew Tridgell 2011-12-10 21:46:27 +11:00
parent 011110e1dd
commit 0a7332b6e3
1 changed files with 1 additions and 1 deletions

View File

@ -80,7 +80,7 @@ static void read_airspeed(void)
airspeed_raw = (float)adc.Ch(AIRSPEED_CH);
g.airspeed_offset.set_and_save(airspeed_raw);
}
airspeed_raw = (adc.Ch(AIRSPEED_CH) * 0.25) + (airspeed_raw * 0.75);
airspeed_raw = (adc.Ch(AIRSPEED_CH) * 0.1) + (airspeed_raw * 0.9);
airspeed_pressure = max((airspeed_raw - g.airspeed_offset), 0);
airspeed = sqrt(airspeed_pressure * g.airspeed_ratio) * 100;
#endif