mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_AHRS : change initialisation requirements for EKF and use dynamic method
This commit is contained in:
parent
6732d6c79b
commit
9f3c19c03a
@ -52,14 +52,14 @@ void AP_AHRS_NavEKF::update(void)
|
||||
_dcm_attitude(roll, pitch, yaw);
|
||||
|
||||
if (!ekf_started) {
|
||||
// if we have a compass set we can start the EKF
|
||||
if (get_compass()) {
|
||||
// if we have a compass set and GPS lock we can start the EKF
|
||||
if (get_compass() && get_gps()->status() >= GPS::GPS_OK_FIX_3D) {
|
||||
if (start_time_ms == 0) {
|
||||
start_time_ms = hal.scheduler->millis();
|
||||
}
|
||||
if (hal.scheduler->millis() - start_time_ms > startup_delay_ms) {
|
||||
ekf_started = true;
|
||||
EKF.InitialiseFilterBootstrap();
|
||||
EKF.InitialiseFilterDynamic();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -38,7 +38,7 @@ public:
|
||||
EKF(this, baro),
|
||||
_baro(baro),
|
||||
ekf_started(false),
|
||||
startup_delay_ms(5000)
|
||||
startup_delay_ms(10000)
|
||||
{
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user