mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF2: Do not use GPS height if GPS accuracy is poor
If we are using GPS height, revert back to using Baro height if the GPS accuracy is poor.
This commit is contained in:
parent
cca8a86962
commit
bb74371c58
@ -552,7 +552,7 @@ void NavEKF2_core::selectHeightForFusion()
|
||||
|
||||
// determine if we should be using a height source other than baro
|
||||
bool usingRangeForHgt = (frontend->_altSource == 1 && imuSampleTime_ms - rngValidMeaTime_ms < 500 && frontend->_fusionModeGPS == 3);
|
||||
bool usingGpsForHgt = (frontend->_altSource == 2 && imuSampleTime_ms - lastTimeGpsReceived_ms < 500 && validOrigin);
|
||||
bool usingGpsForHgt = (frontend->_altSource == 2 && imuSampleTime_ms - lastTimeGpsReceived_ms < 500 && validOrigin && gpsAccuracyGood);
|
||||
|
||||
// if there is new baro data to fuse, calculate filterred baro data required by other processes
|
||||
if (baroDataToFuse) {
|
||||
|
Loading…
Reference in New Issue
Block a user