mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_NavEKF2: Reset yaw estimator bias states at start of flight
Enables yaw bias to be learned when sitting stationary on ground.
This commit is contained in:
parent
5ad5498b07
commit
ea4589ea94
@ -406,6 +406,9 @@ void NavEKF2_core::detectFlight()
|
||||
EKFGSF_yaw_reset_request_ms = 0;
|
||||
EKFGSF_yaw_reset_count = 0;
|
||||
EKFGSF_run_filterbank = true;
|
||||
Vector3f gyroBias;
|
||||
getGyroBias(gyroBias);
|
||||
yawEstimator->setGyroBias(gyroBias);
|
||||
}
|
||||
|
||||
// store current on-ground and in-air status for next time
|
||||
|
Loading…
Reference in New Issue
Block a user