mirror of https://github.com/ArduPilot/ardupilot
AHRS: force an extra read of the compass on startup
the first read from the compass can be bad. This ensures we have a good value when getting the initial AHRS yaw. Thanks to Randy and Jason for the bug report!
This commit is contained in:
parent
8853a104f0
commit
7948b3aee7
|
@ -325,7 +325,10 @@ AP_AHRS_DCM::drift_correction_yaw(void)
|
|||
if (_compass->last_update != _compass_last_update) {
|
||||
yaw_deltat = (_compass->last_update - _compass_last_update) * 1.0e-6;
|
||||
_compass_last_update = _compass->last_update;
|
||||
if (!_have_initial_yaw) {
|
||||
// we force an additional compass read()
|
||||
// here. This has the effect of throwing away
|
||||
// the first compass value, which can be bad
|
||||
if (!_have_initial_yaw && _compass->read()) {
|
||||
float heading = _compass->calculate_heading(_dcm_matrix);
|
||||
_dcm_matrix.from_euler(roll, pitch, heading);
|
||||
_omega_yaw_P.zero();
|
||||
|
|
Loading…
Reference in New Issue