Browse Source

EKF3: RNG_USE_HGT param only used when ALT_SOURCE = rangefinder

master
Randy Mackay 5 years ago committed by Andrew Tridgell
parent
commit
0e1a2efb7c
  1. 2
      libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp

2
libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp

@ -793,7 +793,7 @@ void NavEKF3_core::selectHeightForFusion() @@ -793,7 +793,7 @@ void NavEKF3_core::selectHeightForFusion()
baroDataToFuse = storedBaro.recall(baroDataDelayed, imuDataDelayed.time_ms);
// select height source
if (((frontend->_useRngSwHgt > 0) || (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) {
if (((frontend->_useRngSwHgt > 0) && (frontend->_altSource == 1)) && (imuSampleTime_ms - rngValidMeaTime_ms < 500)) {
if (frontend->_altSource == 1) {
// always use range finder
activeHgtSource = HGT_SOURCE_RNG;

Loading…
Cancel
Save