mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
APM: enable the new offset nulling in APM
This commit is contained in:
parent
e956e21e7d
commit
989304fb47
@ -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);
|
||||||
}
|
}
|
||||||
|
@ -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;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user