AP_InertialNav: fix pos error degradation rate

degrate position_error to 10% over 2 seconds (assumes 5hz update rate)
must be *0.7943 instead of 0.7934
This commit is contained in:
Hug0 2014-05-05 13:55:27 +02:00 committed by Randy Mackay
parent 73dc32108f
commit 6b0d5f9770

View File

@ -175,8 +175,8 @@ void AP_InertialNav::correct_with_gps(uint32_t now, int32_t lon, int32_t lat)
// sanity check the gps position. Relies on the main code calling GPS_Glitch::check_position() immediatley after a GPS update
if (_glitch_detector.glitching()) {
// failed sanity check so degrate position_error to 10% over 2 seconds (assumes 5hz update rate)
_position_error.x *= 0.7934;
_position_error.y *= 0.7934;
_position_error.x *= 0.7943;
_position_error.y *= 0.7943;
}else{
// if our internal glitching flag (from previous iteration) is true we have just recovered from a glitch
// reset the inertial nav position and velocity to gps values