Copter: enable ekf_check only after ekf origin has been set

This commit is contained in:
Randy Mackay 2015-07-16 14:52:17 +09:00
parent cc0ab26f5d
commit 277e3d8675

View File

@ -30,6 +30,12 @@ static struct {
// should be called at 10hz // should be called at 10hz
void Copter::ekf_check() void Copter::ekf_check()
{ {
// exit immediately if ekf has no origin yet - this assumes the origin can never become unset
Location temp_loc;
if (!ahrs.get_NavEKF_const().getOriginLLH(temp_loc)) {
return;
}
// return immediately if motors are not armed, ekf check is disabled, not using ekf or usb is connected // return immediately if motors are not armed, ekf check is disabled, not using ekf or usb is connected
if (!motors.armed() || ap.usb_connected || (g.fs_ekf_thresh <= 0.0f)) { if (!motors.armed() || ap.usb_connected || (g.fs_ekf_thresh <= 0.0f)) {
ekf_check_state.fail_count = 0; ekf_check_state.fail_count = 0;