DCM: fixed a bug when using GPS for yaw correction

When using GPS for yaw correction we need to apply the x and y omegaI
corrections from the _omega_I_sum in the period before we get to the
minimum ground speed for GPS yaw correction. Otherwise we get a large
sudden omega_I change on takeoff.
This commit is contained in:
Andrew Tridgell 2012-05-21 12:14:52 +10:00
parent 7ff5a200e7
commit 8f27297896

View File

@ -429,7 +429,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
// lost the yaw reference sensor completely we don't
// keep using a stale offset
_omega_yaw_P *= 0.97;
return;
goto check_sum_time;
}
// ensure the course error is scaled from -PI to PI
@ -461,6 +461,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
_error_yaw_sum += error_course;
_error_yaw_count++;
check_sum_time:
if (_omega_I_sum_time > 10) {
// every 10 seconds we apply the accumulated
// _omega_I_sum changes to _omega_I. We do this to