Skip to content

Commit e47b4e5

Browse files
committed
Add a strong end-to-end test
1 parent ca50c82 commit e47b4e5

File tree

2 files changed

+113
-41
lines changed

2 files changed

+113
-41
lines changed

gtsam/navigation/tests/testAHRSFactor.cpp

+90-16
Original file line numberDiff line numberDiff line change
@@ -29,17 +29,20 @@
2929
#include <gtsam/nonlinear/Marginals.h>
3030
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
3131
#include <gtsam/nonlinear/factorTesting.h>
32+
#include <gtsam/slam/BetweenFactor.h>
3233

3334
#include <cmath>
3435
#include <list>
36+
#include <memory>
37+
#include "gtsam/nonlinear/LevenbergMarquardtParams.h"
3538

3639
using namespace std::placeholders;
3740
using namespace std;
3841
using namespace gtsam;
3942

4043
// Convenience for named keys
4144
using symbol_shorthand::B;
42-
using symbol_shorthand::X;
45+
using symbol_shorthand::R;
4346

4447
Vector3 kZeroOmegaCoriolis(0, 0, 0);
4548

@@ -136,7 +139,7 @@ TEST(AHRSFactor, Error) {
136139
pim.integrateMeasurement(measuredOmega, deltaT);
137140

138141
// Create factor
139-
AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis, {});
142+
AHRSFactor factor(R(1), R(2), B(1), pim, kZeroOmegaCoriolis, {});
140143

141144
// Check value
142145
Vector3 errorActual = factor.evaluateError(Ri, Rj, bias);
@@ -145,8 +148,8 @@ TEST(AHRSFactor, Error) {
145148

146149
// Check Derivatives
147150
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);
150153
values.insert(B(1), bias);
151154
EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-6);
152155
}
@@ -165,7 +168,7 @@ TEST(AHRSFactor, ErrorWithBiases) {
165168
pim.integrateMeasurement(measuredOmega, deltaT);
166169

167170
// Create factor
168-
AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis);
171+
AHRSFactor factor(R(1), R(2), B(1), pim, kZeroOmegaCoriolis);
169172

170173
// Check value
171174
Vector3 errorExpected(0, 0, 0);
@@ -174,8 +177,8 @@ TEST(AHRSFactor, ErrorWithBiases) {
174177

175178
// Check Derivatives
176179
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);
179182
values.insert(B(1), bias);
180183
EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-6);
181184
}
@@ -324,12 +327,12 @@ TEST(AHRSFactor, ErrorWithBiasesAndSensorBodyDisplacement) {
324327
EXPECT(assert_equal(kMeasuredOmegaCovariance, pim.preintMeasCov()));
325328

326329
// Create factor
327-
AHRSFactor factor(X(1), X(2), B(1), pim, omegaCoriolis);
330+
AHRSFactor factor(R(1), R(2), B(1), pim, omegaCoriolis);
328331

329332
// Check Derivatives
330333
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);
333336
values.insert(B(1), bias);
334337
EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-5, 1e-6);
335338
}
@@ -350,7 +353,7 @@ TEST(AHRSFactor, predictTest) {
350353
expectedMeasCov = 200 * kMeasuredOmegaCovariance;
351354
EXPECT(assert_equal(expectedMeasCov, pim.preintMeasCov()));
352355

353-
AHRSFactor factor(X(1), X(2), B(1), pim, kZeroOmegaCoriolis);
356+
AHRSFactor factor(R(1), R(2), B(1), pim, kZeroOmegaCoriolis);
354357

355358
// Predict
356359
Rot3 x;
@@ -368,7 +371,6 @@ TEST(AHRSFactor, predictTest) {
368371
EXPECT(assert_equal(expectedH, H, 1e-8));
369372
}
370373
//******************************************************************************
371-
372374
TEST(AHRSFactor, graphTest) {
373375
// linearization point
374376
Rot3 Ri(Rot3::RzRyRx(0, 0, 0));
@@ -393,15 +395,87 @@ TEST(AHRSFactor, graphTest) {
393395
}
394396

395397
// 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);
399401
values.insert(B(1), bias);
400402
graph.push_back(factor);
401403
LevenbergMarquardtOptimizer optimizer(graph, values);
402404
Values result = optimizer.optimize();
403405
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+
}
405479
}
406480

407481
//******************************************************************************

gtsam/navigation/tests/testImuFactor.cpp

+23-25
Original file line numberDiff line numberDiff line change
@@ -410,33 +410,33 @@ TEST(ImuFactor, PartialDerivative_wrt_Bias) {
410410
const Matrix3 Jr =
411411
Rot3::ExpmapDerivative((measuredOmega - biasOmega) * deltaT);
412412

413-
Matrix3 actualdelRdelBiasOmega = -Jr * deltaT; // the delta bias appears with the minus sign
413+
Matrix3 actualDelRdelBiasOmega = -Jr * deltaT; // the delta bias appears with the minus sign
414414

415415
// Compare Jacobians
416-
EXPECT(assert_equal(expectedDelRdelBiasOmega, actualdelRdelBiasOmega, 1e-9));
416+
EXPECT(assert_equal(expectedDelRdelBiasOmega, actualDelRdelBiasOmega, 1e-9));
417417
}
418418

419419
/* ************************************************************************* */
420420
TEST(ImuFactor, PartialDerivativeLogmap) {
421421
// Linearization point
422-
Vector3 thetahat(0.1, 0.1, 0); // Current estimate of rotation rate bias
422+
Vector3 thetaHat(0.1, 0.1, 0); // Current estimate of rotation rate bias
423423

424424
// Measurements
425-
Vector3 deltatheta(0, 0, 0);
425+
Vector3 deltaTheta(0, 0, 0);
426426

427-
auto evaluateLogRotation = [=](const Vector3 deltatheta) {
427+
auto evaluateLogRotation = [=](const Vector3 delta) {
428428
return Rot3::Logmap(
429-
Rot3::Expmap(thetahat).compose(Rot3::Expmap(deltatheta)));
429+
Rot3::Expmap(thetaHat).compose(Rot3::Expmap(delta)));
430430
};
431431

432432
// Compute numerical derivatives
433-
Matrix expectedDelFdeltheta =
434-
numericalDerivative11<Vector, Vector3>(evaluateLogRotation, deltatheta);
433+
Matrix expectedDelFdelTheta =
434+
numericalDerivative11<Vector, Vector3>(evaluateLogRotation, deltaTheta);
435435

436-
Matrix3 actualDelFdeltheta = Rot3::LogmapDerivative(thetahat);
436+
Matrix3 actualDelFdelTheta = Rot3::LogmapDerivative(thetaHat);
437437

438438
// Compare Jacobians
439-
EXPECT(assert_equal(expectedDelFdeltheta, actualDelFdeltheta));
439+
EXPECT(assert_equal(expectedDelFdelTheta, actualDelFdelTheta));
440440
}
441441

442442
/* ************************************************************************* */
@@ -450,22 +450,21 @@ TEST(ImuFactor, fistOrderExponential) {
450450

451451
// change w.r.t. linearization point
452452
double alpha = 0.0;
453-
Vector3 deltabiasOmega;
454-
deltabiasOmega << alpha, alpha, alpha;
453+
Vector3 deltaBiasOmega;
454+
deltaBiasOmega << alpha, alpha, alpha;
455455

456456
const Matrix3 Jr = Rot3::ExpmapDerivative(
457457
(measuredOmega - biasOmega) * deltaT);
458458

459459
Matrix3 delRdelBiasOmega = -Jr * deltaT; // the delta bias appears with the minus sign
460460

461461
const Matrix expectedRot = Rot3::Expmap(
462-
(measuredOmega - biasOmega - deltabiasOmega) * deltaT).matrix();
462+
(measuredOmega - biasOmega - deltaBiasOmega) * deltaT).matrix();
463463

