testAHRS.cpp
Go to the documentation of this file.
1 /*
2  * @file testAHRS.cpp
3  * @brief Test AHRS
4  * @author Frank Dellaert
5  * @author Chris Beall
6  */
7 
8 #include "../AHRS.h"
9 #include <gtsam/geometry/Rot3.h>
10 #include <gtsam/base/Vector.h>
11 #include <gtsam/base/Testable.h>
13 #include <list>
14 
15 using namespace std;
16 using namespace gtsam;
17 
18 // stationary interval of gyro U and acc F
19 Matrix stationaryU = trans((Matrix(3, 3) << -0.0004,-0.0002,-0.0014,0.0006,-0.0003,0.0007,0.0006,-0.0002,-0.0003).finished());
20 Matrix stationaryF = trans((Matrix(3, 3) << 0.1152,-0.0188,9.7419,-0.0163,0.0146,9.7753,-0.0283,-0.0428,9.9021).finished());
21 double g_e = 9.7963; // Atlanta
22 
23 /* ************************************************************************* */
24 TEST (AHRS, cov) {
25 
26  // samples stored by row
27  Matrix A = (Matrix(4, 3) <<
28  1.0, 2.0, 3.0,
29  5.0, 7.0, 0.0,
30  9.0, 4.0, 7.0,
31  6.0, 3.0, 2.0).finished();
32 
33  Matrix actual = AHRS::Cov(trans(A));
34  Matrix expected = (Matrix(3, 3) <<
35  10.9167, 2.3333, 5.0000,
36  2.3333, 4.6667, -2.6667,
37  5.0000, -2.6667, 8.6667).finished();
38 
39  EXPECT(assert_equal(expected, actual, 1e-4));
40 }
41 
42 /* ************************************************************************* */
43 TEST (AHRS, covU) {
44 
45  Matrix actual = AHRS::Cov(10000*stationaryU);
46  Matrix expected = (Matrix(3, 3) <<
47  33.3333333, -1.66666667, 53.3333333,
48  -1.66666667, 0.333333333, -5.16666667,
49  53.3333333, -5.16666667, 110.333333).finished();
50 
51  EXPECT(assert_equal(expected, actual, 1e-4));
52 }
53 
54 /* ************************************************************************* */
55 TEST (AHRS, covF) {
56 
57  Matrix actual = AHRS::Cov(100*stationaryF);
58  Matrix expected = (Matrix(3, 3) <<
59  63.3808333, -0.432166667, -48.1706667,
60  -0.432166667, 8.31053333, -16.6792667,
61  -48.1706667, -16.6792667, 71.4297333).finished();
62 
63  EXPECT(assert_equal(expected, actual, 1e-4));
64 }
65 
66 /* ************************************************************************* */
68  AHRS ahrs = AHRS(stationaryU,stationaryF,g_e);
69 }
70 
71 /* ************************************************************************* */
72 // TODO make a testMechanization_bRn2
73 TEST (AHRS, Mechanization_integrate) {
74  AHRS ahrs = AHRS(stationaryU,stationaryF,g_e);
75  Mechanization_bRn2 mech;
76  KalmanFilter::State state;
77 // boost::tie(mech,state) = ahrs.initialize(g_e);
78 // Vector u = Vector3(0.05,0.0,0.0);
79 // double dt = 2;
80 // Rot3 expected;
81 // Mechanization_bRn2 mech2 = mech.integrate(u,dt);
82 // Rot3 actual = mech2.bRn();
83 // EXPECT(assert_equal(expected, actual));
84 }
85 
86 /* ************************************************************************* */
87 /* TODO: currently fails because of problem with ill-conditioned system
88 TEST (AHRS, init) {
89  AHRS ahrs = AHRS(stationaryU,stationaryF,g_e);
90  std::pair<Mechanization_bRn2, KalmanFilter::State> result = ahrs.initialize(g_e);
91 }
92 */
93 /* ************************************************************************* */
94 int main() {
95  TestResult tr;
96  return TestRegistry::runAllTests(tr);
97 }
98 /* ************************************************************************* */
99 
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
TEST(AHRS, cov)
Definition: testAHRS.cpp:24
Matrix expected
Definition: testMatrix.cpp:974
GaussianDensity::shared_ptr State
Definition: KalmanFilter.h:56
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Definition: Half.h:150
static char trans
Matrix stationaryF
Definition: testAHRS.cpp:20
int main()
Definition: testAHRS.cpp:94
double g_e
Definition: testAHRS.cpp:21
Matrix stationaryU
Definition: testAHRS.cpp:19
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
3D rotation represented as a rotation matrix or quaternion


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:04