mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: make rngBcnDataToFuse const false if beacon not compiled in
This commit is contained in:
parent
81d39677ab
commit
f36f387948
|
@ -263,7 +263,9 @@ void NavEKF2_core::InitialiseVariables()
|
|||
varInnovRngBcn = 0.0f;
|
||||
innovRngBcn = 0.0f;
|
||||
memset(&lastTimeRngBcn_ms, 0, sizeof(lastTimeRngBcn_ms));
|
||||
#if AP_BEACON_ENABLED
|
||||
rngBcnDataToFuse = false;
|
||||
#endif
|
||||
beaconVehiclePosNED.zero();
|
||||
beaconVehiclePosErr = 1.0f;
|
||||
rngBcnLast3DmeasTime_ms = 0;
|
||||
|
|
|
@ -1019,7 +1019,11 @@ private:
|
|||
ftype varInnovRngBcn; // range beacon observation innovation variance (m^2)
|
||||
ftype innovRngBcn; // range beacon observation innovation (m)
|
||||
uint32_t lastTimeRngBcn_ms[10]; // last time we received a range beacon measurement (msec)
|
||||
#if AP_BEACON_ENABLED
|
||||
bool rngBcnDataToFuse; // true when there is new range beacon data to fuse
|
||||
#else
|
||||
const bool rngBcnDataToFuse = false; // true when there is new range beacon data to fuse
|
||||
#endif
|
||||
Vector3F beaconVehiclePosNED; // NED position estimate from the beacon system (NED)
|
||||
ftype beaconVehiclePosErr; // estimated position error from the beacon system (m)
|
||||
uint32_t rngBcnLast3DmeasTime_ms; // last time the beacon system returned a 3D fix (msec)
|
||||
|
|
Loading…
Reference in New Issue