mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: fixed matrix inverse for new name
This commit is contained in:
parent
8278a8a00b
commit
d0d480e858
|
@ -655,11 +655,11 @@ void CompassCalibrator::run_sphere_fit()
|
|||
JTJ2[i*COMPASS_CAL_NUM_SPHERE_PARAMS+i] += _sphere_lambda/lma_damping;
|
||||
}
|
||||
|
||||
if (!inverse(JTJ, JTJ, 4)) {
|
||||
if (!mat_inverse(JTJ, JTJ, 4)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (!inverse(JTJ2, JTJ2, 4)) {
|
||||
if (!mat_inverse(JTJ2, JTJ2, 4)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -771,11 +771,11 @@ void CompassCalibrator::run_ellipsoid_fit()
|
|||
JTJ2[i*COMPASS_CAL_NUM_ELLIPSOID_PARAMS+i] += _ellipsoid_lambda/lma_damping;
|
||||
}
|
||||
|
||||
if (!inverse(JTJ, JTJ, 9)) {
|
||||
if (!mat_inverse(JTJ, JTJ, 9)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (!inverse(JTJ2, JTJ2, 9)) {
|
||||
if (!mat_inverse(JTJ2, JTJ2, 9)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue