AP_AHRS : Enable EKF start without GPS

This commit is contained in:
priseborough 2014-10-29 11:55:53 +11:00 committed by Andrew Tridgell
parent 41f0231cfb
commit 44e1695d5a

View File

@ -77,15 +77,13 @@ void AP_AHRS_NavEKF::update(void)
_dcm_attitude(roll, pitch, yaw); _dcm_attitude(roll, pitch, yaw);
if (!ekf_started) { if (!ekf_started) {
// if we have a GPS lock and more than 6 satellites, we can start the EKF // wait 10 seconds
if (get_gps().status() >= AP_GPS::GPS_OK_FIX_3D && get_gps().num_sats() >= _gps_minsats) { if (start_time_ms == 0) {
if (start_time_ms == 0) { start_time_ms = hal.scheduler->millis();
start_time_ms = hal.scheduler->millis(); }
} if (hal.scheduler->millis() - start_time_ms > startup_delay_ms) {
if (hal.scheduler->millis() - start_time_ms > startup_delay_ms) { ekf_started = true;
ekf_started = true; EKF.InitialiseFilterDynamic();
EKF.InitialiseFilterDynamic();
}
} }
} }
if (ekf_started) { if (ekf_started) {