AP_NavEKF2: use get_distance instead of location_diff

This commit is contained in:
Pierre Kancir 2019-04-08 15:16:13 +02:00 committed by Tom Pittenger
parent 0b50f32c32
commit 3f5a6a243c
1 changed files with 1 additions and 1 deletions

View File

@ -51,7 +51,7 @@ bool NavEKF2_core::calcGpsGoodToAlign(void)
float deltaTime = constrain_float(float(imuDataDelayed.time_ms - lastPreAlignGpsCheckTime_ms)*0.001f,0.01f,posFiltTimeConst);
lastPreAlignGpsCheckTime_ms = imuDataDelayed.time_ms;
// Sum distance moved
gpsDriftNE += location_diff(gpsloc_prev, gpsloc).length();
gpsDriftNE += gpsloc_prev.get_distance(gpsloc);
gpsloc_prev = gpsloc;
// Decay distance moved exponentially to zero
gpsDriftNE *= (1.0f - deltaTime/posFiltTimeConst);