mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
DCM: fixed the sense of the compass GPS test in initial yaw
we were only disabling null offsets when we didn't have a compass, which doesn't make much sense!
This commit is contained in:
parent
cf749ef29c
commit
5bf138fb38
@ -426,11 +426,11 @@ AP_DCM::drift_correction(void)
|
||||
// DCM matrix to the current
|
||||
// roll/pitch values, but with yaw
|
||||
// from the GPS
|
||||
if (!_compass) {
|
||||
if (_compass) {
|
||||
_compass->null_offsets_disable();
|
||||
}
|
||||
rotation_matrix_from_euler(_dcm_matrix, roll, pitch, ToRad(_gps->ground_course));
|
||||
if (!_compass) {
|
||||
if (_compass) {
|
||||
_compass->null_offsets_enable();
|
||||
}
|
||||
_have_initial_yaw = true;
|
||||
|
Loading…
Reference in New Issue
Block a user