APM: enable the new offset nulling in APM

This commit is contained in:
Andrew Tridgell 2012-03-27 15:16:41 +11:00
parent e956e21e7d
commit 989304fb47
2 changed files with 2 additions and 2 deletions

View File

@ -784,7 +784,7 @@ static void medium_loop()
// Calculate heading // Calculate heading
Matrix3f m = ahrs.get_dcm_matrix(); Matrix3f m = ahrs.get_dcm_matrix();
compass.calculate(m); compass.calculate(m);
compass.null_offsets(m); compass.null_offsets();
} else { } else {
ahrs.set_compass(NULL); ahrs.set_compass(NULL);
} }

View File

@ -603,7 +603,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
// Calculate heading // Calculate heading
Matrix3f m = ahrs.get_dcm_matrix(); Matrix3f m = ahrs.get_dcm_matrix();
compass.calculate(m); compass.calculate(m);
compass.null_offsets(m); compass.null_offsets();
} }
medium_loopCounter = 0; medium_loopCounter = 0;
} }