30 using namespace gtsam;
31 using namespace noiseModel;
40 TEST(NoiseModel, constructors)
46 vector<Gaussian::shared_ptr>
m;
47 m.push_back(Gaussian::SqrtInformation(
R,
false));
49 m.push_back(Gaussian::Information(
kCovariance.inverse(),
false));
50 m.push_back(Diagonal::Sigmas(
kSigmas,
false));
53 m.push_back(Isotropic::Sigma(3,
kSigma,
false));
54 m.push_back(Isotropic::Variance(3,
kVariance,
false));
55 m.push_back(Isotropic::Precision(3,
prc,
false));
90 1.0, 0.0, 0.0, 1.0).finished());
96 m[0]->WhitenInPlace(
H);
112 g2 = Gaussian::SqrtInformation(I_3x3);
114 d2 = Diagonal::Sigmas(
Vector3(0.1, 0.2, 0.3));
116 i2 = Isotropic::Sigma(3, 0.7);
146 TEST(NoiseModel, ConstrainedConstructors )
153 actual = Constrained::All(
d);
160 actual = Constrained::All(
d,
m);
163 actual = Constrained::All(
d,
mu);
166 actual = Constrained::MixedSigmas(
mu,
sigmas);
169 actual = Constrained::MixedSigmas(
m,
sigmas);
174 TEST(NoiseModel, ConstrainedMixed )
177 infeasible =
Vector3(1.0, 1.0, 1.0);
183 DOUBLES_EQUAL(0.5 * (1000.0 + 0.25 + 0.25),
d->loss(
d->squaredMahalanobisDistance(infeasible)),1
e-9);
189 TEST(NoiseModel, ConstrainedAll )
192 infeasible =
Vector3(1.0, 1.0, 1.0);
199 DOUBLES_EQUAL(0.5 * 1000.0 * 3.0,
i->loss(
i->squaredMahalanobisDistance(infeasible)),1
e-9);
208 -1., 0., 1., 0., 0., 0., -0.2,
209 0., -1., 0., 1., 0., 0., 0.3,
210 1., 0., 0., 0., -1., 0., 0.2,
211 0., 1., 0., 0., 0., -1., -0.1).finished();
216 11.1803, 0.0, -2.23607, 0.0, -8.94427, 0.0, 2.23607,
217 0.0, 11.1803, 0.0, -2.23607, 0.0, -8.94427,-1.56525,
218 0.0, 0.0, 4.47214, 0.0, -4.47214, 0.0, 0.0,
219 0.0, 0.0, 0.0, 4.47214, 0.0, -4.47214, 0.894427).finished();
232 EXPECT(actual1->isUnit());
236 Vector expectedSigmas = (
Vector(4) << 0.0894427, 0.0894427, 0.223607, 0.223607).finished();
237 SharedDiagonal expectedModel = noiseModel::Diagonal::Sigmas(expectedSigmas);
239 1., 0., -0.2, 0., -0.8, 0., 0.2,
240 0., 1., 0.,-0.2, 0., -0.8,-0.14,
241 0., 0., 1., 0., -1., 0., 0.0,
242 0., 0., 0., 1., 0., -1., 0.2).finished();
252 TEST(NoiseModel, OverdeterminedQR) {
260 Vector9
sigmas = Vector9::Ones() ;
263 EXPECT(actual1->isUnit());
265 expectedRd << -2.64575131, -2.64575131, -2.64575131, -2.64575131,
272 Vector3 expectedSigmas(0.377964473, 1, 1);
273 SharedDiagonal expectedModel = noiseModel::Diagonal::Sigmas(expectedSigmas);
279 expectedRd.row(0) *= 0.377964473;
298 Vector mixed_sigmas = (
Vector(5) << 0, 1, 0, 1, 1).finished();
299 SharedDiagonal constrained = noiseModel::Constrained::MixedSigmas(mixed_sigmas);
302 Vector expectedSigmas = (
Vector(5) << 0, 1, 0, 1, 1).finished();
303 SharedDiagonal expectedModel = noiseModel::Diagonal::Sigmas(expectedSigmas);
304 Matrix expectedRd(5, 6+1);
305 expectedRd << 1, 0, 0, 0, 0, 1, 0,
342 Vector3 expectedSigmas(0,0,1.0/3);
343 SharedDiagonal expectedModel = noiseModel::Constrained::MixedSigmas(expectedSigmas);
344 Matrix expectedRd(11, 3+1);
345 expectedRd.setZero();
346 expectedRd.row(0) << -1, 0, 1, 0;
347 expectedRd.row(1) << 0, -1, 1, 0;
348 expectedRd.row(2) << 0, 0, 1, 0;
356 TEST( NoiseModel, FullyConstrained )
368 expectedRd << 1, 0, 0, 0, 0, 1, 2,
382 Matrix Ab = (Matrix25() << 2, 4, 2, 4, 6, 2, 1, 2, 4, 4).finished();
385 Matrix expectedAb = (Matrix25() << 1, 2, 1, 2, 3, 0, 1, 0, 0, 2.0/3).finished();
393 TEST(NoiseModel, SmartSqrtInformation )
402 TEST(NoiseModel, SmartSqrtInformation2 )
411 TEST(NoiseModel, SmartInformation )
422 TEST(NoiseModel, SmartCovariance )
431 TEST(NoiseModel, ScalarOrVector )
440 TEST(NoiseModel, WhitenInPlace)
460 TEST(NoiseModel, robustFunctionFair)
462 const double k = 5.0, error1 = 1.0, error2 = 10.0, error3 = -10.0, error4 = -1.0;
476 TEST(NoiseModel, robustFunctionHuber)
478 const double k = 5.0, error1 = 1.0, error2 = 10.0, error3 = -10.0, error4 = -1.0;
492 TEST(NoiseModel, robustFunctionCauchy)
494 const double k = 5.0, error1 = 1.0, error2 = 10.0, error3 = -10.0, error4 = -1.0;
508 TEST(NoiseModel, robustFunctionAsymmetricCauchy)
510 const double k = 5.0, error1 = 1.0, error2 = 10.0, error3 = -10.0, error4 = -1.0;
524 TEST(NoiseModel, robustFunctionGemanMcClure)
526 const double k = 1.0, error1 = 1.0, error2 = 10.0, error3 = -10.0, error4 = -1.0;
539 TEST(NoiseModel, robustFunctionWelsch)
541 const double k = 5.0, error1 = 1.0, error2 = 10.0, error3 = -10.0, error4 = -1.0;
555 TEST(NoiseModel, robustFunctionTukey)
557 const double k = 5.0, error1 = 1.0, error2 = 10.0, error3 = -10.0, error4 = -1.0;
571 TEST(NoiseModel, robustFunctionAsymmetricTukey)
573 const double k = 5.0, error1 = 1.0, error2 = 10.0, error3 = -10.0, error4 = -1.0;
587 TEST(NoiseModel, robustFunctionDCS)
589 const double k = 1.0, error1 = 1.0, error2 = 10.0;
599 TEST(NoiseModel, robustFunctionL2WithDeadZone)
601 const double k = 1.0, e0 = -10.0, e1 = -1.01, e2 = -0.99, e3 = 0.99, e4 = 1.01, e5 = 10.0;
620 TEST(NoiseModel, robustNoiseHuber)
622 const double k = 10.0, error1 = 1.0, error2 = 100.0;
623 Matrix A = (
Matrix(2, 2) << 1.0, 10.0, 100.0, 1000.0).finished();
629 robust->WhitenSystem(
A,
b);
640 TEST(NoiseModel, robustNoiseGemanMcClure)
642 const double k = 1.0, error1 = 1.0, error2 = 100.0;
643 const double a00 = 1.0, a01 = 10.0, a10 = 100.0, a11 = 1000.0;
650 robust->WhitenSystem(
A,
b);
652 const double k2 = k*k;
653 const double k4 = k2*k2;
654 const double k2error = k2 + error2*error2;
656 const double sqrt_weight_error1 =
sqrt(0.25);
657 const double sqrt_weight_error2 =
sqrt(k4/(k2error*k2error));
668 TEST(NoiseModel, robustNoiseDCS)
670 const double k = 1.0, error1 = 1.0, error2 = 100.0;
671 const double a00 = 1.0, a01 = 10.0, a10 = 100.0, a11 = 1000.0;
678 robust->WhitenSystem(
A,
b);
680 const double sqrt_weight = 2.0*k/(k + error2*error2);
691 TEST(NoiseModel, robustNoiseL2WithDeadZone)
693 double dead_zone_size = 1.0;
694 auto robust = noiseModel::Robust::Create(
695 noiseModel::mEstimator::L2WithDeadZone::Create(dead_zone_size),
698 for (
int i = 0;
i < 5;
i++) {
700 robust->WhitenSystem(
error);
702 robust->squaredMahalanobisDistance(
error), 1
e-8);
707 TEST(NoiseModel, robustNoiseCustomHuber) {
708 const double k = 10.0, error1 = 1.0, error2 = 100.0;
709 Matrix A = (
Matrix(2, 2) << 1.0, 10.0, 100.0, 1000.0).finished();
712 Robust::Create(mEstimator::Custom::Create(
715 return abs_e <= k ? 1.0 : k / abs_e;
719 return abs_e <= k ? abs_e * abs_e / 2.0 : k * abs_e - k * k / 2.0;
724 robust->WhitenSystem(
A,
b);
735 TEST(NoiseModel, lossFunctionAtZero)
737 const double k = 5.0;
738 auto fair = mEstimator::Fair::Create(k);
741 auto huber = mEstimator::Huber::Create(k);
744 auto cauchy = mEstimator::Cauchy::Create(k);
747 auto gmc = mEstimator::GemanMcClure::Create(k);
750 auto welsch = mEstimator::Welsch::Create(k);
753 auto tukey = mEstimator::Tukey::Create(k);
756 auto dcs = mEstimator::DCS::Create(k);
759 auto lsdz = mEstimator::L2WithDeadZone::Create(k);
762 auto assy_cauchy = mEstimator::AsymmetricCauchy::Create(k);
765 auto assy_tukey = mEstimator::AsymmetricTukey::Create(k);
772 #define TEST_GAUSSIAN(gaussian)\
773 EQUALITY(info, gaussian->information());\
774 EQUALITY(cov, gaussian->covariance());\
775 EXPECT(assert_equal(white, gaussian->whiten(e)));\
776 EXPECT(assert_equal(e, gaussian->unwhiten(white)));\
777 EXPECT_DOUBLES_EQUAL(251.0, gaussian->squaredMahalanobisDistance(e), 1e-9);\
778 EXPECT_DOUBLES_EQUAL(0.5 * 251.0, gaussian->loss(251.0), 1e-9);\
779 Matrix A = R.inverse(); Vector b = e;\
780 gaussian->WhitenSystem(A, b);\
781 EXPECT(assert_equal(I, A));\
782 EXPECT(assert_equal(white, b));
784 TEST(NoiseModel, NonDiagonalGaussian)
787 R << 6, 5, 4, 0, 3, 2, 0, 0, 1;
788 const Matrix3
info =
R.transpose() *
R;
789 const Matrix3 cov =
info.inverse();
810 TEST(NoiseModel, NegLogNormalizationConstant1D) {
822 double actual_value =
noise_model->negLogConstant();
828 double actual_value =
noise_model->negLogConstant();
834 double actual_value =
noise_model->negLogConstant();
840 double actual_value =
noise_model->negLogConstant();
847 TEST(NoiseModel, NegLogNormalizationConstant3D) {
862 double actual_value =
noise_model->negLogConstant();
868 double actual_value =
noise_model->negLogConstant();
874 double actual_value =
noise_model->negLogConstant();
880 double actual_value =
noise_model->negLogConstant();