mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Compass: fix sitl build
This commit is contained in:
parent
7cb9fa8898
commit
05d3616e0d
@ -1041,7 +1041,7 @@ float CompassCalibrator::det6x6(const float C[36])
|
||||
}
|
||||
|
||||
f = A[0];
|
||||
isodd = FALSE;
|
||||
isodd = false;
|
||||
for (jy = 0; jy < 5; jy++) {
|
||||
f *= A[(jy + 6 * (1 + jy)) + 1];
|
||||
if (ipiv[jy] > 1 + jy) {
|
||||
@ -1130,7 +1130,7 @@ float CompassCalibrator::det9x9(const float C[81])
|
||||
}
|
||||
|
||||
f = A[0];
|
||||
isodd = FALSE;
|
||||
isodd = false;
|
||||
for (jy = 0; jy < 8; jy++) {
|
||||
f *= A[(jy + 9 * (1 + jy)) + 1];
|
||||
if (ipiv[jy] > 1 + jy) {
|
||||
|
Loading…
Reference in New Issue
Block a user