testImuBias.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 
22 
23 using namespace std::placeholders;
24 using namespace std;
25 using namespace gtsam;
26 
28 
29 Vector biasAcc1(Vector3(0.2, -0.1, 0));
30 Vector biasGyro1(Vector3(0.1, -0.3, -0.2));
32 
33 Vector biasAcc2(Vector3(0.1, 0.2, 0.04));
34 Vector biasGyro2(Vector3(-0.002, 0.005, 0.03));
36 
37 /* ************************************************************************* */
38 TEST(ImuBias, Constructor) {
39  // Default Constructor
40  Bias bias1;
41 
42  // Acc + Gyro Constructor
44 
45  // Copy Constructor
46  Bias bias3(bias2);
47 }
48 
49 /* ************************************************************************* */
50 TEST(ImuBias, operatorSub) {
51  Bias biasActual = -bias1;
52  Bias biasExpected(-biasAcc1, -biasGyro1);
53  EXPECT(assert_equal(biasExpected, biasActual));
54 }
55 
56 /* ************************************************************************* */
57 TEST(ImuBias, operatorAdd) {
58  Bias biasActual = bias2 + bias1;
59  Bias biasExpected(biasAcc2 + biasAcc1, biasGyro2 + biasGyro1);
60  EXPECT(assert_equal(biasExpected, biasActual));
61 }
62 
63 /* ************************************************************************* */
64 TEST(ImuBias, operatorSubB) {
65  Bias biasActual = bias2 - bias1;
66  Bias biasExpected(biasAcc2 - biasAcc1, biasGyro2 - biasGyro1);
67  EXPECT(assert_equal(biasExpected, biasActual));
68 }
69 
70 /* ************************************************************************* */
71 TEST(ImuBias, Correct1) {
72  Matrix aH1, aH2;
73  const Vector3 measurement(1, 2, 3);
74  std::function<Vector3(const Bias&, const Vector3&)> f =
75  std::bind(&Bias::correctAccelerometer, std::placeholders::_1,
76  std::placeholders::_2, nullptr, nullptr);
80 }
81 
82 /* ************************************************************************* */
83 TEST(ImuBias, Correct2) {
84  Matrix aH1, aH2;
85  const Vector3 measurement(1, 2, 3);
86  std::function<Vector3(const Bias&, const Vector3&)> f =
87  std::bind(&Bias::correctGyroscope, std::placeholders::_1,
88  std::placeholders::_2, nullptr, nullptr);
92 }
93 
94 /* ************************************************************************* */
95 int main() {
96  TestResult tr;
97  return TestRegistry::runAllTests(tr);
98 }
99 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
biasGyro1
Vector biasGyro1(Vector3(0.1, -0.3, -0.2))
biasAcc2
Vector biasAcc2(Vector3(0.1, 0.2, 0.04))
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
gtsam::numericalDerivative22
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(std::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:195
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::imuBias::ConstantBias::correctAccelerometer
Vector3 correctAccelerometer(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Definition: ImuBias.h:76
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
bias2
Bias bias2(biasAcc2, biasGyro2)
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
bias1
Bias bias1(biasAcc1, biasGyro1)
biasAcc1
Vector biasAcc1(Vector3(0.2, -0.1, 0))
numericalDerivative.h
Some functions to compute numerical derivatives.
TEST
TEST(ImuBias, Constructor)
Definition: testImuBias.cpp:38
TestResult
Definition: TestResult.h:26
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
ImuBias.h
gtsam::imuBias::ConstantBias
Definition: ImuBias.h:32
gtsam
traits
Definition: chartTesting.h:28
Bias
imuBias::ConstantBias Bias
Definition: testImuBias.cpp:27
gtsam::numericalDerivative21
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const std::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Definition: numericalDerivative.h:166
biasGyro2
Vector biasGyro2(Vector3(-0.002, 0.005, 0.03))
std
Definition: BFloat16.h:88
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
main
int main()
Definition: testImuBias.cpp:95
gtsam::imuBias::ConstantBias::correctGyroscope
Vector3 correctGyroscope(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Definition: ImuBias.h:85
measurement
static Point2 measurement(323.0, 240.0)


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:05:58