mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 10:58:30 -04:00
DCM: use the new use_for_yaw() compass method
This commit is contained in:
parent
c3319afadd
commit
3abe035557
@ -391,7 +391,7 @@ AP_DCM::drift_correction(void)
|
|||||||
|
|
||||||
//*****YAW***************
|
//*****YAW***************
|
||||||
|
|
||||||
if (_compass && _compass->healthy) {
|
if (_compass && _compass->use_for_yaw()) {
|
||||||
if (_have_initial_yaw) {
|
if (_have_initial_yaw) {
|
||||||
// Equation 23, Calculating YAW error
|
// Equation 23, Calculating YAW error
|
||||||
// We make the gyro YAW drift correction based
|
// We make the gyro YAW drift correction based
|
||||||
|
Loading…
Reference in New Issue
Block a user