mirror of https://github.com/ArduPilot/ardupilot
AP_AccelCal: fixed inverse matrix call for new name
This commit is contained in:
parent
999268cbba
commit
2e2ccb40b2
|
@ -355,7 +355,7 @@ void AccelCalibrator::run_fit(uint8_t max_iterations, float& fitness)
|
|||
}
|
||||
}
|
||||
|
||||
if (!inverse(JTJ, JTJ, get_num_params())) {
|
||||
if (!mat_inverse(JTJ, JTJ, get_num_params())) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue