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 #include <boost/bind.hpp>
26 
27 #include "imuFactorTesting.h"
28 
29 namespace testing {
30 // Create default parameters with Z-down and above noise parameters
31 static boost::shared_ptr<PreintegrationParams> Params() {
32  auto p = PreintegrationParams::MakeSharedD(kGravity);
33  p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3;
34  p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3;
35  p->integrationCovariance = 0.0001 * I_3x3;
36  return p;
37 }
38 }
39 
40 /* ************************************************************************* */
41 TEST(ManifoldPreintegration, BiasCorrectionJacobians) {
42  testing::SomeMeasurements measurements;
43 
44  boost::function<Rot3(const Vector3&, const Vector3&)> deltaRij =
45  [=](const Vector3& a, const Vector3& w) {
47  testing::integrateMeasurements(measurements, &pim);
48  return pim.deltaRij();
49  };
50 
51  boost::function<Point3(const Vector3&, const Vector3&)> deltaPij =
52  [=](const Vector3& a, const Vector3& w) {
54  testing::integrateMeasurements(measurements, &pim);
55  return pim.deltaPij();
56  };
57 
58  boost::function<Vector3(const Vector3&, const Vector3&)> deltaVij =
59  [=](const Vector3& a, const Vector3& w) {
61  testing::integrateMeasurements(measurements, &pim);
62  return pim.deltaVij();
63  };
64 
65  // Actual pre-integrated values
67  testing::integrateMeasurements(measurements, &pim);
68 
69  EXPECT(
71  Matrix3(Z_3x3)));
72  EXPECT(
74  pim.delRdelBiasOmega(), 1e-3));
75 
76  EXPECT(
78  pim.delPdelBiasAcc()));
79  EXPECT(
81  pim.delPdelBiasOmega(), 1e-3));
82 
83  EXPECT(
85  pim.delVdelBiasAcc()));
86  EXPECT(
88  pim.delVdelBiasOmega(), 1e-3));
89 }
90 
91 /* ************************************************************************* */
92 TEST(ManifoldPreintegration, computeError) {
94  NavState x1, x2;
96  Matrix9 aH1, aH2;
97  Matrix96 aH3;
98  pim.computeError(x1, x2, bias, aH1, aH2, aH3);
99  boost::function<Vector9(const NavState&, const NavState&,
100  const imuBias::ConstantBias&)> f =
101  boost::bind(&ManifoldPreintegration::computeError, pim, _1, _2, _3,
102  boost::none, boost::none, boost::none);
103  // NOTE(frank): tolerance of 1e-3 on H1 because approximate away from 0
104  EXPECT(assert_equal(numericalDerivative31(f, x1, x2, bias), aH1, 1e-9));
105  EXPECT(assert_equal(numericalDerivative32(f, x1, x2, bias), aH2, 1e-9));
106  EXPECT(assert_equal(numericalDerivative33(f, x1, x2, bias), aH3, 1e-9));
107 }
108 
109 /* ************************************************************************* */
110 int main() {
111  TestResult tr;
112  return TestRegistry::runAllTests(tr);
113 }
114 /* ************************************************************************* */
const double kGravity
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
void integrateMeasurements(const vector< ImuMeasurement > &measurements, PIM *pim)
internal::FixedSizeMatrix< Y, X3 >::type numericalDerivative33(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Some functions to compute numerical derivatives.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative31(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
internal::FixedSizeMatrix< Y, X1 >::type numericalDerivative21(const boost::function< Y(const X1 &, const X2 &)> &h, const X1 &x1, const X2 &x2, double delta=1e-5)
Common testing infrastructure.
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.
Array33i a
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative32(boost::function< Y(const X1 &, const X2 &, const X3 &)> h, const X1 &x1, const X2 &x2, const X3 &x3, double delta=1e-5)
Vector3 deltaPij() const override
internal::FixedSizeMatrix< Y, X2 >::type numericalDerivative22(boost::function< Y(const X1 &, const X2 &)> h, const X1 &x1, const X2 &x2, double delta=1e-5)
Vector3 deltaVij() const override
static const double kAccelSigma
Test harness methods for expressions.
TEST(ManifoldPreintegration, BiasCorrectionJacobians)
#define EXPECT(condition)
Definition: Test.h:151
static const Vector3 kZero
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static boost::shared_ptr< PreintegratedCombinedMeasurements::Params > Params()
Point3 bias(10,-10, 50)
RowVector3d w
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
imuBias::ConstantBias Bias
Pose3 x1
Definition: testPose3.cpp:588
float * p
static const double kGyroSigma


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