forked from Archive/PX4-Autopilot
Use new Vector4 class
This commit is contained in:
parent
08d6465ce5
commit
b0189d95af
|
@ -50,7 +50,7 @@ class AxisAngle;
|
|||
* described by this class.
|
||||
*/
|
||||
template<typename Type>
|
||||
class Quaternion : public Vector<Type, 4>
|
||||
class Quaternion : public Vector4<Type>
|
||||
{
|
||||
public:
|
||||
using Matrix41 = Matrix<Type, 4, 1>;
|
||||
|
@ -62,7 +62,7 @@ public:
|
|||
* @param data_ array
|
||||
*/
|
||||
explicit Quaternion(const Type data_[4]) :
|
||||
Vector<Type, 4>(data_)
|
||||
Vector4<Type>(data_)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -84,7 +84,7 @@ public:
|
|||
* @param other Matrix41 to copy
|
||||
*/
|
||||
Quaternion(const Matrix41 &other) :
|
||||
Vector<Type, 4>(other)
|
||||
Vector4<Type>(other)
|
||||
{
|
||||
}
|
||||
|
||||
|
|
|
@ -260,7 +260,7 @@ TEST(MatrixAttitudeTest, Attitude)
|
|||
|
||||
// quaterion copy ctors
|
||||
float data_v4[] = {1, 2, 3, 4};
|
||||
Vector<float, 4> v4(data_v4);
|
||||
Vector4f v4(data_v4);
|
||||
Quatf q_from_v(v4);
|
||||
EXPECT_EQ(q_from_v, v4);
|
||||
|
||||
|
@ -270,15 +270,13 @@ TEST(MatrixAttitudeTest, Attitude)
|
|||
|
||||
// quaternion derivative in frame 1
|
||||
Quatf q1(0, 1, 0, 0);
|
||||
Vector<float, 4> q1_dot1 = q1.derivative1(Vector3f(1, 2, 3));
|
||||
float data_q_dot1_check[] = { -0.5f, 0.0f, -1.5f, 1.0f};
|
||||
Vector<float, 4> q1_dot1_check(data_q_dot1_check);
|
||||
Vector4f q1_dot1 = q1.derivative1(Vector3f(1, 2, 3));
|
||||
Vector4f q1_dot1_check(-0.5f, 0.0f, -1.5f, 1.0f);
|
||||
EXPECT_EQ(q1_dot1, q1_dot1_check);
|
||||
|
||||
// quaternion derivative in frame 2
|
||||
Vector<float, 4> q1_dot2 = q1.derivative2(Vector3f(1, 2, 3));
|
||||
float data_q_dot2_check[] = { -0.5f, 0.0f, 1.5f, -1.0f};
|
||||
Vector<float, 4> q1_dot2_check(data_q_dot2_check);
|
||||
Vector4f q1_dot2 = q1.derivative2(Vector3f(1, 2, 3));
|
||||
Vector4f q1_dot2_check(-0.5f, 0.0f, 1.5f, -1.0f);
|
||||
EXPECT_EQ(q1_dot2, q1_dot2_check);
|
||||
|
||||
// quaternion product
|
||||
|
|
|
@ -50,19 +50,12 @@ TEST(MatrixLeastSquaresTest, 4x3)
|
|||
-1.f, -1.1f, -1.2f
|
||||
};
|
||||
Matrix<float, 4, 3> A(data);
|
||||
|
||||
float b_data[4] = {2.0f, 3.0f, 4.0f, 5.0f};
|
||||
Vector<float, 4> b(b_data);
|
||||
|
||||
float x_check_data[3] = {-0.69168233f,
|
||||
-0.26227593f,
|
||||
-1.03767522f
|
||||
};
|
||||
Vector<float, 3> x_check(x_check_data);
|
||||
Vector4f b(2.0f, 3.0f, 4.0f, 5.0f);
|
||||
Vector3f x_check(-0.69168233f, -0.26227593f, -1.03767522f);
|
||||
|
||||
LeastSquaresSolver<float, 4, 3> qrd = LeastSquaresSolver<float, 4, 3>(A);
|
||||
|
||||
Vector<float, 3> x = qrd.solve(b);
|
||||
Vector3f x = qrd.solve(b);
|
||||
EXPECT_EQ(x, x_check);
|
||||
}
|
||||
|
||||
|
@ -75,20 +68,12 @@ TEST(MatrixLeastSquaresTest, 4x4)
|
|||
-1.f, -1.1f, -1.2f, -1.3f
|
||||
};
|
||||
Matrix<float, 4, 4> A(data);
|
||||
|
||||
float b_data[4] = {2.0f, 3.0f, 4.0f, 5.0f};
|
||||
Vector<float, 4> b(b_data);
|
||||
|
||||
float x_check_data[4] = { 0.97893433f,
|
||||
-2.80798701f,
|
||||
-0.03175765f,
|
||||
-2.19387649f
|
||||
};
|
||||
Vector<float, 4> x_check(x_check_data);
|
||||
Vector4f b(2.0f, 3.0f, 4.0f, 5.0f);
|
||||
Vector4f x_check(0.97893433f, -2.80798701f, -0.03175765f, -2.19387649f);
|
||||
|
||||
LeastSquaresSolver<float, 4, 4> qrd = LeastSquaresSolver<float, 4, 4>(A);
|
||||
|
||||
Vector<float, 4> x = qrd.solve(b);
|
||||
Vector4f x = qrd.solve(b);
|
||||
EXPECT_EQ(x, x_check);
|
||||
}
|
||||
|
||||
|
|
|
@ -92,11 +92,11 @@ TEST(MatrixSparseVectorTest, setZero)
|
|||
|
||||
TEST(MatrixSparseVectorTest, additionWithDenseVector)
|
||||
{
|
||||
Vector<float, 4> dense_vec;
|
||||
Vector4f dense_vec;
|
||||
dense_vec.setAll(1.f);
|
||||
const float data[3] = {1.f, 2.f, 3.f};
|
||||
const SparseVectorf<4, 1, 2, 3> sparse_vec(data);
|
||||
const Vector<float, 4> res = sparse_vec + dense_vec;
|
||||
const Vector4f res = sparse_vec + dense_vec;
|
||||
EXPECT_FLOAT_EQ(res(0), 1.f);
|
||||
EXPECT_FLOAT_EQ(res(1), 2.f);
|
||||
EXPECT_FLOAT_EQ(res(2), 3.f);
|
||||
|
@ -115,7 +115,7 @@ TEST(MatrixSparseVectorTest, addScalar)
|
|||
|
||||
TEST(MatrixSparseVectorTest, dotProductWithDenseVector)
|
||||
{
|
||||
Vector<float, 4> dense_vec;
|
||||
Vector4f dense_vec;
|
||||
dense_vec.setAll(3.f);
|
||||
const float data[3] = {1.f, 2.f, 3.f};
|
||||
const SparseVectorf<4, 1, 2, 3> sparse_vec(data);
|
||||
|
|
|
@ -71,13 +71,7 @@ TEST(MatrixVector3Test, Vector3)
|
|||
|
||||
Vector3f h;
|
||||
EXPECT_EQ(h, Vector3f(0, 0, 0));
|
||||
|
||||
Vector<float, 4> j;
|
||||
j(0) = 1;
|
||||
j(1) = 2;
|
||||
j(2) = 3;
|
||||
j(3) = 4;
|
||||
|
||||
Vector4f j(1.f, 2.f, 3.f, 4.f);
|
||||
Vector3f k = j.slice<3, 1>(0, 0);
|
||||
Vector3f k_test(1, 2, 3);
|
||||
EXPECT_EQ(k, k_test);
|
||||
|
|
|
@ -61,9 +61,8 @@ TEST_F(ArxRlsTest, test211)
|
|||
_rls.update(1, 2);
|
||||
_rls.update(3, 4);
|
||||
_rls.update(5, 6);
|
||||
const Vector<float, 4> coefficients = _rls.getCoefficients();
|
||||
float data_check[] = {-1.79f, 0.97f, 0.42f, -0.48f}; // generated from Python script
|
||||
const Vector<float, 4> coefficients_check(data_check);
|
||||
const Vector4f coefficients = _rls.getCoefficients();
|
||||
const Vector4f coefficients_check(-1.79f, 0.97f, 0.42f, -0.48f); // generated from Python script
|
||||
float eps = 1e-2;
|
||||
EXPECT_TRUE((coefficients - coefficients_check).abs().max() < eps);
|
||||
}
|
||||
|
|
|
@ -250,9 +250,9 @@ float EkfWrapper::getYawAngle() const
|
|||
return euler(2);
|
||||
}
|
||||
|
||||
matrix::Vector<float, 4> EkfWrapper::getQuaternionVariance() const
|
||||
matrix::Vector4f EkfWrapper::getQuaternionVariance() const
|
||||
{
|
||||
return matrix::Vector<float, 4>(_ekf->orientation_covariances().diag());
|
||||
return matrix::Vector4f(_ekf->orientation_covariances().diag());
|
||||
}
|
||||
|
||||
int EkfWrapper::getQuaternionResetCounter() const
|
||||
|
|
|
@ -111,7 +111,7 @@ public:
|
|||
|
||||
Eulerf getEulerAngles() const;
|
||||
float getYawAngle() const;
|
||||
matrix::Vector<float, 4> getQuaternionVariance() const;
|
||||
matrix::Vector4f getQuaternionVariance() const;
|
||||
int getQuaternionResetCounter() const;
|
||||
|
||||
matrix::Vector3f getDeltaVelBiasVariance() const;
|
||||
|
|
|
@ -331,9 +331,9 @@ TEST_F(EkfGpsHeadingTest, stopOnGround)
|
|||
_ekf_wrapper.setMagFuseTypeNone();
|
||||
|
||||
// WHEN: running without yaw aiding
|
||||
const matrix::Vector<float, 4> quat_variance_before = _ekf_wrapper.getQuaternionVariance();
|
||||
const matrix::Vector4f quat_variance_before = _ekf_wrapper.getQuaternionVariance();
|
||||
_sensor_simulator.runSeconds(20.0);
|
||||
const matrix::Vector<float, 4> quat_variance_after = _ekf_wrapper.getQuaternionVariance();
|
||||
const matrix::Vector4f quat_variance_after = _ekf_wrapper.getQuaternionVariance();
|
||||
|
||||
// THEN: the yaw variance is constrained by fusing constant data
|
||||
EXPECT_LT(quat_variance_after(3), quat_variance_before(3));
|
||||
|
|
|
@ -83,7 +83,7 @@ public:
|
|||
|
||||
void quaternionVarianceBigEnoughAfterOrientationInitialization()
|
||||
{
|
||||
const matrix::Vector<float, 4> quat_variance = _ekf_wrapper.getQuaternionVariance();
|
||||
const matrix::Vector4f quat_variance = _ekf_wrapper.getQuaternionVariance();
|
||||
const float quat_variance_limit = 0.0001f;
|
||||
EXPECT_TRUE(quat_variance(1) > quat_variance_limit) << "quat_variance(1)" << quat_variance(1);
|
||||
EXPECT_TRUE(quat_variance(2) > quat_variance_limit) << "quat_variance(2)" << quat_variance(2);
|
||||
|
|
|
@ -59,8 +59,8 @@ public:
|
|||
bool isAvailable() { return _input_available; };
|
||||
|
||||
// Position : 0 : pitch, 1 : roll, 2 : throttle, 3 : yaw
|
||||
const matrix::Vector<float, 4> &getPosition() { return _positions; }; // Raw stick position, no deadzone
|
||||
const matrix::Vector<float, 4> &getPositionExpo() { return _positions_expo; }; // Deadzone and expo applied
|
||||
const matrix::Vector4f &getPosition() { return _positions; }; // Raw stick position, no deadzone
|
||||
const matrix::Vector4f &getPositionExpo() { return _positions_expo; }; // Deadzone and expo applied
|
||||
|
||||
// Helper functions to get stick values more intuitively
|
||||
float getRoll() const { return _positions(1); }
|
||||
|
@ -90,8 +90,8 @@ public:
|
|||
|
||||
private:
|
||||
bool _input_available{false};
|
||||
matrix::Vector<float, 4> _positions; ///< unmodified manual stick inputs
|
||||
matrix::Vector<float, 4> _positions_expo; ///< modified manual sticks using expo function
|
||||
matrix::Vector4f _positions; ///< unmodified manual stick inputs
|
||||
matrix::Vector4f _positions_expo; ///< modified manual sticks using expo function
|
||||
|
||||
uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)};
|
||||
uORB::Subscription _failsafe_flags_sub{ORB_ID(failsafe_flags)};
|
||||
|
|
|
@ -233,7 +233,7 @@ bool MatrixTest::attitudeTests()
|
|||
|
||||
// quaterion copy ctors
|
||||
float data_v4[] = {1, 2, 3, 4};
|
||||
Vector<float, 4> v4(data_v4);
|
||||
Vector4f v4(data_v4);
|
||||
Quatf q_from_v(v4);
|
||||
ut_test(isEqual(q_from_v, v4));
|
||||
|
||||
|
@ -242,7 +242,7 @@ bool MatrixTest::attitudeTests()
|
|||
ut_test(isEqual(q_from_m, m4));
|
||||
|
||||
// quaternion derivative
|
||||
Vector<float, 4> q_dot = q.derivative1(Vector3f(1, 2, 3));
|
||||
Vector4f q_dot = q.derivative1(Vector3f(1, 2, 3));
|
||||
(void)q_dot;
|
||||
|
||||
// quaternion product
|
||||
|
|
Loading…
Reference in New Issue