AP_NavEKF3: Use FIR filtered airspeed

Switch to use of an airspeed reading averaged across the raw sensor readings. since the last update.
This avoids use of the IIR which requires a larger time delay compensation and violates the assumption of uncorrelated noise.
The time delay parameter has been reduced to compensate for the removal of the airspeed IIR filtering.
This commit is contained in:
priseborough 2016-12-19 09:09:17 +11:00 committed by Randy Mackay
parent 9261c34097
commit 8d1733cee6
2 changed files with 2 additions and 2 deletions

View File

@ -537,7 +537,7 @@ NavEKF3::NavEKF3(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng) :
gpsDVelVarAccScale(0.07f), // Scale factor applied to vertical velocity measurement variance due to manoeuvre acceleration - used when GPS doesn't report speed error
gpsPosVarAccScale(0.05f), // Scale factor applied to horizontal position measurement variance due to manoeuvre acceleration
magDelay_ms(60), // Magnetometer measurement delay (msec)
tasDelay_ms(240), // Airspeed measurement delay (msec)
tasDelay_ms(100), // Airspeed measurement delay (msec)
tiltDriftTimeMax_ms(15000), // Maximum number of ms allowed without any form of tilt aiding (GPS, flow, TAS, etc)
posRetryTimeUseVel_ms(10000), // Position aiding retry time with velocity measurements (msec)
posRetryTimeNoVel_ms(7000), // Position aiding retry time without velocity measurements (msec)

View File

@ -635,7 +635,7 @@ void NavEKF3_core::readAirSpdData()
if (aspeed &&
aspeed->use() &&
(aspeed->last_update_ms() - timeTasReceived_ms) > frontend->sensorIntervalMin_ms) {
tasDataNew.tas = aspeed->get_airspeed() * aspeed->get_EAS2TAS();
tasDataNew.tas = aspeed->get_raw_airspeed() * aspeed->get_EAS2TAS();
timeTasReceived_ms = aspeed->last_update_ms();
tasDataNew.time_ms = timeTasReceived_ms - frontend->tasDelay_ms;