mirror of https://github.com/ArduPilot/ardupilot
APM: avoid fetching the DCM matrix twice
also no special case for quaternions
This commit is contained in:
parent
1016d3c95d
commit
371677610d
|
@ -781,12 +781,9 @@ static void medium_loop()
|
||||||
if (g.compass_enabled && compass.read()) {
|
if (g.compass_enabled && compass.read()) {
|
||||||
dcm.set_compass(&compass);
|
dcm.set_compass(&compass);
|
||||||
// Calculate heading
|
// Calculate heading
|
||||||
#if QUATERNION_ENABLE == ENABLED
|
Matrix3f m = dcm.get_dcm_matrix();
|
||||||
compass.calculate(dcm.roll, dcm.pitch);
|
compass.calculate(m);
|
||||||
#else
|
compass.null_offsets(m);
|
||||||
compass.calculate(dcm.get_dcm_matrix());
|
|
||||||
compass.null_offsets(dcm.get_dcm_matrix());
|
|
||||||
#endif
|
|
||||||
} else {
|
} else {
|
||||||
dcm.set_compass(NULL);
|
dcm.set_compass(NULL);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue