mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Airspeed: a bit more filtering
this helps reduce noise at low speed
This commit is contained in:
parent
69c29f5196
commit
f3f9d644d9
@ -11,7 +11,6 @@
|
||||
#include <FastSerial.h>
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Airspeed.h>
|
||||
#include <LowPassFilter.h>
|
||||
|
||||
// table of user settable parameters
|
||||
const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = {
|
||||
@ -71,5 +70,5 @@ void AP_Airspeed::read(void)
|
||||
}
|
||||
_airspeed_raw = _source->read();
|
||||
airspeed_pressure = max((_airspeed_raw - _offset), 0);
|
||||
_airspeed = sqrt(airspeed_pressure * _ratio);
|
||||
_airspeed = 0.7 * _airspeed + 0.3 * sqrt(airspeed_pressure * _ratio);
|
||||
}
|
||||
|
@ -6,8 +6,6 @@
|
||||
#include <AP_Common.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_AnalogSource.h>
|
||||
#include <Filter.h>
|
||||
#include <AverageFilter.h>
|
||||
|
||||
class AP_Airspeed
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user