mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: enable ekf_check only after ekf origin has been set
This commit is contained in:
parent
cc0ab26f5d
commit
277e3d8675
@ -30,6 +30,12 @@ static struct {
|
||||
// should be called at 10hz
|
||||
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
|
||||
if (!motors.armed() || ap.usb_connected || (g.fs_ekf_thresh <= 0.0f)) {
|
||||
ekf_check_state.fail_count = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user