AP_NavEKF3: only report terrain estimator innovations with valid rng value
This commit is contained in:
parent
171e80d8dc
commit
be96a27fa8
@ -589,7 +589,7 @@ void NavEKF3_core::send_status_report(mavlink_channel_t chan)
|
|||||||
// height estimation or optical flow operation. This prevents false alarms at the GCS if a
|
// height estimation or optical flow operation. This prevents false alarms at the GCS if a
|
||||||
// range finder is fitted for other applications
|
// range finder is fitted for other applications
|
||||||
float temp;
|
float temp;
|
||||||
if ((frontend->_useRngSwHgt > 0) || PV_AidingMode == AID_RELATIVE || flowDataValid) {
|
if (((frontend->_useRngSwHgt > 0) && activeHgtSource == HGT_SOURCE_RNG) || (PV_AidingMode == AID_RELATIVE && flowDataValid)) {
|
||||||
temp = sqrtf(auxRngTestRatio);
|
temp = sqrtf(auxRngTestRatio);
|
||||||
} else {
|
} else {
|
||||||
temp = 0.0f;
|
temp = 0.0f;
|
||||||
|
Loading…
Reference in New Issue
Block a user