mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 19:07:45 +08:00
matrix: update submodule (improves matrix inversion)
This commit is contained in:
+1
-1
Submodule src/lib/matrix updated: 3d1c9b988d...007a7f78ae
@@ -54,7 +54,7 @@ void
|
|||||||
ControlAllocationPseudoInverse::updatePseudoInverse()
|
ControlAllocationPseudoInverse::updatePseudoInverse()
|
||||||
{
|
{
|
||||||
if (_mix_update_needed) {
|
if (_mix_update_needed) {
|
||||||
_mix = matrix::geninv(_effectiveness);
|
matrix::geninv(_effectiveness, _mix);
|
||||||
_mix_update_needed = false;
|
_mix_update_needed = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -170,8 +170,8 @@ bool MicroBenchMatrix::time_matrix_dcm()
|
|||||||
|
|
||||||
bool MicroBenchMatrix::time_matrix_pseduo_inverse()
|
bool MicroBenchMatrix::time_matrix_pseduo_inverse()
|
||||||
{
|
{
|
||||||
PERF("matrix 6x16 pseudo inverse (all non-zero columns)", A16 = matrix::geninv(B16), 100);
|
PERF("matrix 6x16 pseudo inverse (all non-zero columns)", matrix::geninv(B16, A16), 100);
|
||||||
PERF("matrix 6x16 pseudo inverse (4 non-zero columns)", A16 = matrix::geninv(B16_4), 100);
|
PERF("matrix 6x16 pseudo inverse (4 non-zero columns)", matrix::geninv(B16_4, A16), 100);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -776,7 +776,8 @@ bool MatrixTest::pseudoInverseTests()
|
|||||||
};
|
};
|
||||||
|
|
||||||
Matrix<float, 3, 4> A0(data0);
|
Matrix<float, 3, 4> A0(data0);
|
||||||
Matrix<float, 4, 3> A0_I = geninv(A0);
|
Matrix<float, 4, 3> A0_I;
|
||||||
|
geninv(A0, A0_I);
|
||||||
Matrix<float, 4, 3> A0_I_check(data0_check);
|
Matrix<float, 4, 3> A0_I_check(data0_check);
|
||||||
|
|
||||||
ut_test((A0_I - A0_I_check).abs().max() < 1e-5);
|
ut_test((A0_I - A0_I_check).abs().max() < 1e-5);
|
||||||
@@ -795,7 +796,8 @@ bool MatrixTest::pseudoInverseTests()
|
|||||||
};
|
};
|
||||||
|
|
||||||
Matrix<float, 4, 3> A1(data1);
|
Matrix<float, 4, 3> A1(data1);
|
||||||
Matrix<float, 3, 4> A1_I = geninv(A1);
|
Matrix<float, 3, 4> A1_I;
|
||||||
|
geninv(A1, A1_I);
|
||||||
Matrix<float, 3, 4> A1_I_check(data1_check);
|
Matrix<float, 3, 4> A1_I_check(data1_check);
|
||||||
|
|
||||||
ut_test((A1_I - A1_I_check).abs().max() < 1e-5);
|
ut_test((A1_I - A1_I_check).abs().max() < 1e-5);
|
||||||
@@ -845,7 +847,8 @@ bool MatrixTest::pseudoInverseTests()
|
|||||||
{ 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}
|
{ 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}
|
||||||
};
|
};
|
||||||
Matrix<float, 16, 6> A_check(A_quad_w);
|
Matrix<float, 16, 6> A_check(A_quad_w);
|
||||||
Matrix<float, 16, 6> A = geninv(B);
|
Matrix<float, 16, 6> A;
|
||||||
|
geninv(B, A);
|
||||||
ut_test((A - A_check).abs().max() < 1e-5);
|
ut_test((A - A_check).abs().max() < 1e-5);
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|||||||
Reference in New Issue
Block a user