testCombinedImuFactor.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 
24 #include <gtsam/geometry/Pose3.h>
25 #include <gtsam/nonlinear/Values.h>
26 #include <gtsam/inference/Symbol.h>
29 
31 
32 #include <boost/bind.hpp>
33 #include <list>
34 
35 #include "imuFactorTesting.h"
36 
37 namespace testing {
38 // Create default parameters with Z-down and above noise parameters
39 static boost::shared_ptr<PreintegratedCombinedMeasurements::Params> Params() {
40  auto p = PreintegratedCombinedMeasurements::Params::MakeSharedD(kGravity);
41  p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3;
42  p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3;
43  p->integrationCovariance = 0.0001 * I_3x3;
44  return p;
45 }
46 }
47 
48 /* ************************************************************************* */
49 TEST( CombinedImuFactor, PreintegratedMeasurements ) {
50  // Linearization point
51  Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0));
52 
53  // Measurements
54  Vector3 measuredAcc(0.1, 0.0, 0.0);
55  Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0);
56  double deltaT = 0.5;
57  double tol = 1e-6;
58 
59  auto p = testing::Params();
60 
61  // Actual preintegrated values
62  PreintegratedImuMeasurements expected1(p, bias);
63  expected1.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
64 
65  PreintegratedCombinedMeasurements actual1(p, bias);
66 
67  actual1.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
68 
69  EXPECT(assert_equal(Vector(expected1.deltaPij()), actual1.deltaPij(), tol));
70  EXPECT(assert_equal(Vector(expected1.deltaVij()), actual1.deltaVij(), tol));
71  EXPECT(assert_equal(expected1.deltaRij(), actual1.deltaRij(), tol));
72  DOUBLES_EQUAL(expected1.deltaTij(), actual1.deltaTij(), tol);
73 }
74 
75 /* ************************************************************************* */
76 TEST( CombinedImuFactor, ErrorWithBiases ) {
77  Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot)
78  Bias bias2(Vector3(0.2, 0.2, 0), Vector3(1, 0, 0.3)); // Biases (acc, rot)
79  Pose3 x1(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0)), Point3(5.0, 1.0, -50.0));
80  Vector3 v1(0.5, 0.0, 0.0);
81  Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)),
82  Point3(5.5, 1.0, -50.0));
83  Vector3 v2(0.5, 0.0, 0.0);
84 
85  auto p = testing::Params();
86  p->omegaCoriolis = Vector3(0,0.1,0.1);
88  p, Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)));
89 
90  // Measurements
92  measuredOmega << 0, 0, M_PI / 10.0 + 0.3;
94  x1.rotation().unrotate(-p->n_gravity) + Vector3(0.2, 0.0, 0.0);
95  double deltaT = 1.0;
96  double tol = 1e-6;
97 
98  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
99 
101  Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)));
102 
103  combined_pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
104 
105  // Create factor
106  ImuFactor imuFactor(X(1), V(1), X(2), V(2), B(1), pim);
107 
108  noiseModel::Gaussian::shared_ptr Combinedmodel =
109  noiseModel::Gaussian::Covariance(combined_pim.preintMeasCov());
110  CombinedImuFactor combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2),
111  combined_pim);
112 
113  Vector errorExpected = imuFactor.evaluateError(x1, v1, x2, v2, bias);
114  Vector errorActual = combinedfactor.evaluateError(x1, v1, x2, v2, bias,
115  bias2);
116  EXPECT(assert_equal(errorExpected, errorActual.head(9), tol));
117 
118  // Expected Jacobians
119  Matrix H1e, H2e, H3e, H4e, H5e;
120  (void) imuFactor.evaluateError(x1, v1, x2, v2, bias, H1e, H2e, H3e, H4e, H5e);
121 
122  // Actual Jacobians
123  Matrix H1a, H2a, H3a, H4a, H5a, H6a;
124  (void) combinedfactor.evaluateError(x1, v1, x2, v2, bias, bias2, H1a, H2a,
125  H3a, H4a, H5a, H6a);
126 
127  EXPECT(assert_equal(H1e, H1a.topRows(9)));
128  EXPECT(assert_equal(H2e, H2a.topRows(9)));
129  EXPECT(assert_equal(H3e, H3a.topRows(9)));
130  EXPECT(assert_equal(H4e, H4a.topRows(9)));
131  EXPECT(assert_equal(H5e, H5a.topRows(9)));
132 }
133 
134 /* ************************************************************************* */
135 #ifdef GTSAM_TANGENT_PREINTEGRATION
136 TEST(CombinedImuFactor, FirstOrderPreIntegratedMeasurements) {
137  auto p = testing::Params();
138  testing::SomeMeasurements measurements;
139 
140  auto preintegrated = [=](const Vector3& a, const Vector3& w) {
142  testing::integrateMeasurements(measurements, &pim);
143  return pim.preintegrated();
144  };
145 
146  // Actual pre-integrated values
148  testing::integrateMeasurements(measurements, &pim);
149 
150  EXPECT(assert_equal(numericalDerivative21<Vector9, Vector3, Vector3>(preintegrated, Z_3x1, Z_3x1),
151  pim.preintegrated_H_biasAcc()));
152  EXPECT(assert_equal(numericalDerivative22<Vector9, Vector3, Vector3>(preintegrated, Z_3x1, Z_3x1),
153  pim.preintegrated_H_biasOmega(), 1e-3));
154 }
155 #endif
156 
157 /* ************************************************************************* */
158 TEST(CombinedImuFactor, PredictPositionAndVelocity) {
159  const Bias bias(Vector3(0, 0.1, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot)
160 
161  auto p = testing::Params();
162 
163  // Measurements
164  const Vector3 measuredOmega(0, 0.1, 0); // M_PI/10.0+0.3;
165  const Vector3 measuredAcc(0, 1.1, -kGravity);
166  const double deltaT = 0.01;
167 
169 
170  for (int i = 0; i < 100; ++i)
171  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
172 
173  // Create factor
174  const noiseModel::Gaussian::shared_ptr combinedmodel =
175  noiseModel::Gaussian::Covariance(pim.preintMeasCov());
176  const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim);
177 
178  // Predict
179  const NavState actual = pim.predict(NavState(), bias);
180  const Pose3 expectedPose(Rot3(), Point3(0, 0.5, 0));
181  const Vector3 expectedVelocity(0, 1, 0);
182  EXPECT(assert_equal(expectedPose, actual.pose()));
183  EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity())));
184 }
185 
186 /* ************************************************************************* */
187 TEST(CombinedImuFactor, PredictRotation) {
188  const Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot)
189  auto p = testing::Params();
192  const Vector3 measuredOmega(0, 0, M_PI / 10.0);
193  const double deltaT = 0.01;
194  const double tol = 1e-4;
195  for (int i = 0; i < 100; ++i)
196  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
197  const CombinedImuFactor Combinedfactor(X(1), V(1), X(2), V(2), B(1), B(2), pim);
198 
199  // Predict
200  const Pose3 x(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0)), x2;
201  const Vector3 v(0, 0, 0), v2;
202  const NavState actual = pim.predict(NavState(x, v), bias);
203  const Pose3 expectedPose(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0, 0, 0));
204  EXPECT(assert_equal(expectedPose, actual.pose(), tol));
205 }
206 
207 /* ************************************************************************* */
208 int main() {
209  TestResult tr;
210  return TestRegistry::runAllTests(tr);
211 }
212 /* ************************************************************************* */
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
Definition: ImuFactor.cpp:53
const double kGravity
Provides additional testing facilities for common data structures.
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
Vector v2
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector v1
A non-templated config holding any types of Manifold-group elements.
Bias bias2(biasAcc2, biasGyro2)
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:142
ArrayXcf v
Definition: Cwise_arg.cpp:1
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
Point3 unrotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
rotate point from world to rotated frame
Definition: Rot3.cpp:136
const Pose3 pose() const
Definition: NavState.h:86
void integrateMeasurements(const vector< ImuMeasurement > &measurements, PIM *pim)
Pose2_ Expmap(const Vector3_ &xi)
TEST(CombinedImuFactor, PreintegratedMeasurements)
Some functions to compute numerical derivatives.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
static const Vector3 kGravityAlongNavZDown(0, 0, kGravity)
Common testing infrastructure.
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
NavState predict(const NavState &state_i, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 6 > H2=boost::none) const
Predict state at time j.
Array33i a
Vector3 deltaPij() const override
Vector evaluateError(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none, boost::optional< Matrix & > H5=boost::none) const override
vector of errors
Definition: ImuFactor.cpp:150
Eigen::VectorXd Vector
Definition: Vector.h:38
Vector3 deltaVij() const override
static const double kAccelSigma
#define EXPECT(condition)
Definition: Test.h:151
static const double deltaT
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static boost::shared_ptr< PreintegratedCombinedMeasurements::Params > Params()
static const Vector3 measuredAcc
Point3 bias(10,-10, 50)
RowVector3d w
const Velocity3 & velocity(OptionalJacobian< 3, 9 > H=boost::none) const
Definition: NavState.cpp:64
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
static const Vector3 measuredOmega(w, 0, 0)
imuBias::ConstantBias Bias
Pose3 x1
Definition: testPose3.cpp:588
float * p
boost::shared_ptr< Gaussian > shared_ptr
Definition: NoiseModel.h:189
static const double kGyroSigma
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
#define X
Definition: icosphere.cpp:20
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
3D Pose
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266
int main()


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