mirror of https://github.com/ArduPilot/ardupilot
APM: enable the new offset nulling in APM
This commit is contained in:
parent
4821eb4807
commit
3a325541f6
|
@ -784,7 +784,7 @@ static void medium_loop()
|
|||
// Calculate heading
|
||||
Matrix3f m = ahrs.get_dcm_matrix();
|
||||
compass.calculate(m);
|
||||
compass.null_offsets(m);
|
||||
compass.null_offsets();
|
||||
} else {
|
||||
ahrs.set_compass(NULL);
|
||||
}
|
||||
|
|
|
@ -603,7 +603,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
|||
// Calculate heading
|
||||
Matrix3f m = ahrs.get_dcm_matrix();
|
||||
compass.calculate(m);
|
||||
compass.null_offsets(m);
|
||||
compass.null_offsets();
|
||||
}
|
||||
medium_loopCounter = 0;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue