29
29
#include < gtsam/nonlinear/Marginals.h>
30
30
#include < gtsam/nonlinear/NonlinearFactorGraph.h>
31
31
#include < gtsam/nonlinear/factorTesting.h>
32
+ #include < gtsam/slam/BetweenFactor.h>
32
33
33
34
#include < cmath>
34
35
#include < list>
36
+ #include < memory>
37
+ #include " gtsam/nonlinear/LevenbergMarquardtParams.h"
35
38
36
39
using namespace std ::placeholders;
37
40
using namespace std ;
38
41
using namespace gtsam ;
39
42
40
43
// Convenience for named keys
41
44
using symbol_shorthand::B;
42
- using symbol_shorthand::X ;
45
+ using symbol_shorthand::R ;
43
46
44
47
Vector3 kZeroOmegaCoriolis (0 , 0 , 0 );
45
48
@@ -136,7 +139,7 @@ TEST(AHRSFactor, Error) {
136
139
pim.integrateMeasurement (measuredOmega, deltaT);
137
140
138
141
// Create factor
139
- AHRSFactor factor (X (1 ), X (2 ), B (1 ), pim, kZeroOmegaCoriolis , {});
142
+ AHRSFactor factor (R (1 ), R (2 ), B (1 ), pim, kZeroOmegaCoriolis , {});
140
143
141
144
// Check value
142
145
Vector3 errorActual = factor.evaluateError (Ri, Rj, bias);
@@ -145,8 +148,8 @@ TEST(AHRSFactor, Error) {
145
148
146
149
// Check Derivatives
147
150
Values values;
148
- values.insert (X (1 ), Ri);
149
- values.insert (X (2 ), Rj);
151
+ values.insert (R (1 ), Ri);
152
+ values.insert (R (2 ), Rj);
150
153
values.insert (B (1 ), bias);
151
154
EXPECT_CORRECT_FACTOR_JACOBIANS (factor, values, 1e-5 , 1e-6 );
152
155
}
@@ -165,7 +168,7 @@ TEST(AHRSFactor, ErrorWithBiases) {
165
168
pim.integrateMeasurement (measuredOmega, deltaT);
166
169
167
170
// Create factor
168
- AHRSFactor factor (X (1 ), X (2 ), B (1 ), pim, kZeroOmegaCoriolis );
171
+ AHRSFactor factor (R (1 ), R (2 ), B (1 ), pim, kZeroOmegaCoriolis );
169
172
170
173
// Check value
171
174
Vector3 errorExpected (0 , 0 , 0 );
@@ -174,8 +177,8 @@ TEST(AHRSFactor, ErrorWithBiases) {
174
177
175
178
// Check Derivatives
176
179
Values values;
177
- values.insert (X (1 ), Ri);
178
- values.insert (X (2 ), Rj);
180
+ values.insert (R (1 ), Ri);
181
+ values.insert (R (2 ), Rj);
179
182
values.insert (B (1 ), bias);
180
183
EXPECT_CORRECT_FACTOR_JACOBIANS (factor, values, 1e-5 , 1e-6 );
181
184
}
@@ -324,12 +327,12 @@ TEST(AHRSFactor, ErrorWithBiasesAndSensorBodyDisplacement) {
324
327
EXPECT (assert_equal (kMeasuredOmegaCovariance , pim.preintMeasCov ()));
325
328
326
329
// Create factor
327
- AHRSFactor factor (X (1 ), X (2 ), B (1 ), pim, omegaCoriolis);
330
+ AHRSFactor factor (R (1 ), R (2 ), B (1 ), pim, omegaCoriolis);
328
331
329
332
// Check Derivatives
330
333
Values values;
331
- values.insert (X (1 ), Ri);
332
- values.insert (X (2 ), Rj);
334
+ values.insert (R (1 ), Ri);
335
+ values.insert (R (2 ), Rj);
333
336
values.insert (B (1 ), bias);
334
337
EXPECT_CORRECT_FACTOR_JACOBIANS (factor, values, 1e-5 , 1e-6 );
335
338
}
@@ -350,7 +353,7 @@ TEST(AHRSFactor, predictTest) {
350
353
expectedMeasCov = 200 * kMeasuredOmegaCovariance ;
351
354
EXPECT (assert_equal (expectedMeasCov, pim.preintMeasCov ()));
352
355
353
- AHRSFactor factor (X (1 ), X (2 ), B (1 ), pim, kZeroOmegaCoriolis );
356
+ AHRSFactor factor (R (1 ), R (2 ), B (1 ), pim, kZeroOmegaCoriolis );
354
357
355
358
// Predict
356
359
Rot3 x;
@@ -368,7 +371,6 @@ TEST(AHRSFactor, predictTest) {
368
371
EXPECT (assert_equal (expectedH, H, 1e-8 ));
369
372
}
370
373
// ******************************************************************************
371
-
372
374
TEST (AHRSFactor, graphTest) {
373
375
// linearization point
374
376
Rot3 Ri (Rot3::RzRyRx (0 , 0 , 0 ));
@@ -393,15 +395,87 @@ TEST(AHRSFactor, graphTest) {
393
395
}
394
396
395
397
// pim.print("Pre integrated measurements");
396
- AHRSFactor factor (X (1 ), X (2 ), B (1 ), pim, kZeroOmegaCoriolis );
397
- values.insert (X (1 ), Ri);
398
- values.insert (X (2 ), Rj);
398
+ AHRSFactor factor (R (1 ), R (2 ), B (1 ), pim, kZeroOmegaCoriolis );
399
+ values.insert (R (1 ), Ri);
400
+ values.insert (R (2 ), Rj);
399
401
values.insert (B (1 ), bias);
400
402
graph.push_back (factor);
401
403
LevenbergMarquardtOptimizer optimizer (graph, values);
402
404
Values result = optimizer.optimize ();
403
405
Rot3 expectedRot (Rot3::RzRyRx (0 , M_PI / 4 , 0 ));
404
- EXPECT (assert_equal (expectedRot, result.at <Rot3>(X (2 ))));
406
+ EXPECT (assert_equal (expectedRot, result.at <Rot3>(R (2 ))));
407
+ }
408
+
409
+ /* ************************************************************************* */
410
+ TEST (AHRSFactor, bodyPSensorWithBias) {
411
+ using noiseModel::Diagonal;
412
+
413
+ int numRotations = 10 ;
414
+ const Vector3 noiseBetweenBiasSigma (3.0e-6 , 3.0e-6 , 3.0e-6 );
415
+ SharedDiagonal biasNoiseModel = Diagonal::Sigmas (noiseBetweenBiasSigma);
416
+
417
+ // Measurements in the sensor frame:
418
+ const double omega = 0.1 ;
419
+ const Vector3 realOmega (omega, 0 , 0 );
420
+ const Vector3 realBias (1 , 2 , 3 ); // large !
421
+ const Vector3 measuredOmega = realOmega + realBias;
422
+
423
+ auto p = std::make_shared<PreintegratedAhrsMeasurements::Params>();
424
+ p->body_P_sensor = Pose3 (Rot3::Yaw (M_PI_2), Point3 (0 , 0 , 0 ));
425
+ p->gyroscopeCovariance = 1e-8 * I_3x3;
426
+ double deltaT = 0.005 ;
427
+
428
+ // Specify noise values on priors
429
+ const Vector3 priorNoisePoseSigmas (0.001 , 0.001 , 0.001 );
430
+ const Vector3 priorNoiseBiasSigmas (0.5e-1 , 0.5e-1 , 0.5e-1 );
431
+ SharedDiagonal priorNoisePose = Diagonal::Sigmas (priorNoisePoseSigmas);
432
+ SharedDiagonal priorNoiseBias = Diagonal::Sigmas (priorNoiseBiasSigmas);
433
+
434
+ // Create a factor graph with priors on initial pose, velocity and bias
435
+ NonlinearFactorGraph graph;
436
+ Values values;
437
+
438
+ graph.addPrior (R (0 ), Rot3 (), priorNoisePose);
439
+ values.insert (R (0 ), Rot3 ());
440
+
441
+ // The key to this test is that we specify the bias, in the sensor frame, as
442
+ // known a priori. We also create factors below that encode our assumption
443
+ // that this bias is constant over time In theory, after optimization, we
444
+ // should recover that same bias estimate
445
+ graph.addPrior (B (0 ), realBias, priorNoiseBias);
446
+ values.insert (B (0 ), realBias);
447
+
448
+ // Now add IMU factors and bias noise models
449
+ const Vector3 zeroBias (0 , 0 , 0 );
450
+ for (int i = 1 ; i < numRotations; i++) {
451
+ PreintegratedAhrsMeasurements pim (p, realBias);
452
+ for (int j = 0 ; j < 200 ; ++j)
453
+ pim.integrateMeasurement (measuredOmega, deltaT);
454
+
455
+ // Create factors
456
+ graph.emplace_shared <AHRSFactor>(R (i - 1 ), R (i), B (i - 1 ), pim);
457
+ graph.emplace_shared <BetweenFactor<Vector3> >(B (i - 1 ), B (i), zeroBias,
458
+ biasNoiseModel);
459
+
460
+ values.insert (R (i), Rot3 ());
461
+ values.insert (B (i), realBias);
462
+ }
463
+
464
+ // Finally, optimize, and get bias at last time step
465
+ LevenbergMarquardtParams params;
466
+ // params.setVerbosityLM("SUMMARY");
467
+ Values result = LevenbergMarquardtOptimizer (graph, values, params).optimize ();
468
+ const Vector3 biasActual = result.at <Vector3>(B (numRotations - 1 ));
469
+
470
+ // Bias should be a self-fulfilling prophesy:
471
+ EXPECT (assert_equal (realBias, biasActual, 1e-3 ));
472
+
473
+ // Check that the successive rotations are all `omega` apart:
474
+ for (int i = 0 ; i < numRotations; i++) {
475
+ Rot3 expectedRot = Rot3::Pitch (omega * i);
476
+ Rot3 actualRot = result.at <Rot3>(R (i));
477
+ EXPECT (assert_equal (expectedRot, actualRot, 1e-3 ));
478
+ }
405
479
}
406
480
407
481
// ******************************************************************************
0 commit comments