testImuFactor.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 
21 // #define ENABLE_TIMING // uncomment for timing results
22 
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/nonlinear/Values.h>
28 #include <gtsam/linear/Sampler.h>
31 
33 #include <boost/bind.hpp>
34 #include <list>
35 
36 #include "imuFactorTesting.h"
37 
38 namespace testing {
39 // Create default parameters with Z-down and above noise parameters
40 static boost::shared_ptr<PreintegrationParams> Params() {
41  auto p = PreintegrationParams::MakeSharedD(kGravity);
42  p->gyroscopeCovariance = kGyroSigma * kGyroSigma * I_3x3;
43  p->accelerometerCovariance = kAccelSigma * kAccelSigma * I_3x3;
44  p->integrationCovariance = 0.0001 * I_3x3;
45  return p;
46 }
47 }
48 
49 /* ************************************************************************* */
50 namespace {
51 // Auxiliary functions to test evaluate error in ImuFactor
52 /* ************************************************************************* */
53 Rot3 evaluateRotationError(const ImuFactor& factor, const Pose3& pose_i,
54  const Vector3& vel_i, const Pose3& pose_j, const Vector3& vel_j,
55  const Bias& bias) {
56  return Rot3::Expmap(
57  factor.evaluateError(pose_i, vel_i, pose_j, vel_j, bias).head(3));
58 }
59 
60 } // namespace
61 
62 /* ************************************************************************* */
63 TEST(ImuFactor, PreintegratedMeasurementsConstruction) {
64  // Actual pre-integrated values
66  EXPECT(assert_equal(Rot3(), actual.deltaRij()));
67  EXPECT(assert_equal(kZero, actual.deltaPij()));
68  EXPECT(assert_equal(kZero, actual.deltaVij()));
69  DOUBLES_EQUAL(0.0, actual.deltaTij(), 1e-9);
70 }
71 
72 /* ************************************************************************* */
73 TEST(ImuFactor, PreintegratedMeasurementsReset) {
74 
75  auto p = testing::Params();
76  // Create a preintegrated measurement struct and integrate
78  Vector3 measuredAcc(0.5, 1.0, 0.5);
79  Vector3 measuredOmega(0.1, 0.3, 0.1);
80  double deltaT = 1.0;
81  pimActual.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
82 
83  // reset and make sure that it is the same as a fresh one
84  pimActual.resetIntegration();
86 
87  // Now create one with a different bias ..
88  Bias nonZeroBias(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3));
89  PreintegratedImuMeasurements pimExpected(p, nonZeroBias);
90 
91  // integrate again, then reset to a new bias
92  pimActual.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
93  pimActual.resetIntegrationAndSetBias(nonZeroBias);
94  CHECK(assert_equal(pimActual, pimExpected));
95 }
96 
97 /* ************************************************************************* */
98 TEST(ImuFactor, Accelerating) {
99  const double a = 0.2, v = 50;
100 
101  // Set up body pointing towards y axis, and start at 10,20,0 with velocity going in X
102  // The body itself has Z axis pointing down
103  const Rot3 nRb(Point3(0, 1, 0), Point3(1, 0, 0), Point3(0, 0, -1));
104  const Point3 initial_position(10, 20, 0);
105  const Vector3 initial_velocity(v, 0, 0);
106 
107  const AcceleratingScenario scenario(nRb, initial_position, initial_velocity,
108  Vector3(a, 0, 0));
109 
110  const double T = 3.0; // seconds
111  ScenarioRunner runner(scenario, testing::Params(), T / 10);
112 
113  PreintegratedImuMeasurements pim = runner.integrate(T);
114  EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose(), 1e-9));
115 
116  Matrix9 estimatedCov = runner.estimateCovariance(T, 100);
117  EXPECT(assert_equal(estimatedCov, pim.preintMeasCov(), 0.1));
118 }
119 
120 /* ************************************************************************* */
121 TEST(ImuFactor, PreintegratedMeasurements) {
122  // Measurements
123  const double a = 0.1, w = M_PI / 100.0;
124  Vector3 measuredAcc(a, 0.0, 0.0);
125  Vector3 measuredOmega(w, 0.0, 0.0);
126  double deltaT = 0.5;
127 
128  // Expected pre-integrated values
129  Vector3 expectedDeltaR1(w * deltaT, 0.0, 0.0);
130  Vector3 expectedDeltaP1(0.5 * a * deltaT*deltaT, 0, 0);
131  Vector3 expectedDeltaV1(0.05, 0.0, 0.0);
132 
133  // Actual pre-integrated values
135  actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
136  EXPECT(assert_equal(Rot3::Expmap(expectedDeltaR1), actual.deltaRij()));
137  EXPECT(assert_equal(expectedDeltaP1, actual.deltaPij()));
138  EXPECT(assert_equal(expectedDeltaV1, actual.deltaVij()));
139  DOUBLES_EQUAL(0.5, actual.deltaTij(), 1e-9);
140 
141  // Check derivatives of computeError
142  Bias bias(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); // Biases (acc, rot)
143  NavState x1, x2 = actual.predict(x1, bias);
144 
145  {
146  Matrix9 aH1, aH2;
147  Matrix96 aH3;
148  actual.computeError(x1, x2, bias, aH1, aH2, aH3);
149  boost::function<Vector9(const NavState&, const NavState&, const Bias&)> f =
150  boost::bind(&PreintegrationBase::computeError, actual, _1, _2, _3,
151  boost::none, boost::none, boost::none);
152  EXPECT(assert_equal(numericalDerivative31(f, x1, x2, bias), aH1, 1e-9));
153  EXPECT(assert_equal(numericalDerivative32(f, x1, x2, bias), aH2, 1e-9));
154  EXPECT(assert_equal(numericalDerivative33(f, x1, x2, bias), aH3, 1e-9));
155  }
156 
157  // Integrate again
158  Vector3 expectedDeltaR2(2.0 * 0.5 * M_PI / 100.0, 0.0, 0.0);
159  Vector3 expectedDeltaP2(0.025 + expectedDeltaP1(0) + 0.5 * 0.1 * 0.5 * 0.5, 0, 0);
160  Vector3 expectedDeltaV2 = Vector3(0.05, 0.0, 0.0) +
161  Rot3::Expmap(expectedDeltaR1) * measuredAcc * 0.5;
162 
163  // Actual pre-integrated values
164  actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
165  EXPECT(assert_equal(Rot3::Expmap(expectedDeltaR2), actual.deltaRij()));
166  EXPECT(assert_equal(expectedDeltaP2, actual.deltaPij()));
167  EXPECT(assert_equal(expectedDeltaV2, actual.deltaVij()));
168  DOUBLES_EQUAL(1.0, actual.deltaTij(), 1e-9);
169 }
170 /* ************************************************************************* */
171 // Common linearization point and measurements for tests
172 namespace common {
173 static const Pose3 x1(Rot3::RzRyRx(M_PI / 12.0, M_PI / 6.0, M_PI / 4.0),
174  Point3(5.0, 1.0, 0));
175 static const Vector3 v1(Vector3(0.5, 0.0, 0.0));
176 static const NavState state1(x1, v1);
177 
178 // Measurements
179 static const double w = M_PI / 100;
180 static const Vector3 measuredOmega(w, 0, 0);
181 static const Vector3 measuredAcc = x1.rotation().unrotate(
183 static const double deltaT = 1.0;
184 
185 static const Pose3 x2(Rot3::RzRyRx(M_PI / 12.0 + w, M_PI / 6.0, M_PI / 4.0),
186  Point3(5.5, 1.0, 0));
187 static const Vector3 v2(Vector3(0.5, 0.0, 0.0));
188 static const NavState state2(x2, v2);
189 } // namespace common
190 
191 /* ************************************************************************* */
192 TEST(ImuFactor, PreintegrationBaseMethods) {
193  using namespace common;
194  auto p = testing::Params();
195  p->omegaCoriolis = Vector3(0.02, 0.03, 0.04);
196  p->use2ndOrderCoriolis = true;
197 
199  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
200  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
201 
202  // biasCorrectedDelta
203  Matrix96 actualH;
204  pim.biasCorrectedDelta(kZeroBias, actualH);
205  Matrix expectedH = numericalDerivative11<Vector9, Bias>(
206  boost::bind(&PreintegrationBase::biasCorrectedDelta, pim, _1,
207  boost::none), kZeroBias);
208  EXPECT(assert_equal(expectedH, actualH));
209 
210  Matrix9 aH1;
211  Matrix96 aH2;
212  NavState predictedState = pim.predict(state1, kZeroBias, aH1, aH2);
213  Matrix eH1 = numericalDerivative11<NavState, NavState>(
214  boost::bind(&PreintegrationBase::predict, pim, _1, kZeroBias, boost::none,
215  boost::none), state1);
216  EXPECT(assert_equal(eH1, aH1));
217  Matrix eH2 = numericalDerivative11<NavState, Bias>(
218  boost::bind(&PreintegrationBase::predict, pim, state1, _1, boost::none,
219  boost::none), kZeroBias);
220  EXPECT(assert_equal(eH2, aH2));
221 }
222 
223 /* ************************************************************************* */
224 TEST(ImuFactor, MultipleMeasurements) {
225  using namespace common;
226 
228  expected.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
229  expected.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
230 
231  Matrix32 acc,gyro;
232  Matrix12 dts;
233  acc << measuredAcc, measuredAcc;
234  gyro << measuredOmega, measuredOmega;
235  dts << deltaT, deltaT;
237  actual.integrateMeasurements(acc,gyro,dts);
238 
239  EXPECT(assert_equal(expected,actual));
240 }
241 
242 /* ************************************************************************* */
243 TEST(ImuFactor, ErrorAndJacobians) {
244  using namespace common;
246 
247  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
248  EXPECT(assert_equal(state2, pim.predict(state1, kZeroBias)));
249 
250  // Create factor
251  ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim);
252 
253  // Expected error
254  Vector expectedError(9);
255  expectedError << 0, 0, 0, 0, 0, 0, 0, 0, 0;
256  EXPECT(
257  assert_equal(expectedError,
258  factor.evaluateError(x1, v1, x2, v2, kZeroBias)));
259 
260  Values values;
261  values.insert(X(1), x1);
262  values.insert(V(1), v1);
263  values.insert(X(2), x2);
264  values.insert(V(2), v2);
265  values.insert(B(1), kZeroBias);
266  EXPECT(assert_equal(expectedError, factor.unwhitenedError(values)));
267 
268  // Make sure linearization is correct
269  double diffDelta = 1e-7;
270  EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3);
271 
272  // Actual Jacobians
273  Matrix H1a, H2a, H3a, H4a, H5a;
274  (void) factor.evaluateError(x1, v1, x2, v2, kZeroBias, H1a, H2a, H3a, H4a,
275  H5a);
276 
277  // Make sure rotation part is correct when error is interpreted as axis-angle
278  // Jacobians are around zero, so the rotation part is the same as:
279  Matrix H1Rot3 = numericalDerivative11<Rot3, Pose3>(
280  boost::bind(&evaluateRotationError, factor, _1, v1, x2, v2, kZeroBias),
281  x1);
282  EXPECT(assert_equal(H1Rot3, H1a.topRows(3)));
283 
284  Matrix H3Rot3 = numericalDerivative11<Rot3, Pose3>(
285  boost::bind(&evaluateRotationError, factor, x1, v1, _1, v2, kZeroBias),
286  x2);
287  EXPECT(assert_equal(H3Rot3, H3a.topRows(3)));
288 
289  // Evaluate error with wrong values
290  Vector3 v2_wrong = v2 + Vector3(0.1, 0.1, 0.1);
291  values.update(V(2), v2_wrong);
292  expectedError << 0, 0, 0, 0, 0, 0, -0.0724744871, -0.040715657, -0.151952901;
293  EXPECT(
294  assert_equal(expectedError,
295  factor.evaluateError(x1, v1, x2, v2_wrong, kZeroBias), 1e-2));
296  EXPECT(assert_equal(expectedError, factor.unwhitenedError(values), 1e-2));
297 
298  // Make sure the whitening is done correctly
299  Matrix cov = pim.preintMeasCov();
300  Matrix R = RtR(cov.inverse());
301  Vector whitened = R * expectedError;
302  EXPECT(assert_equal(0.5 * whitened.squaredNorm(), factor.error(values), 1e-4));
303 
304  // Make sure linearization is correct
305  EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3);
306 }
307 
308 /* ************************************************************************* */
309 TEST(ImuFactor, ErrorAndJacobianWithBiases) {
310  using common::x1;
311  using common::v1;
312  using common::v2;
313  Bias bias(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); // Biases (acc, rot)
314  Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 10.0 + M_PI / 10.0)),
315  Point3(5.5, 1.0, -50.0));
316 
317  // Measurements
319  measuredOmega << 0, 0, M_PI / 10.0 + 0.3;
320  Vector3 measuredAcc = x1.rotation().unrotate(-kGravityAlongNavZDown)
321  + Vector3(0.2, 0.0, 0.0);
322  double deltaT = 1.0;
323 
324  auto p = testing::Params();
325  p->omegaCoriolis = kNonZeroOmegaCoriolis;
326 
327  Bias biasHat(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.1));
328  PreintegratedImuMeasurements pim(p, biasHat);
329  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
330 
331  // Make sure of biasCorrectedDelta
332  Matrix96 actualH;
333  pim.biasCorrectedDelta(bias, actualH);
334  Matrix expectedH = numericalDerivative11<Vector9, Bias>(
335  boost::bind(&PreintegrationBase::biasCorrectedDelta, pim, _1,
336  boost::none), bias);
337  EXPECT(assert_equal(expectedH, actualH));
338 
339  // Create factor
340  ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim);
341 
342  Values values;
343  values.insert(X(1), x1);
344  values.insert(V(1), v1);
345  values.insert(X(2), x2);
346  values.insert(V(2), v2);
347  values.insert(B(1), bias);
348 
349  // Make sure linearization is correct
350  double diffDelta = 1e-7;
351  EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3);
352 }
353 
354 /* ************************************************************************* */
355 TEST(ImuFactor, ErrorAndJacobianWith2ndOrderCoriolis) {
356  using common::x1;
357  using common::v1;
358  using common::v2;
359  Bias bias(Vector3(0.2, 0, 0), Vector3(0.1, 0, 0.3)); // Biases (acc, rot)
360  Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 10.0 + M_PI / 10.0)),
361  Point3(5.5, 1.0, -50.0));
362 
363  // Measurements
365  measuredOmega << 0, 0, M_PI / 10.0 + 0.3;
366  Vector3 measuredAcc = x1.rotation().unrotate(-kGravityAlongNavZDown)
367  + Vector3(0.2, 0.0, 0.0);
368  double deltaT = 1.0;
369 
370  auto p = testing::Params();
371  p->omegaCoriolis = kNonZeroOmegaCoriolis;
372  p->use2ndOrderCoriolis = true;
373 
375  Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.1)));
376  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
377 
378  // Create factor
379  ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim);
380 
381  Values values;
382  values.insert(X(1), x1);
383  values.insert(V(1), v1);
384  values.insert(X(2), x2);
385  values.insert(V(2), v2);
386  values.insert(B(1), bias);
387 
388  // Make sure linearization is correct
389  double diffDelta = 1e-7;
390  EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3);
391 }
392 
393 /* ************************************************************************* */
394 TEST(ImuFactor, PartialDerivative_wrt_Bias) {
395  // Linearization point
396  Vector3 biasOmega(0, 0, 0); // Current estimate of rotation rate bias
397 
398  // Measurements
399  Vector3 measuredOmega(0.1, 0, 0);
400  double deltaT = 0.5;
401 
402  auto evaluateRotation = [=](const Vector3 biasOmega) {
403  return Rot3::Expmap((measuredOmega - biasOmega) * deltaT);
404  };
405 
406  // Compute numerical derivatives
407  Matrix expectedDelRdelBiasOmega =
408  numericalDerivative11<Rot3, Vector3>(evaluateRotation, biasOmega);
409 
410  const Matrix3 Jr =
411  Rot3::ExpmapDerivative((measuredOmega - biasOmega) * deltaT);
412 
413  Matrix3 actualdelRdelBiasOmega = -Jr * deltaT; // the delta bias appears with the minus sign
414 
415  // Compare Jacobians
416  EXPECT(assert_equal(expectedDelRdelBiasOmega, actualdelRdelBiasOmega, 1e-9));
417 }
418 
419 /* ************************************************************************* */
420 TEST(ImuFactor, PartialDerivativeLogmap) {
421  // Linearization point
422  Vector3 thetahat(0.1, 0.1, 0); // Current estimate of rotation rate bias
423 
424  // Measurements
425  Vector3 deltatheta(0, 0, 0);
426 
427  auto evaluateLogRotation = [=](const Vector3 deltatheta) {
428  return Rot3::Logmap(
429  Rot3::Expmap(thetahat).compose(Rot3::Expmap(deltatheta)));
430  };
431 
432  // Compute numerical derivatives
433  Matrix expectedDelFdeltheta =
434  numericalDerivative11<Vector, Vector3>(evaluateLogRotation, deltatheta);
435 
436  Matrix3 actualDelFdeltheta = Rot3::LogmapDerivative(thetahat);
437 
438  // Compare Jacobians
439  EXPECT(assert_equal(expectedDelFdeltheta, actualDelFdeltheta));
440 }
441 
442 /* ************************************************************************* */
443 TEST(ImuFactor, fistOrderExponential) {
444  // Linearization point
445  Vector3 biasOmega(0, 0, 0); // Current estimate of rotation rate bias
446 
447  // Measurements
448  Vector3 measuredOmega(0.1, 0, 0);
449  double deltaT = 1.0;
450 
451  // change w.r.t. linearization point
452  double alpha = 0.0;
453  Vector3 deltabiasOmega;
454  deltabiasOmega << alpha, alpha, alpha;
455 
456  const Matrix3 Jr = Rot3::ExpmapDerivative(
457  (measuredOmega - biasOmega) * deltaT);
458 
459  Matrix3 delRdelBiasOmega = -Jr * deltaT; // the delta bias appears with the minus sign
460 
461  const Matrix expectedRot = Rot3::Expmap(
462  (measuredOmega - biasOmega - deltabiasOmega) * deltaT).matrix();
463 
464  const Matrix3 hatRot =
465  Rot3::Expmap((measuredOmega - biasOmega) * deltaT).matrix();
466  const Matrix3 actualRot = hatRot
467  * Rot3::Expmap(delRdelBiasOmega * deltabiasOmega).matrix();
468  // hatRot * (I_3x3 + skewSymmetric(delRdelBiasOmega * deltabiasOmega));
469 
470  // This is a first order expansion so the equality is only an approximation
471  EXPECT(assert_equal(expectedRot, actualRot));
472 }
473 
474 /* ************************************************************************* */
476  const Vector3& measuredAcc, const Vector3& measuredOmega) {
477  Vector3 correctedAcc = pim.biasHat().correctAccelerometer(measuredAcc);
478  Vector3 correctedOmega = pim.biasHat().correctGyroscope(measuredOmega);
479  return pim.correctMeasurementsBySensorPose(correctedAcc, correctedOmega).first;
480 }
481 
482 TEST(ImuFactor, ErrorWithBiasesAndSensorBodyDisplacement) {
483  const Rot3 nRb = Rot3::Expmap(Vector3(0, 0, M_PI / 4.0));
484  const Point3 p1(5.0, 1.0, -50.0);
485  const Vector3 v1(0.5, 0.0, 0.0);
486 
487  const Vector3 a = nRb * Vector3(0.2, 0.0, 0.0);
488  const AcceleratingScenario scenario(nRb, p1, v1, a,
489  Vector3(0, 0, M_PI / 10.0 + 0.3));
490 
491  auto p = testing::Params();
492  p->body_P_sensor = Pose3(Rot3::Expmap(Vector3(0, M_PI / 2, 0)),
493  Point3(0.1, 0.05, 0.01));
494  p->omegaCoriolis = kNonZeroOmegaCoriolis;
495 
496  Bias biasHat(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0));
497 
498  const double T = 3.0; // seconds
499  ScenarioRunner runner(scenario, p, T / 10);
500 
501  // PreintegratedImuMeasurements pim = runner.integrate(T);
502  // EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 1e-9));
503  //
504  // Matrix6 estimatedCov = runner.estimatePoseCovariance(T);
505  // EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 0.1));
506  //
508  Pose3 x1(nRb, p1);
509 
510  // Measurements
511  Vector3 measuredOmega = runner.actualAngularVelocity(0);
512  Vector3 measuredAcc = runner.actualSpecificForce(0);
513 
514  // Get mean prediction from "ground truth" measurements
515  const Vector3 accNoiseVar2(0.01, 0.02, 0.03);
516  const Vector3 omegaNoiseVar2(0.03, 0.01, 0.02);
517  PreintegratedImuMeasurements pim(p, biasHat);
518 
519  // Check updatedDeltaXij derivatives
520  Matrix3 D_correctedAcc_measuredOmega = Z_3x3;
521  pim.correctMeasurementsBySensorPose(measuredAcc, measuredOmega,
522  boost::none, D_correctedAcc_measuredOmega, boost::none);
523  Matrix3 expectedD = numericalDerivative11<Vector3, Vector3>(
524  boost::bind(correctedAcc, pim, measuredAcc, _1), measuredOmega, 1e-6);
525  EXPECT(assert_equal(expectedD, D_correctedAcc_measuredOmega, 1e-5));
526 
527  double dt = 0.1;
528 
529 // TODO(frank): revive derivative tests
530 // Matrix93 G1, G2;
531 // Vector9 preint =
532 // pim.updatedDeltaXij(measuredAcc, measuredOmega, dt, boost::none, G1, G2);
533 //
534 // Matrix93 expectedG1 = numericalDerivative21<NavState, Vector3, Vector3>(
535 // boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, _1, _2,
536 // dt, boost::none, boost::none, boost::none), measuredAcc,
537 // measuredOmega, 1e-6);
538 // EXPECT(assert_equal(expectedG1, G1, 1e-5));
539 //
540 // Matrix93 expectedG2 = numericalDerivative22<NavState, Vector3, Vector3>(
541 // boost::bind(&PreintegratedImuMeasurements::updatedDeltaXij, pim, _1, _2,
542 // dt, boost::none, boost::none, boost::none), measuredAcc,
543 // measuredOmega, 1e-6);
544 // EXPECT(assert_equal(expectedG2, G2, 1e-5));
545 
546  Bias bias(Vector3(0.2, 0, 0), Vector3(0, 0, 0.3)); // Biases (acc, rot)
547 
548  // integrate at least twice to get position information
549  // otherwise factor cov noise from preint_cov is not positive definite
550  pim.integrateMeasurement(measuredAcc, measuredOmega, dt);
551  pim.integrateMeasurement(measuredAcc, measuredOmega, dt);
552 
553  // Create factor
554  ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim);
555 
556  Pose3 x2(Rot3::Expmap(Vector3(0, 0, M_PI / 4.0 + M_PI / 10.0)),
557  Point3(5.5, 1.0, -50.0));
558  Vector3 v2(Vector3(0.5, 0.0, 0.0));
559 
560  Values values;
561  values.insert(X(1), x1);
562  values.insert(V(1), v1);
563  values.insert(X(2), x2);
564  values.insert(V(2), v2);
565  values.insert(B(1), bias);
566 
567  // Make sure linearization is correct
568  double diffDelta = 1e-8;
569  EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, diffDelta, 1e-3);
570 }
571 
572 /* ************************************************************************* */
573 TEST(ImuFactor, PredictPositionAndVelocity) {
574  gttic(PredictPositionAndVelocity);
575  Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot)
576 
577  // Measurements
579  measuredOmega << 0, 0, 0; // M_PI/10.0+0.3;
581  measuredAcc << 0, 1, -kGravity;
582  double deltaT = 0.001;
583 
585  Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)));
586 
587  for (int i = 0; i < 1000; ++i)
588  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
589 
590  // Create factor
591  ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim);
592 
593  // Predict
594  Pose3 x1;
595  Vector3 v1(0, 0.0, 0.0);
596  NavState actual = pim.predict(NavState(x1, v1), bias);
597  NavState expected(Rot3(), Point3(0, 0.5, 0), Vector3(0, 1, 0));
598  EXPECT(assert_equal(expected, actual));
599 }
600 
601 /* ************************************************************************* */
602 TEST(ImuFactor, PredictRotation) {
603  gttic(PredictRotation);
604  Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0)); // Biases (acc, rot)
605 
606  // Measurements
608  measuredOmega << 0, 0, M_PI / 10; // M_PI/10.0+0.3;
610  measuredAcc << 0, 0, -kGravity;
611  double deltaT = 0.001;
612 
614  Bias(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0)));
615 
616  for (int i = 0; i < 1000; ++i)
617  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
618 
619  // Create factor
620  ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim);
621 
622  // Predict
623  NavState actual = pim.predict(NavState(), bias);
624  NavState expected(Rot3::Ypr(M_PI / 10, 0, 0), Point3(0,0,0), Z_3x1);
625  EXPECT(assert_equal(expected, actual));
626 }
627 
628 /* ************************************************************************* */
629 TEST(ImuFactor, PredictArbitrary) {
630  gttic(PredictArbitrary);
631  Pose3 x1;
632  const Vector3 v1(0, 0, 0);
633 
635  Vector3(0.1, 0.2, 0), Vector3(M_PI / 10, M_PI / 10, M_PI / 10));
636 
637  const double T = 3.0; // seconds
638  ScenarioRunner runner(scenario, testing::Params(), T / 10);
639  //
640  // PreintegratedImuMeasurements pim = runner.integrate(T);
641  // EXPECT(assert_equal(scenario.pose(T), runner.predict(pim).pose, 1e-9));
642  //
643  // Matrix6 estimatedCov = runner.estimatePoseCovariance(T);
644  // EXPECT(assert_equal(estimatedCov, runner.poseCovariance(pim), 0.1));
646 
647  Bias biasHat(Vector3(0.2, 0.0, 0.0), Vector3(0.0, 0.0, 0.0));
648 
649  // Measurements
651  Vector3 measuredAcc = runner.actualSpecificForce(0);
652 
653  auto p = testing::Params();
654  p->integrationCovariance = Z_3x3; // MonteCarlo does not sample integration noise
655  PreintegratedImuMeasurements pim(p, biasHat);
656  Bias bias(Vector3(0, 0, 0), Vector3(0, 0, 0));
657 // EXPECT(MonteCarlo(pim, NavState(x1, v1), bias, 0.1, boost::none, measuredAcc, measuredOmega,
658 // Vector3::Constant(accNoiseVar), Vector3::Constant(omegaNoiseVar), 100000));
659 
660  double dt = 0.001;
661  for (int i = 0; i < 1000; ++i)
662  pim.integrateMeasurement(measuredAcc, measuredOmega, dt);
663 
664  // Create factor
665  ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim);
666 
667  // Predict
668  NavState actual = pim.predict(NavState(x1, v1), bias);
669 
670  // Regression test for Imu Refactor
671  Rot3 expectedR( //
672  +0.903715275, -0.250741668, 0.347026393, //
673  +0.347026393, 0.903715275, -0.250741668, //
674  -0.250741668, 0.347026393, 0.903715275);
675  Point3 expectedT(-0.516077031, 0.57842919, 0.0876478403);
676  Vector3 expectedV(-1.62337767, 1.57954409, 0.343833571);
677  NavState expected(expectedR, expectedT, expectedV);
678  EXPECT(assert_equal(expected, actual, 1e-7));
679 }
680 
681 /* ************************************************************************* */
682 TEST(ImuFactor, bodyPSensorNoBias) {
683  gttic(bodyPSensorNoBias);
684  Bias bias(Vector3(0, 0, 0), Vector3(0, 0.1, 0)); // Biases (acc, rot)
685 
686  // Rotate sensor (z-down) to body (same as navigation) i.e. z-up
687  auto p = testing::Params();
688  p->n_gravity = Vector3(0, 0, -kGravity); // z-up nav frame
689  p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3(0, 0, 0));
690 
691  // Measurements
692  // Gyroscope measurement is the angular velocity of sensor w.r.t nav frame in sensor frame
693  Vector3 s_omegaMeas_ns(0, 0.1, M_PI / 10);
694  // Acc measurement is acceleration of sensor in the sensor frame, when stationary,
695  // table exerts an equal and opposite force w.r.t gravity
696  Vector3 s_accMeas(0, 0, -kGravity);
697  double dt = 0.001;
698 
699  PreintegratedImuMeasurements pim(p, bias);
700 
701  for (int i = 0; i < 1000; ++i)
702  pim.integrateMeasurement(s_accMeas, s_omegaMeas_ns, dt);
703 
704  // Create factor
705  ImuFactor factor(X(1), V(1), X(2), V(2), B(1), pim);
706 
707  // Predict
708  NavState actual = pim.predict(NavState(), bias);
709 
710  Pose3 expectedPose(Rot3::Ypr(-M_PI / 10, 0, 0), Point3(0, 0, 0));
711  EXPECT(assert_equal(expectedPose, actual.pose()));
712 
713  Vector3 expectedVelocity(0, 0, 0);
714  EXPECT(assert_equal(Vector(expectedVelocity), Vector(actual.velocity())));
715 }
716 
717 /* ************************************************************************* */
722 
723 TEST(ImuFactor, bodyPSensorWithBias) {
724  gttic(bodyPSensorWithBias);
725  using noiseModel::Diagonal;
726  typedef Bias Bias;
727 
728  int numFactors = 10;
729  Vector6 noiseBetweenBiasSigma;
730  noiseBetweenBiasSigma << Vector3(2.0e-5, 2.0e-5, 2.0e-5), Vector3(3.0e-6,
731  3.0e-6, 3.0e-6);
732  SharedDiagonal biasNoiseModel = Diagonal::Sigmas(noiseBetweenBiasSigma);
733 
734  // Measurements
735  // Sensor frame is z-down
736  // Gyroscope measurement is the angular velocity of sensor w.r.t nav frame in sensor frame
737  Vector3 measuredOmega(0, 0.01, 0);
738  // Acc measurement is acceleration of sensor in the sensor frame, when stationary,
739  // table exerts an equal and opposite force w.r.t gravity
740  Vector3 measuredAcc(0, 0, -kGravity);
741 
742  auto p = testing::Params();
743  p->n_gravity = Vector3(0, 0, -kGravity);
744  p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3(0,0,0));
745  p->accelerometerCovariance = 1e-7 * I_3x3;
746  p->gyroscopeCovariance = 1e-8 * I_3x3;
747  p->integrationCovariance = 1e-9 * I_3x3;
748  double deltaT = 0.005;
749 
750  // Specify noise values on priors
751  Vector6 priorNoisePoseSigmas(
752  (Vector(6) << 0.001, 0.001, 0.001, 0.01, 0.01, 0.01).finished());
753  Vector3 priorNoiseVelSigmas((Vector(3) << 0.1, 0.1, 0.1).finished());
754  Vector6 priorNoiseBiasSigmas(
755  (Vector(6) << 0.1, 0.1, 0.1, 0.5e-1, 0.5e-1, 0.5e-1).finished());
756  SharedDiagonal priorNoisePose = Diagonal::Sigmas(priorNoisePoseSigmas);
757  SharedDiagonal priorNoiseVel = Diagonal::Sigmas(priorNoiseVelSigmas);
758  SharedDiagonal priorNoiseBias = Diagonal::Sigmas(priorNoiseBiasSigmas);
759  Vector3 zeroVel(0, 0, 0);
760 
761  // Create a factor graph with priors on initial pose, vlocity and bias
763  Values values;
764 
765  graph.addPrior(X(0), Pose3(), priorNoisePose);
766  values.insert(X(0), Pose3());
767 
768  graph.addPrior(V(0), zeroVel, priorNoiseVel);
769  values.insert(V(0), zeroVel);
770 
771  // The key to this test is that we specify the bias, in the sensor frame, as known a priori
772  // We also create factors below that encode our assumption that this bias is constant over time
773  // In theory, after optimization, we should recover that same bias estimate
774  Bias priorBias(Vector3(0, 0, 0), Vector3(0, 0.01, 0)); // Biases (acc, rot)
775  graph.addPrior(B(0), priorBias, priorNoiseBias);
776  values.insert(B(0), priorBias);
777 
778  // Now add IMU factors and bias noise models
779  Bias zeroBias(Vector3(0, 0, 0), Vector3(0, 0, 0));
780  for (int i = 1; i < numFactors; i++) {
782  priorBias);
783  for (int j = 0; j < 200; ++j)
784  pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
785 
786  // Create factors
787  graph.emplace_shared<ImuFactor>(X(i - 1), V(i - 1), X(i), V(i), B(i - 1), pim);
788  graph.emplace_shared<BetweenFactor<Bias> >(B(i - 1), B(i), zeroBias, biasNoiseModel);
789 
790  values.insert(X(i), Pose3());
791  values.insert(V(i), zeroVel);
792  values.insert(B(i), priorBias);
793  }
794 
795  // Finally, optimize, and get bias at last time step
797  Bias biasActual = results.at<Bias>(B(numFactors - 1));
798 
799  // And compare it with expected value (our prior)
800  Bias biasExpected(Vector3(0, 0, 0), Vector3(0, 0.01, 0));
801  EXPECT(assert_equal(biasExpected, biasActual, 1e-3));
802 }
803 
804 /* ************************************************************************* */
805 #ifdef GTSAM_TANGENT_PREINTEGRATION
806 static const double kVelocity = 2.0, kAngularVelocity = M_PI / 6;
807 
808 struct ImuFactorMergeTest {
809  boost::shared_ptr<PreintegrationParams> p_;
810  const ConstantTwistScenario forward_, loop_;
811 
812  ImuFactorMergeTest()
813  : p_(PreintegrationParams::MakeSharedU(kGravity)),
814  forward_(kZero, Vector3(kVelocity, 0, 0)),
815  loop_(Vector3(0, -kAngularVelocity, 0), Vector3(kVelocity, 0, 0)) {
816  // arbitrary noise values
817  p_->gyroscopeCovariance = I_3x3 * 0.01;
818  p_->accelerometerCovariance = I_3x3 * 0.02;
819  p_->accelerometerCovariance = I_3x3 * 0.03;
820  }
821 
822  int TestScenario(TestResult& result_, const std::string& name_,
823  const Scenario& scenario,
824  const Bias& bias01,
825  const Bias& bias12, double tol) {
826  // Test merge by creating a 01, 12, and 02 PreintegratedRotation,
827  // then checking the merge of 01-12 matches 02.
828  PreintegratedImuMeasurements pim01(p_, bias01);
829  PreintegratedImuMeasurements pim12(p_, bias12);
830  PreintegratedImuMeasurements pim02_expected(p_, bias01);
831 
832  double deltaT = 0.01;
833  ScenarioRunner runner(scenario, p_, deltaT);
834  // TODO(frank) can this loop just go into runner ?
835  for (int i = 0; i < 100; i++) {
836  double t = i * deltaT;
837  // integrate the measurements appropriately
838  Vector3 accel_meas = runner.actualSpecificForce(t);
839  Vector3 omega_meas = runner.actualAngularVelocity(t);
840  pim02_expected.integrateMeasurement(accel_meas, omega_meas, deltaT);
841  if (i < 50) {
842  pim01.integrateMeasurement(accel_meas, omega_meas, deltaT);
843  } else {
844  pim12.integrateMeasurement(accel_meas, omega_meas, deltaT);
845  }
846  }
847  auto actual_pim02 = ImuFactor::Merge(pim01, pim12);
848  EXPECT(assert_equal(pim02_expected.preintegrated(),
849  actual_pim02.preintegrated(), tol));
850  EXPECT(assert_equal(pim02_expected, actual_pim02, tol));
851 
852  ImuFactor::shared_ptr factor01 =
853  boost::make_shared<ImuFactor>(X(0), V(0), X(1), V(1), B(0), pim01);
854  ImuFactor::shared_ptr factor12 =
855  boost::make_shared<ImuFactor>(X(1), V(1), X(2), V(2), B(0), pim12);
856  ImuFactor::shared_ptr factor02_expected = boost::make_shared<ImuFactor>(
857  X(0), V(0), X(2), V(2), B(0), pim02_expected);
858 
859  ImuFactor::shared_ptr factor02_merged = ImuFactor::Merge(factor01, factor12);
860  EXPECT(assert_equal(*factor02_expected, *factor02_merged, tol));
861  return result_.getFailureCount();
862  }
863 
864  void TestScenarios(TestResult& result_, const std::string& name_,
865  const Bias& bias01,
866  const Bias& bias12, double tol) {
867  for (auto scenario : {forward_, loop_})
868  TestScenario(result_, name_, scenario, bias01, bias12, tol);
869  }
870 };
871 
872 /* ************************************************************************* */
873 // Test case with zero biases
874 TEST(ImuFactor, MergeZeroBias) {
875  ImuFactorMergeTest mergeTest;
876  mergeTest.TestScenarios(result_, name_, kZeroBias, kZeroBias, 1e-4);
877 }
878 
879 // Test case with identical biases: we expect an exact answer.
880 TEST(ImuFactor, MergeConstantBias) {
881  ImuFactorMergeTest mergeTest;
882  Bias bias(Vector3(0.03, -0.02, 0.01), Vector3(-0.01, 0.02, -0.03));
883  mergeTest.TestScenarios(result_, name_, bias, bias, 1e-4);
884 }
885 
886 // Test case with different biases where we expect there to be some variation.
887 TEST(ImuFactor, MergeChangingBias) {
888  ImuFactorMergeTest mergeTest;
889  mergeTest.TestScenarios(result_, name_,
890  Bias(Vector3(0.03, -0.02, 0.01), Vector3(-0.01, 0.02, -0.03)),
891  Bias(Vector3(0.01, 0.02, 0.03), Vector3(0.03, -0.02, 0.01)), 1e-1);
892 }
893 
894 // Test case with non-zero coriolis
895 TEST(ImuFactor, MergeWithCoriolis) {
896  ImuFactorMergeTest mergeTest;
897  mergeTest.p_->omegaCoriolis = Vector3(0.1, 0.2, -0.1);
898  mergeTest.TestScenarios(result_, name_, kZeroBias, kZeroBias, 1e-4);
899 }
900 #endif
901 
902 /* ************************************************************************* */
903 // Same values as pre-integration test but now testing covariance
904 TEST(ImuFactor, CheckCovariance) {
905  gttic(CheckCovariance);
906  // Measurements
907  Vector3 measuredAcc(0.1, 0.0, 0.0);
908  Vector3 measuredOmega(M_PI / 100.0, 0.0, 0.0);
909  double deltaT = 0.5;
910 
912  actual.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
914  expected << 1.0577e-08, 0, 0, 0, 0, 0, 0, 0, 0, //
915  0, 1.0577e-08, 0, 0, 0, 0, 0, 0, 0, //
916  0, 0, 1.0577e-08, 0, 0, 0, 0, 0, 0, //
917  0, 0, 0, 5.00868e-05, 0, 0, 3.47222e-07, 0, 0, //
918  0, 0, 0, 0, 5.00868e-05, 0, 0, 3.47222e-07, 0, //
919  0, 0, 0, 0, 0, 5.00868e-05, 0, 0, 3.47222e-07, //
920  0, 0, 0, 3.47222e-07, 0, 0, 1.38889e-06, 0, 0, //
921  0, 0, 0, 0, 3.47222e-07, 0, 0, 1.38889e-06, 0, //
922  0, 0, 0, 0, 0, 3.47222e-07, 0, 0, 1.38889e-06;
923  EXPECT(assert_equal(expected, actual.preintMeasCov()));
924 }
925 
926 /* ************************************************************************* */
927 int main() {
928  TestResult tr;
930 #ifdef ENABLE_TIMING
931  tictoc_print_();
932 #endif
933  return result;
934 }
935 /* ************************************************************************* */
static const Bias kZeroBiasHat
const imuBias::ConstantBias & biasHat() const
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.
#define CHECK(condition)
Definition: Test.h:109
double error(const Values &c) const override
Vector3 correctedAcc(const PreintegratedImuMeasurements &pim, const Vector3 &measuredAcc, const Vector3 &measuredOmega)
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
void integrateMeasurements(const Matrix &measuredAccs, const Matrix &measuredOmegas, const Matrix &dts)
Add multiple measurements, in matrix columns.
Definition: ImuFactor.cpp:85
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:46
Vector3 actualSpecificForce(double t) const
virtual const Values & optimize()
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
A non-templated config holding any types of Manifold-group elements.
Vector3f p1
Vector9 biasCorrectedDelta(const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H=boost::none) const override
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Matrix expected
Definition: testMatrix.cpp:974
#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
Rot2 R(Rot2::fromAngle(0.1))
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
leaf::MyValues values
Pose2_ Expmap(const Vector3_ &xi)
static const Velocity3 kVelocity(0.4, 0.5, 0.6)
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.
static const Vector3 kGravityAlongNavZDown(0, 0, kGravity)
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)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
Evaluate derivatives of a nonlinear factor numerically.
static const Vector3 v2(Vector3(0.5, 0.0, 0.0))
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.
static const NavState state1(x1, v1)
NonlinearFactorGraph graph
Matrix< SCALARB, Dynamic, Dynamic > B
Definition: bench_gemm.cpp:36
PreintegratedImuMeasurements integrate(double T, const Bias &estimatedBias=Bias(), bool corrupted=false) const
Integrate measurements for T seconds into a PIM.
std::pair< Vector3, Vector3 > correctMeasurementsBySensorPose(const Vector3 &unbiasedAcc, const Vector3 &unbiasedOmega, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedAcc=boost::none, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedOmega=boost::none, OptionalJacobian< 3, 3 > correctedOmega_H_unbiasedOmega=boost::none) const
Matrix RtR(const Matrix &A)
Definition: Matrix.cpp:529
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
Point2 expectedT(-0.0446635, 0.29552)
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
static const Vector3 kNonZeroOmegaCoriolis(0, 0.1, 0.1)
const double dt
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
static const Bias kZeroBias
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)
#define gttic(label)
Definition: timing.h:280
static const Pose3 x2(Rot3::RzRyRx(M_PI/12.0+w, M_PI/6.0, M_PI/4.0), Point3(5.5, 1.0, 0))
Vector3 deltaPij() const override
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
static const double w
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
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
Vector3 deltaVij() const override
void resetIntegrationAndSetBias(const Bias &biasHat)
static const double kAccelSigma
static const NavState state2(x2, v2)
#define EXPECT(condition)
Definition: Test.h:151
Matrix preintMeasCov() const
Return pre-integrated measurement covariance.
Definition: ImuFactor.h:136
Vector3 correctAccelerometer(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Definition: ImuBias.h:69
boost::shared_ptr< ImuFactor > shared_ptr
Definition: ImuFactor.h:182
static const double deltaT
static const Vector3 kZero
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Matrix9 estimateCovariance(double T, size_t N=1000, const Bias &estimatedBias=Bias()) const
Compute a Monte Carlo estimate of the predict covariance using N samples.
RealScalar alpha
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
void tictoc_print_()
Definition: timing.h:253
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static boost::shared_ptr< PreintegratedCombinedMeasurements::Params > Params()
static const Vector3 measuredAcc
sampling from a NoiseModel
ConstantTwistScenario scenario(Z_3x1, Vector3(v, 0, 0))
Point3 bias(10,-10, 50)
Pose3 pose(double t) const override
pose at time t
Definition: Scenario.h:92
Simple trajectory simulator.
Definition: Scenario.h:25
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
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 Pose3 x1(Rot3::RzRyRx(M_PI/12.0, M_PI/6.0, M_PI/4.0), Point3(5.0, 1.0, 0))
Rot2 expectedR
Definition: testPose2.cpp:151
static const Vector3 measuredOmega(w, 0, 0)
Vector3 actualAngularVelocity(double t) const
static const Vector3 v1(Vector3(0.5, 0.0, 0.0))
imuBias::ConstantBias Bias
Simple class to test navigation scenarios.
std::map< std::string, Array< float, 1, 8, DontAlign|RowMajor > > results
#define EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, numerical_derivative_step, tolerance)
Check the Jacobians produced by a factor against finite differences.
float * p
int getFailureCount()
Definition: TestResult.h:35
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
Vector3 correctGyroscope(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Definition: ImuBias.h:78
void update(Key j, const Value &val)
Definition: Values.cpp:161
A class for computing marginals in a NonlinearFactorGraph.
static const double kGyroSigma
TEST(ImuFactor, PreintegratedMeasurementsConstruction)
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
int main()
Rot3 nRb
#define X
Definition: icosphere.cpp:20
3D Pose
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
void resetIntegration() override
Re-initialize PreintegratedIMUMeasurements.
Definition: ImuFactor.cpp:47
NavState predict(const PreintegratedImuMeasurements &pim, const Bias &estimatedBias=Bias()) const
Predict predict given a PIM.
Accelerating from an arbitrary initial state, with optional rotation.
Definition: Scenario.h:83
std::ptrdiff_t j
Point2 t(10, 10)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:47:15