@@ -512,7 +512,7 @@ void NavEKF3_core::SelectVelPosFusion()
512
512
}
513
513
514
514
const AP_NavEKF_Source::SourceXY posxy_source = frontend->sources .getPosXYSource ();
515
- #if EK3_FEATURE_EXTERNAL_NAV
515
+ #if EK3_FEATURE_EXTERNAL_NAV
516
516
// Check for data at the fusion time horizon
517
517
extNavDataToFuse = (posxy_source == AP_NavEKF_Source::SourceXY::EXTNAV) && storedExtNav.recall (extNavDataDelayed, imuDataDelayed.time_ms );
518
518
if (extNavDataToFuse) {
@@ -546,7 +546,6 @@ void NavEKF3_core::SelectVelPosFusion()
546
546
}
547
547
548
548
// detect position source changes. Trigger position reset if position source is valid
549
- // GCS_SEND_TEXT(MAV_SEVERITY_INFO, "posxy_source: %u",(unsigned)posxy_source);
550
549
if (posxy_source != posxy_source_last) {
551
550
posxy_source_reset = (posxy_source != AP_NavEKF_Source::SourceXY::NONE);
552
551
posxy_source_last = posxy_source;
@@ -713,7 +712,9 @@ void NavEKF3_core::FuseVelPosNED()
713
712
R_OBS[4 ] = R_OBS[0 ];
714
713
for (uint8_t i=0 ; i<=2 ; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
715
714
} else {
715
+ #if EK3_FEATURE_EXTERNAL_NAV
716
716
const bool extNavUsedForVel = extNavVelToFuse && frontend->sources .useVelXYSource (AP_NavEKF_Source::SourceXY::EXTNAV);
717
+ #endif
717
718
if (fuseVelData)
718
719
{
719
720
#if EK3_FEATURE_EXTERNAL_NAV
@@ -784,57 +785,56 @@ void NavEKF3_core::FuseVelPosNED()
784
785
// For horizontal GPS velocity we don't want the acceptance radius to increase with reported GPS accuracy so we use a value based on best GPS performance
785
786
// plus a margin for manoeuvres. It is better to reject GPS horizontal velocity errors early
786
787
ftype obs_data_chk;
788
+ #if EK3_FEATURE_EXTERNAL_NAV
789
+ if (extNavUsedForVel) {
790
+ obs_data_chk = sq (constrain_ftype (extNavVelDelayed.err , 0 .05f , 5 .0f )) + sq (frontend->extNavVelVarAccScale * accNavMag);
791
+ } else
792
+ #endif
787
793
if (gpsDataToFuse)
788
794
{
789
795
obs_data_chk = sq (constrain_ftype (frontend->_gpsHorizVelNoise , 0 .05f , 5 .0f )) + sq (frontend->gpsNEVelVarAccScale * accNavMag);
790
- }
791
- #if EK3_FEATURE_EXTERNAL_NAV
792
- else if (extNavUsedForVel) {
793
- obs_data_chk = sq (constrain_ftype (extNavVelDelayed.err , 0 .05f , 5 .0f )) + sq (frontend->extNavVelVarAccScale * accNavMag);
794
796
} else {
795
797
// TODO (EF): No horizontal vel this update, default value
796
798
obs_data_chk = 5 .0f ;
797
799
}
798
- #endif
799
800
R_OBS_DATA_CHECKS[0 ] = R_OBS_DATA_CHECKS[1 ] = R_OBS_DATA_CHECKS[2 ] = obs_data_chk;
800
801
801
802
}
802
803
803
804
R_OBS[5 ] = posDownObsNoise;
804
805
for (uint8_t i=3 ; i<=5 ; i++) R_OBS_DATA_CHECKS[i] = R_OBS[i];
805
806
806
- // TODO (EF): extra indentation for cleaner git diff, remove
807
- // if vertical GPS velocity data and an independent height source is being used, check to see if the GPS vertical velocity and altimeter
808
- // innovations have the same sign and are outside limits. If so, then it is likely aliasing is affecting
809
- // the accelerometers and we should disable the GPS and barometer innovation consistency checks.
810
- if (gpsDataDelayed.have_vz && fuseVelData && (frontend->sources .getPosZSource () != AP_NavEKF_Source::SourceZ::GPS)) {
811
- // calculate innovations for height and vertical GPS vel measurements
812
- const ftype hgtErr = stateStruct.position .z - velPosObs[5 ];
813
- const ftype velDErr = stateStruct.velocity .z - velPosObs[2 ];
814
- // Check if they are the same sign and both more than 3-sigma out of bounds
815
- // Step the test threshold up in stages from 1 to 2 to 3 sigma after exiting
816
- // from a previous bad IMU event so that a subsequent error is caught more quickly.
817
- const uint32_t timeSinceLastBadIMU_ms = imuSampleTime_ms - badIMUdata_ms;
818
- float R_gain;
819
- if (timeSinceLastBadIMU_ms > (BAD_IMU_DATA_HOLD_MS * 2 )) {
820
- R_gain = 9 .0F ;
821
- } else if (timeSinceLastBadIMU_ms > ((BAD_IMU_DATA_HOLD_MS * 3 ) / 2 )) {
822
- R_gain = 4 .0F ;
823
- } else {
824
- R_gain = 1 .0F ;
825
- }
826
- if ((hgtErr*velDErr > 0 .0f ) && (sq (hgtErr) > R_gain * R_OBS[5 ]) && (sq (velDErr) >R_gain * R_OBS[2 ])) {
827
- badIMUdata_ms = imuSampleTime_ms;
828
- } else {
829
- goodIMUdata_ms = imuSampleTime_ms;
830
- }
831
- if (timeSinceLastBadIMU_ms < BAD_IMU_DATA_HOLD_MS) {
832
- badIMUdata = true ;
833
- stateStruct.velocity .z = gpsDataDelayed.vel .z ;
834
- } else {
835
- badIMUdata = false ;
836
- }
807
+ // If vertical GPS velocity data and an independent height source is being used, check to see if the GPS vertical velocity and altimeter
808
+ // innovations have the same sign and are outside limits. If so, then it is likely aliasing is affecting
809
+ // the accelerometers and we should disable the GPS and barometer innovation consistency checks.
810
+ if (gpsDataDelayed.have_vz && fuseVelData && (frontend->sources .getPosZSource () != AP_NavEKF_Source::SourceZ::GPS)) {
811
+ // calculate innovations for height and vertical GPS vel measurements
812
+ const ftype hgtErr = stateStruct.position .z - velPosObs[5 ];
813
+ const ftype velDErr = stateStruct.velocity .z - velPosObs[2 ];
814
+ // Check if they are the same sign and both more than 3-sigma out of bounds
815
+ // Step the test threshold up in stages from 1 to 2 to 3 sigma after exiting
816
+ // from a previous bad IMU event so that a subsequent error is caught more quickly.
817
+ const uint32_t timeSinceLastBadIMU_ms = imuSampleTime_ms - badIMUdata_ms;
818
+ float R_gain;
819
+ if (timeSinceLastBadIMU_ms > (BAD_IMU_DATA_HOLD_MS * 2 )) {
820
+ R_gain = 9 .0F ;
821
+ } else if (timeSinceLastBadIMU_ms > ((BAD_IMU_DATA_HOLD_MS * 3 ) / 2 )) {
822
+ R_gain = 4 .0F ;
823
+ } else {
824
+ R_gain = 1 .0F ;
825
+ }
826
+ if ((hgtErr*velDErr > 0 .0f ) && (sq (hgtErr) > R_gain * R_OBS[5 ]) && (sq (velDErr) >R_gain * R_OBS[2 ])) {
827
+ badIMUdata_ms = imuSampleTime_ms;
828
+ } else {
829
+ goodIMUdata_ms = imuSampleTime_ms;
830
+ }
831
+ if (timeSinceLastBadIMU_ms < BAD_IMU_DATA_HOLD_MS) {
832
+ badIMUdata = true ;
833
+ stateStruct.velocity .z = gpsDataDelayed.vel .z ;
834
+ } else {
835
+ badIMUdata = false ;
837
836
}
837
+ }
838
838
839
839
// Test horizontal position measurements
840
840
if (fusePosData) {
@@ -871,11 +871,13 @@ void NavEKF3_core::FuseVelPosNED()
871
871
// if timed out or outside the specified uncertainty radius, reset to the external sensor
872
872
// if velocity drift is being constrained, dont reset until gps passes quality checks
873
873
bool posVarianceIsTooLarge = false ;
874
+ #if EK3_FEATURE_EXTERNAL_NAV
874
875
if (extNavDataToFuse)
875
876
{
876
877
posVarianceIsTooLarge = (P[8 ][8 ] + P[7 ][7 ]) > sq (ftype (extNavDataDelayed.posErr ));
877
- }
878
- else if (gpsDataToFuse)
878
+ } else
879
+ #endif
880
+ if (gpsDataToFuse)
879
881
{
880
882
posVarianceIsTooLarge = (frontend->_gpsGlitchRadiusMax > 0 ) && (P[8 ][8 ] + P[7 ][7 ]) > sq (ftype (frontend->_gpsGlitchRadiusMax ));
881
883
}
@@ -896,17 +898,18 @@ void NavEKF3_core::FuseVelPosNED()
896
898
// Reset the position variances and corresponding covariances to a value that will pass the checks
897
899
zeroRows (P,7 ,8 );
898
900
zeroCols (P,7 ,8 );
901
+ #if EK3_FEATURE_EXTERNAL_NAV
899
902
if (extNavDataToFuse)
900
903
{
901
904
P[7 ][7 ] = sq (ftype (0 .5f *extNavDataDelayed.posErr ));
902
- }
903
- else if (gpsDataToFuse)
905
+ } else
906
+ #endif
907
+ if (gpsDataToFuse)
904
908
{
905
909
P[7 ][7 ] = sq (ftype (0 .5f *frontend->_gpsGlitchRadiusMax ));
906
910
}
907
911
else
908
912
{
909
- // (EF): Doesn't seem to trigger
910
913
GCS_SEND_TEXT (MAV_SEVERITY_INFO, " reset pos variance w/o extnav or GPS" );
911
914
}
912
915
P[8 ][8 ] = P[7 ][7 ];
0 commit comments