Browse Source

AP_NavEKF3: only use bcn EKF is the alignement as been completed

mission-4.1.18
Pierre Kancir 7 years ago committed by Randy Mackay
parent
commit
2b2c1e2d78
  1. 2
      libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp
  2. 4
      libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp

2
libraries/AP_NavEKF3/AP_NavEKF3_Control.cpp

@ -447,7 +447,7 @@ bool NavEKF3_core::readyToUseGPS(void) const @@ -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

4
libraries/AP_NavEKF3/AP_NavEKF3_RngBcnFusion.cpp

@ -23,8 +23,8 @@ void NavEKF3_core::SelectRngBcnFusion() @@ -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…
Cancel
Save