29 using namespace gtsam;
31 using Dims = std::vector<Eigen::Index>;
36 using Terms = vector<pair<Key, Matrix> >;
37 const Terms terms{{5, I_3x3}, {10, 2 * I_3x3}, {15, 3 * I_3x3}};
42 noiseModel::Diagonal::Sigmas(
Vector3(0.5, 0.5, 0.5));
60 EXPECT(!actual.get_model());
67 LONGS_EQUAL((
long)terms[0].first, (
long)actual.keys().back());
75 EXPECT(noise == actual.get_model());
81 terms[1].first, terms[1].second,
b, noise);
83 LONGS_EQUAL((
long)terms[1].first, (
long)actual.keys().back());
91 EXPECT(noise == actual.get_model());
97 terms[1].first, terms[1].second, terms[2].first, terms[2].second,
b, noise);
99 LONGS_EQUAL((
long)terms[2].first, (
long)actual.keys().back());
107 EXPECT(noise == actual.get_model());
112 map<Key,Matrix> mapTerms;
114 mapTerms.insert(terms[2]);
115 mapTerms.insert(terms[1]);
116 mapTerms.insert(terms[0]);
130 blockMatrix(0) = terms[0].second;
131 blockMatrix(1) = terms[1].second;
132 blockMatrix(2) = terms[2].second;
136 for (
const auto& term : terms)
137 keys.push_back(term.first);
150 TEST(JabobianFactor, Hessian_conversion) {
152 1.57, 2.695, -1.1, -2.35,
153 2.695, 11.3125, -0.65, -10.225,
155 -2.35, -10.225, 0.5, 9.25).finished(),
156 (
Vector(4) << -7.885, -28.5175, 2.75, 25.675).finished(),
160 1.2530, 2.1508, -0.8779, -1.8755,
161 0, 2.5858, 0.4789, -2.3943).finished(),
168 TEST(JabobianFactor, Hessian_conversion2) {
179 TEST(JabobianFactor, Hessian_conversion3) {
182 0, 3, 2, 1).finished(),
196 auto factor1 = std::make_shared<JacobianFactor>(
203 auto factor2 = std::make_shared<JacobianFactor>(
210 auto factor3 = std::make_shared<JacobianFactor>(
245 Vector expected_unwhitened(3); expected_unwhitened << 2.0, 1.0, 0.0;
249 Vector expected_whitened(3); expected_whitened << 4.0, 2.0, 0.0;
253 double expected_error = 0.5 * expected_whitened.squaredNorm();
264 Matrix jacobianExpected(3, 9);
265 jacobianExpected << simple::terms[0].second, simple::terms[1].second, simple::terms[2].second;
267 Matrix augmentedJacobianExpected(3, 10);
268 augmentedJacobianExpected << jacobianExpected, rhsExpected;
270 Matrix augmentedHessianExpected =
271 augmentedJacobianExpected.transpose() * augmentedJacobianExpected;
289 expectDiagonal.
insert(5, Vector::Ones(3));
290 expectDiagonal.
insert(10, 4*Vector::Ones(3));
291 expectDiagonal.
insert(15, 9*Vector::Ones(3));
308 Matrix jacobianExpected(3, 9);
309 jacobianExpected << simple::terms[0].second, simple::terms[1].second, simple::terms[2].second;
311 Matrix augmentedJacobianExpected(3, 10);
312 augmentedJacobianExpected << jacobianExpected, rhsExpected;
314 Matrix augmentedHessianExpected =
315 augmentedJacobianExpected.transpose() * simple::noise->R().transpose()
316 * simple::noise->R() * augmentedJacobianExpected;
351 const double sigma = 0.1;
370 const double alpha = 0.5;
410 0.0, 0.0, 1.0).finished();
417 0.0, 0.0, 2.0).finished();
421 0.0, 0.0, -2.0).finished();
428 0.0, 0.0, 3.0).finished();
433 gfg.
add(1, A01, b0, noiseModel::Diagonal::Sigmas(s0,
true));
434 gfg.
add(0,
A10, 1,
A11,
b1, noiseModel::Diagonal::Sigmas(s1,
true));
435 gfg.
add(1,
A21,
b2, noiseModel::Diagonal::Sigmas(s2,
true));
437 Matrix zero3x3 = Matrix::Zero(3,3);
440 Vector9
b;
b <<
b1, b0,
b2;
488 vector<pair<Key, Matrix> > meas;
489 meas.push_back(make_pair(2, Ax2));
490 meas.push_back(make_pair(11, Al1x1));
494 pair<GaussianConditional::shared_ptr, JacobianFactor::shared_ptr>
498 double oldSigma = 0.0894427;
502 ).finished()/oldSigma;
504 -0.20, 0.00,-0.80, 0.00,
505 +0.00,-0.20,+0.00,-0.80
506 ).finished()/oldSigma;
513 double sigma = 0.2236;
516 1.00, 0.00, -1.00, 0.00,
517 0.00, 1.00, +0.00, -1.00
529 4., 0., 1., 4., 1., 0., 3., 6., 8., 8., 1.,
530 9., 2., 0., 1., 6., 3., 9., 6., 6., 9., 4.,
531 5., 3., 7., 9., 5., 5., 9., 1., 3., 7., 0.,
532 5., 6., 5., 7., 9., 4., 0., 1., 1., 3., 5.,
533 0., 0., 4., 5., 6., 6., 7., 9., 4., 5., 4.,
534 0., 0., 9., 4., 8., 6., 2., 1., 4., 1., 6.,
535 0., 0., 6., 0., 4., 2., 4., 0., 1., 9., 6.,
536 0., 0., 6., 6., 4., 4., 5., 5., 5., 8., 6.,
537 0., 0., 0., 0., 8., 0., 9., 8., 2., 8., 0.,
538 0., 0., 0., 0., 0., 9., 4., 6., 3., 2., 0.,
539 0., 0., 0., 0., 1., 1., 9., 1., 5., 5., 3.,
540 0., 0., 0., 0., 1., 1., 3., 3., 2., 0., 5.,
541 0., 0., 0., 0., 0., 0., 0., 0., 2., 4., 6.,
542 0., 0., 0., 0., 0., 0., 0., 0., 6., 3., 4.).finished();
545 const SharedDiagonal sig_4D = noiseModel::Isotropic::Sigma(4, 0.5);
546 const SharedDiagonal sig_2D = noiseModel::Isotropic::Sigma(2, 0.5);
548 std::make_shared<JacobianFactor>(
KeyVector{3, 5, 7, 9, 11},
VerticalBlockMatrix(
Dims{2, 2, 2, 2, 2, 1},
Ab.block(0, 0, 4, 11)), sig_4D),
549 std::make_shared<JacobianFactor>(
KeyVector{5, 7, 9, 11},
VerticalBlockMatrix(
Dims{2, 2, 2, 2, 1},
Ab.block(4, 2, 4, 9)), sig_4D),
550 std::make_shared<JacobianFactor>(
KeyVector{7, 9, 11},
VerticalBlockMatrix(
Dims{2, 2, 2, 1},
Ab.block(8, 4, 4, 7)), sig_4D),
559 -12.1244, -5.1962, -5.2786, -8.6603, -10.5573, -5.9385, -11.3820, -7.2581, -8.7427, -13.4440, -5.3611,
560 0., 4.6904, 5.0254, 5.5432, 5.5737, 3.0153, -3.0153, -3.5635, -3.9290, -2.7412, 2.1625,
561 0., 0., -13.8160, -8.7166, -10.2245, -8.8666, -8.7632, -5.2544, -6.9192, -10.5537, -9.3250,
562 0., 0., 0., 6.5033, -1.1453, 1.3179, 2.5768, 5.5503, 3.6524, 1.3491, -2.5676,
563 0., 0., 0., 0., -9.6242, -2.1148, -9.3509, -10.5846, -3.5366, -6.8561, -3.2277,
564 0., 0., 0., 0., 0., 9.7887, 4.3551, 5.7572, 2.7876, 0.1611, 1.1769,
565 0., 0., 0., 0., 0., 0., -11.1139, -0.6521, -2.1943, -7.5529, -0.9081,
566 0., 0., 0., 0., 0., 0., 0., -4.6479, -1.9367, -6.5170, -3.7685,
567 0., 0., 0., 0., 0., 0., 0., 0., 8.2503, 3.3757, 6.8476,
568 0., 0., 0., 0., 0., 0., 0., 0., 0., -5.7095, -0.0090).finished();
572 noiseModel::Unit::Create(6));
585 EXPECT(
assert_equal(*noiseModel::Diagonal::Sigmas(Vector4::Ones()), *actualJF.get_model(), 0.001));
596 pair<GaussianConditional::shared_ptr, JacobianFactor::shared_ptr>
600 EXPECT(actual.second->empty());
616 Matrix2
A1;
A1 << 2,4, 2,1;
619 Matrix2
A2;
A2 << 2,4, 2,4;
624 pair<GaussianConditional::shared_ptr, JacobianFactor::shared_ptr>
631 Vector bempty =
m.block(0,0,0,1);
632 JacobianFactor expectedLF(2, Aempty, bempty, noiseModel::Constrained::All(0));
636 Matrix2
R;
R << 1,2, 0,1;
637 Matrix2
S;
S << 1,2, 0,0;
652 Vector9
sigmas = Vector9::Ones();
659 expectedRd << -2.64575131, -2.64575131, -2.64575131, -2.64575131,
663 noiseModel::Unit::Create(3));
665 EXPECT(actual.second->empty());