testManifoldPreintegration.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 
23 
25 
26 #include "imuFactorTesting.h"
27 
28 using namespace std::placeholders;
29 
30 namespace testing {
31 // Create default parameters with Z-down and above noise parameters
32 static std::shared_ptr<PreintegrationParams> Params() {
33  auto p = PreintegrationParams::MakeSharedD(kGravity);
34  p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3;
35  p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3;
36  p->integrationCovariance = 0.0001 * I_3x3;
37  return p;
38 }
39 }
40 
41 /* ************************************************************************* */
42 TEST(ManifoldPreintegration, BiasCorrectionJacobians) {
43  testing::SomeMeasurements measurements;
44 
45  std::function<Rot3(const Vector3&, const Vector3&)> deltaRij =
46  [=](const Vector3& a, const Vector3& w) {
48  testing::integrateMeasurements(measurements, &pim);
49  return pim.deltaRij();
50  };
51 
52  std::function<Point3(const Vector3&, const Vector3&)> deltaPij =
53  [=](const Vector3& a, const Vector3& w) {
55  testing::integrateMeasurements(measurements, &pim);
56  return pim.deltaPij();
57  };
58 
59  std::function<Vector3(const Vector3&, const Vector3&)> deltaVij =
60  [=](const Vector3& a, const Vector3& w) {
62  testing::integrateMeasurements(measurements, &pim);
63  return pim.deltaVij();
64  };
65 
66  // Actual pre-integrated values
68  testing::integrateMeasurements(measurements, &pim);
69 
70  EXPECT(
72  Matrix3(Z_3x3)));
73  EXPECT(
75  pim.delRdelBiasOmega(), 1e-3));
76 
77  EXPECT(
79  pim.delPdelBiasAcc()));
80  EXPECT(
82  pim.delPdelBiasOmega(), 1e-3));
83 
84  EXPECT(
86  pim.delVdelBiasAcc()));
87  EXPECT(
89  pim.delVdelBiasOmega(), 1e-3));
90 }
91 
92 /* ************************************************************************* */
93 TEST(ManifoldPreintegration, computeError) {
95  NavState x1, x2;
97  Matrix9 aH1, aH2;
98  Matrix96 aH3;
99  pim.computeError(x1, x2, bias, aH1, aH2, aH3);
100  std::function<Vector9(const NavState&, const NavState&,
101  const imuBias::ConstantBias&)>
102  f = std::bind(&ManifoldPreintegration::computeError, pim,
103  std::placeholders::_1, std::placeholders::_2,
104  std::placeholders::_3, nullptr, nullptr,
105  nullptr);
106  // NOTE(frank): tolerance of 1e-3 on H1 because approximate away from 0
107  EXPECT(assert_equal(numericalDerivative31(f, x1, x2, bias), aH1, 1e-9));
108  EXPECT(assert_equal(numericalDerivative32(f, x1, x2, bias), aH2, 1e-9));
109  EXPECT(assert_equal(numericalDerivative33(f, x1, x2, bias), aH3, 1e-9));
110 }
111 
112 /* ************************************************************************* */
113 int main() {
114  TestResult tr;
115  return TestRegistry::runAllTests(tr);
116 }
117 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
gtsam::numericalDerivative33
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Definition: numericalDerivative.h:292
testing
Definition: benchmark.h:20
kGyroSigma
static const double kGyroSigma
Definition: testScenarioRunner.cpp:32
ManifoldPreintegration.h
kAccelSigma
static const double kAccelSigma
Definition: testScenarioRunner.cpp:33
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
main
int main()
Definition: testManifoldPreintegration.cpp:113
gtsam::ManifoldPreintegration::delVdelBiasAcc
Matrix3 delVdelBiasAcc() const
Definition: ManifoldPreintegration.h:84
gtsam::ManifoldPreintegration::deltaRij
Rot3 deltaRij() const override
Definition: ManifoldPreintegration.h:77
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::NavState
Definition: NavState.h:34
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
testing::integrateMeasurements
void integrateMeasurements(const vector< ImuMeasurement > &measurements, PIM *pim)
Definition: imuFactorTesting.h:59
testing::Params
static std::shared_ptr< PreintegrationParams > Params()
Definition: testManifoldPreintegration.cpp:32
numericalDerivative.h
Some functions to compute numerical derivatives.
expressions.h
Common expressions, both linear and non-linear.
x1
Pose3 x1
Definition: testPose3.cpp:663
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::numericalDerivative32
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Definition: numericalDerivative.h:259
gtsam::ManifoldPreintegration::delPdelBiasOmega
Matrix3 delPdelBiasOmega() const
Definition: ManifoldPreintegration.h:83
gtsam::ManifoldPreintegration::deltaVij
Vector3 deltaVij() const override
Definition: ManifoldPreintegration.h:79
gtsam::numericalDerivative31
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(std::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Definition: numericalDerivative.h:226
kGravity
const double kGravity
Definition: ImuFactorsExample2.cpp:36
gtsam::ManifoldPreintegration::delRdelBiasOmega
Matrix3 delRdelBiasOmega() const
Definition: ManifoldPreintegration.h:81
gtsam::ManifoldPreintegration::delVdelBiasOmega
Matrix3 delVdelBiasOmega() const
Definition: ManifoldPreintegration.h:85
gtsam::ManifoldPreintegration::delPdelBiasAcc
Matrix3 delPdelBiasAcc() const
Definition: ManifoldPreintegration.h:82
TestResult
Definition: TestResult.h:26
expressionTesting.h
Test harness methods for expressions.
imuFactorTesting.h
Common testing infrastructure.
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
TEST
TEST(ManifoldPreintegration, BiasCorrectionJacobians)
Definition: testManifoldPreintegration.cpp:42
gtsam::ManifoldPreintegration
Definition: ManifoldPreintegration.h:33
gtsam::imuBias::ConstantBias
Definition: ImuBias.h:32
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::PreintegrationBase::computeError
Vector9 computeError(const NavState &state_i, const NavState &state_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1, OptionalJacobian< 9, 9 > H2, OptionalJacobian< 9, 6 > H3) const
Calculate error given navStates.
Definition: PreintegrationBase.cpp:141
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
p
float * p
Definition: Tutorial_Map_using.cpp:9
kZero
static const Vector kZero
Definition: testLPSolver.cpp:37
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
ExpressionFactor.h
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
Eigen::Matrix< double, 9, 9 >
gtsam::ManifoldPreintegration::deltaPij
Vector3 deltaPij() const override
Definition: ManifoldPreintegration.h:78
testing::Params
static std::shared_ptr< PreintegratedCombinedMeasurements::Params > Params(const Matrix3 &biasAccCovariance=Matrix3::Zero(), const Matrix3 &biasOmegaCovariance=Matrix3::Zero(), const Matrix6 &biasAccOmegaInt=Matrix6::Zero())
Definition: testCombinedImuFactor.cpp:39
x2
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
testing::SomeMeasurements
Definition: imuFactorTesting.h:65


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:06:15