mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: Correct missing declaration warning
This commit is contained in:
parent
1d9d0a40db
commit
a8e5ff93b5
@ -72,7 +72,7 @@ static inline void swap(float &a, float &b)
|
|||||||
* @returns false = matrix is Singular or non positive definite, true = matrix inversion successful
|
* @returns false = matrix is Singular or non positive definite, true = matrix inversion successful
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void mat_pivot(float* A, float* pivot, uint8_t n)
|
static void mat_pivot(float* A, float* pivot, uint8_t n)
|
||||||
{
|
{
|
||||||
for(uint8_t i = 0;i<n;i++){
|
for(uint8_t i = 0;i<n;i++){
|
||||||
for(uint8_t j=0;j<n;j++) {
|
for(uint8_t j=0;j<n;j++) {
|
||||||
@ -104,7 +104,7 @@ void mat_pivot(float* A, float* pivot, uint8_t n)
|
|||||||
* @param n, dimension of matrix
|
* @param n, dimension of matrix
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void mat_forward_sub(float *L, float *out, uint8_t n)
|
static void mat_forward_sub(float *L, float *out, uint8_t n)
|
||||||
{
|
{
|
||||||
// Forward substitution solve LY = I
|
// Forward substitution solve LY = I
|
||||||
for(int i = 0; i < n; i++) {
|
for(int i = 0; i < n; i++) {
|
||||||
@ -126,7 +126,7 @@ void mat_forward_sub(float *L, float *out, uint8_t n)
|
|||||||
* @param n, dimension of matrix
|
* @param n, dimension of matrix
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void mat_back_sub(float *U, float *out, uint8_t n)
|
static void mat_back_sub(float *U, float *out, uint8_t n)
|
||||||
{
|
{
|
||||||
// Backward Substitution solve UY = I
|
// Backward Substitution solve UY = I
|
||||||
for(int i = n-1; i >= 0; i--) {
|
for(int i = n-1; i >= 0; i--) {
|
||||||
@ -149,7 +149,7 @@ void mat_back_sub(float *U, float *out, uint8_t n)
|
|||||||
* @param n, dimension of matrix
|
* @param n, dimension of matrix
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void mat_LU_decompose(float* A, float* L, float* U, float *P, uint8_t n)
|
static void mat_LU_decompose(float* A, float* L, float* U, float *P, uint8_t n)
|
||||||
{
|
{
|
||||||
memset(L,0,n*n*sizeof(float));
|
memset(L,0,n*n*sizeof(float));
|
||||||
memset(U,0,n*n*sizeof(float));
|
memset(U,0,n*n*sizeof(float));
|
||||||
@ -189,7 +189,7 @@ void mat_LU_decompose(float* A, float* L, float* U, float *P, uint8_t n)
|
|||||||
* @param n, dimension of square matrix
|
* @param n, dimension of square matrix
|
||||||
* @returns false = matrix is Singular, true = matrix inversion successful
|
* @returns false = matrix is Singular, true = matrix inversion successful
|
||||||
*/
|
*/
|
||||||
bool mat_inverse(float* A, float* inv, uint8_t n)
|
static bool mat_inverse(float* A, float* inv, uint8_t n)
|
||||||
{
|
{
|
||||||
float *L, *U, *P;
|
float *L, *U, *P;
|
||||||
bool ret = true;
|
bool ret = true;
|
||||||
|
Loading…
Reference in New Issue
Block a user