mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_Math: Matrix: Change deallocator to match allocator used
This commit is contained in:
parent
e17fdb2aa9
commit
70942472d3
@ -177,7 +177,7 @@ static void mat_LU_decompose(float* A, float* L, float* U, float *P, uint8_t n)
|
||||
}
|
||||
}
|
||||
}
|
||||
free(APrime);
|
||||
delete[] APrime;
|
||||
}
|
||||
|
||||
/*
|
||||
@ -208,8 +208,8 @@ static bool mat_inverse(float* A, float* inv, uint8_t n)
|
||||
mat_back_sub(U,U_inv,n);
|
||||
|
||||
// decomposed matrices no longer required
|
||||
free(L);
|
||||
free(U);
|
||||
delete[] L;
|
||||
delete[] U;
|
||||
|
||||
float *inv_unpivoted = mat_mul(U_inv,L_inv,n);
|
||||
float *inv_pivoted = mat_mul(inv_unpivoted, P, n);
|
||||
@ -225,11 +225,11 @@ static bool mat_inverse(float* A, float* inv, uint8_t n)
|
||||
memcpy(inv,inv_pivoted,n*n*sizeof(float));
|
||||
|
||||
//free memory
|
||||
free(inv_pivoted);
|
||||
free(inv_unpivoted);
|
||||
free(P);
|
||||
free(U_inv);
|
||||
free(L_inv);
|
||||
delete[] inv_pivoted;
|
||||
delete[] inv_unpivoted;
|
||||
delete[] P;
|
||||
delete[] U_inv;
|
||||
delete[] L_inv;
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user