EKF3: RNG_USE_HGT param only used when ALT_SOURCE = rangefinder
This commit is contained in:
parent
94a52b3525
commit
0e1a2efb7c
@ -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…
Reference in New Issue
Block a user