mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_NavEKF3: only use bcn EKF is the alignement as been completed
This commit is contained in:
parent
44a21bc8ac
commit
2b2c1e2d78
@ -447,7 +447,7 @@ bool NavEKF3_core::readyToUseGPS(void) const
|
||||
// return true if the filter to be ready to use the beacon range measurements
|
||||
bool NavEKF3_core::readyToUseRangeBeacon(void) const
|
||||
{
|
||||
return tiltAlignComplete && yawAlignComplete && delAngBiasLearned && rngBcnGoodToAlign && rngBcnDataToFuse;
|
||||
return tiltAlignComplete && yawAlignComplete && delAngBiasLearned && rngBcnAlignmentCompleted && rngBcnDataToFuse;
|
||||
}
|
||||
|
||||
// return true if we should use the compass
|
||||
|
@ -23,8 +23,8 @@ void NavEKF3_core::SelectRngBcnFusion()
|
||||
// Determine if we need to fuse range beacon data on this time step
|
||||
if (rngBcnDataToFuse) {
|
||||
if (PV_AidingMode == AID_ABSOLUTE) {
|
||||
if (!filterStatus.flags.using_gps) {
|
||||
if (!bcnOriginEstInit && rngBcnAlignmentCompleted) {
|
||||
if (!filterStatus.flags.using_gps && rngBcnAlignmentCompleted) {
|
||||
if (!bcnOriginEstInit) {
|
||||
bcnOriginEstInit = true;
|
||||
bcnPosOffsetNED.x = receiverPos.x - stateStruct.position.x;
|
||||
bcnPosOffsetNED.y = receiverPos.y - stateStruct.position.y;
|
||||
|
Loading…
Reference in New Issue
Block a user