AP_NavEKF3: adjust for Location_Class and Location unification

This commit is contained in:
Peter Barker 2019-01-02 15:43:24 +11:00 committed by Peter Barker
parent ebd12b30e8
commit 0d4475f443
2 changed files with 2 additions and 2 deletions

View File

@ -264,7 +264,7 @@ void NavEKF3_core::InitialiseVariables()
lastInnovPassTime_ms = 0;
lastInnovFailTime_ms = 0;
gpsAccuracyGood = false;
memset(&gpsloc_prev, 0, sizeof(gpsloc_prev));
gpsloc_prev = {};
gpsDriftNE = 0.0f;
gpsVertVelFilt = 0.0f;
gpsHorizVelFilt = 0.0f;

View File

@ -23,7 +23,7 @@
#define EK3_DISABLE_INTERRUPTS 0
#include <AP_Common/Location.h>
#include <AP_Math/AP_Math.h>
#include "AP_NavEKF3.h"
#include <AP_Math/vectorN.h>