464464
const Matrix3 hatRot =
465465
Rot3::Expmap((measuredOmega - biasOmega) * deltaT).matrix();
466466
const Matrix3 actualRot = hatRot
467-
* Rot3::Expmap(delRdelBiasOmega * deltabiasOmega).matrix();
468-
// hatRot * (I_3x3 + skewSymmetric(delRdelBiasOmega * deltabiasOmega));
467+
* Rot3::Expmap(delRdelBiasOmega * deltaBiasOmega).matrix();
469468

470469
// This is a first order expansion so the equality is only an approximation
471470
EXPECT(assert_equal(expectedRot, actualRot));
@@ -728,7 +727,7 @@ TEST(ImuFactor, bodyPSensorWithBias) {
728727
using noiseModel::Diagonal;
729728
typedef Bias Bias;
730729

731-
int numFactors = 10;
730+
int numPoses = 10;
732731
Vector6 noiseBetweenBiasSigma;
733732
noiseBetweenBiasSigma << Vector3(2.0e-5, 2.0e-5, 2.0e-5), Vector3(3.0e-6,
734733
3.0e-6, 3.0e-6);
@@ -761,7 +760,7 @@ TEST(ImuFactor, bodyPSensorWithBias) {
761760
SharedDiagonal priorNoiseBias = Diagonal::Sigmas(priorNoiseBiasSigmas);
762761
Vector3 zeroVel(0, 0, 0);
763762

764-
// Create a factor graph with priors on initial pose, vlocity and bias
763+
// Create a factor graph with priors on initial pose, velocity and bias
765764
NonlinearFactorGraph graph;
766765
Values values;
767766

@@ -780,9 +779,8 @@ TEST(ImuFactor, bodyPSensorWithBias) {
780779

781780
// Now add IMU factors and bias noise models
782781
Bias zeroBias(Vector3(0, 0, 0), Vector3(0, 0, 0));
783-
for (int i = 1; i < numFactors; i++) {
784-
PreintegratedImuMeasurements pim = PreintegratedImuMeasurements(p,
785-
priorBias);
782+
for (int i = 1; i < numPoses; i++) {
783+
PreintegratedImuMeasurements pim(p, priorBias);
786784
for (int j = 0; j < 200; ++j)
787785
pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT);
788786

@@ -796,8 +794,8 @@ TEST(ImuFactor, bodyPSensorWithBias) {
796794
}
797795

798796
// Finally, optimize, and get bias at last time step
799-
Values results = LevenbergMarquardtOptimizer(graph, values).optimize();
800-
Bias biasActual = results.at<Bias>(B(numFactors - 1));
797+
Values result = LevenbergMarquardtOptimizer(graph, values).optimize();
798+
Bias biasActual = result.at<Bias>(B(numPoses - 1));
801799

802800
// And compare it with expected value (our prior)
803801
Bias biasExpected(Vector3(0, 0, 0), Vector3(0, 0.01, 0));
@@ -851,11 +849,11 @@ struct ImuFactorMergeTest {
851849
actual_pim02.preintegrated(), tol));
852850
EXPECT(assert_equal(pim02_expected, actual_pim02, tol));
853851

854-
ImuFactor::shared_ptr factor01 =
852+
auto factor01 =
855853
std::make_shared<ImuFactor>(X(0), V(0), X(1), V(1), B(0), pim01);
856-
ImuFactor::shared_ptr factor12 =
854+
auto factor12 =
857855
std::make_shared<ImuFactor>(X(1), V(1), X(2), V(2), B(0), pim12);
858-
ImuFactor::shared_ptr factor02_expected = std::make_shared<ImuFactor>(
856+
auto factor02_expected = std::make_shared<ImuFactor>(
859857
X(0), V(0), X(2), V(2), B(0), pim02_expected);
860858

861859
ImuFactor::shared_ptr factor02_merged = ImuFactor::Merge(factor01, factor12);

0 commit comments

Comments
 (0)