Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_AHRS_NavEKF: inform all running EKFs that takeoff or touchdown is … #13148

Merged
merged 1 commit into from
Jan 7, 2020
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
34 changes: 4 additions & 30 deletions libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1716,40 +1716,14 @@ bool AP_AHRS_NavEKF::get_variances(float &velVar, float &posVar, float &hgtVar,

void AP_AHRS_NavEKF::setTakeoffExpected(bool val)
{
switch (ekf_type()) {
case EKF_TYPE2:
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
}
EKF2.setTakeoffExpected(val);
EKF3.setTakeoffExpected(val);
}

void AP_AHRS_NavEKF::setTouchdownExpected(bool val)
{
switch (ekf_type()) {
case EKF_TYPE2:
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
}
EKF2.setTouchdownExpected(val);
EKF3.setTouchdownExpected(val);
}

bool AP_AHRS_NavEKF::getGpsGlitchStatus() const
Expand Down