AP_AHRS_NavEKF: inform all running EKFs that takeoff or touchdown is expected

Several other methods in here poke both EKFs like this.
This commit is contained in:
Peter Barker 2020-01-02 14:56:10 +11:00 committed by Andrew Tridgell
parent d5b1f1651e
commit 7a5b8136ad

View File

@ -1716,40 +1716,14 @@ bool AP_AHRS_NavEKF::get_variances(float &velVar, float &posVar, float &hgtVar,
void AP_AHRS_NavEKF::setTakeoffExpected(bool val) void AP_AHRS_NavEKF::setTakeoffExpected(bool val)
{ {
switch (ekf_type()) { EKF2.setTakeoffExpected(val);
case EKF_TYPE2: EKF3.setTakeoffExpected(val);
default:
EKF2.setTakeoffExpected(val);
break;
case EKF_TYPE3:
EKF3.setTakeoffExpected(val);
break;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKF_TYPE_SITL:
break;
#endif
}
} }
void AP_AHRS_NavEKF::setTouchdownExpected(bool val) void AP_AHRS_NavEKF::setTouchdownExpected(bool val)
{ {
switch (ekf_type()) { EKF2.setTouchdownExpected(val);
case EKF_TYPE2: EKF3.setTouchdownExpected(val);
default:
EKF2.setTouchdownExpected(val);
break;
case EKF_TYPE3:
EKF3.setTouchdownExpected(val);
break;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKF_TYPE_SITL:
break;
#endif
}
} }
bool AP_AHRS_NavEKF::getGpsGlitchStatus() const bool AP_AHRS_NavEKF::getGpsGlitchStatus() const