mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_NavEKF3: adjust for Location_Class and Location unification
This commit is contained in:
parent
ebd12b30e8
commit
0d4475f443
@ -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;
|
||||
|
@ -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>
|
||||
|
Loading…
Reference in New Issue
Block a user