NavEKF: check baro health before consuming

This commit is contained in:
Randy Mackay 2015-08-12 14:59:58 -07:00
parent 9f4f0b4f20
commit f6965fffdc

View File

@ -4269,7 +4269,7 @@ void NavEKF::readGpsData()
void NavEKF::readHgtData()
{
// check to see if baro measurement has changed so we know if a new measurement has arrived
if (_baro.get_last_update() != lastHgtMeasTime) {
if (_baro.healthy() && _baro.get_last_update() != lastHgtMeasTime) {
// Don't use Baro height if operating in optical flow mode as we use range finder instead
if (_fusionModeGPS == 3 && _altSource == 1) {
if ((imuSampleTime_ms - rngValidMeaTime_ms) < 2000) {