DCM: use the new use_for_yaw() compass method

This commit is contained in:
Andrew Tridgell 2012-02-25 14:11:31 +11:00
parent c3319afadd
commit 3abe035557
1 changed files with 1 additions and 1 deletions

View File

@ -391,7 +391,7 @@ AP_DCM::drift_correction(void)
//*****YAW***************
if (_compass && _compass->healthy) {
if (_compass && _compass->use_for_yaw()) {
if (_have_initial_yaw) {
// Equation 23, Calculating YAW error
// We make the gyro YAW drift correction based