NavEKF: check baro health before consuming
This commit is contained in:
parent
79efad339f
commit
8b17d32994
@ -4269,7 +4269,7 @@ void NavEKF::readGpsData()
|
|||||||
void NavEKF::readHgtData()
|
void NavEKF::readHgtData()
|
||||||
{
|
{
|
||||||
// check to see if baro measurement has changed so we know if a new measurement has arrived
|
// 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
|
// Don't use Baro height if operating in optical flow mode as we use range finder instead
|
||||||
if (_fusionModeGPS == 3 && _altSource == 1) {
|
if (_fusionModeGPS == 3 && _altSource == 1) {
|
||||||
if ((imuSampleTime_ms - rngValidMeaTime_ms) < 2000) {
|
if ((imuSampleTime_ms - rngValidMeaTime_ms) < 2000) {
|
||||||
|
Loading…
Reference in New Issue
Block a user