16 using namespace gtsam;
31 6.0, 3.0, 2.0).finished();
35 10.9167, 2.3333, 5.0000,
36 2.3333, 4.6667, -2.6667,
37 5.0000, -2.6667, 8.6667).finished();
47 33.3333333, -1.66666667, 53.3333333,
48 -1.66666667, 0.333333333, -5.16666667,
49 53.3333333, -5.16666667, 110.333333).finished();
57 Matrix actual = AHRS::Cov(100*stationaryF);
59 63.3808333, -0.432166667, -48.1706667,
60 -0.432166667, 8.31053333, -16.6792667,
61 -48.1706667, -16.6792667, 71.4297333).finished();
Concept check for values that can be used in unit tests.
static int runAllTests(TestResult &result)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
#define EXPECT(condition)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
typedef and functions to augment Eigen's VectorXd
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
3D rotation represented as a rotation matrix or quaternion