testHybridNonlinearFactorGraph.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
3  * Atlanta, Georgia 30332-0415
4  * All Rights Reserved
5  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
6  * See LICENSE for the license information
7  * -------------------------------------------------------------------------- */
8 
19 #include <gtsam/base/utilities.h>
23 #include <gtsam/geometry/Pose2.h>
34 
35 #include <numeric>
36 
37 #include "Switching.h"
38 
39 // Include for test suite
41 
42 using namespace std;
43 using namespace gtsam;
48 
49 /* ****************************************************************************
50  * Test that any linearizedFactorGraph gaussian factors are appended to the
51  * existing gaussian factor graph in the hybrid factor graph.
52  */
55 
56  // Add a simple prior factor to the nonlinear factor graph
57  fg.emplace_shared<PriorFactor<double>>(X(0), 0, Isotropic::Sigma(1, 0.1));
58 
59  // Linearization point
60  Values linearizationPoint;
61  linearizationPoint.insert<double>(X(0), 0);
62 
63  // Linearize the factor graph.
64  HybridGaussianFactorGraph ghfg = *fg.linearize(linearizationPoint);
65  EXPECT_LONGS_EQUAL(1, ghfg.size());
66 
67  // Check that the error is the same for the nonlinear values.
68  const VectorValues zero{{X(0), Vector1(0)}};
69  const HybridValues hybridValues{zero, {}, linearizationPoint};
70  EXPECT_DOUBLES_EQUAL(fg.error(hybridValues), ghfg.error(hybridValues), 1e-9);
71 }
72 
73 /***************************************************************************
74  * Test equality for Hybrid Nonlinear Factor Graph.
75  */
79 
80  // Test empty factor graphs
81  EXPECT(assert_equal(graph1, graph2));
82 
83  auto f0 = std::make_shared<PriorFactor<Pose2>>(
84  1, Pose2(), noiseModel::Isotropic::Sigma(3, 0.001));
85  graph1.push_back(f0);
86  graph2.push_back(f0);
87 
88  auto f1 = std::make_shared<BetweenFactor<Pose2>>(
89  1, 2, Pose2(), noiseModel::Isotropic::Sigma(3, 0.1));
90  graph1.push_back(f1);
91  graph2.push_back(f1);
92 
93  // Test non-empty graphs
94  EXPECT(assert_equal(graph1, graph2));
95 }
96 
97 /***************************************************************************
98  * Test that the resize method works correctly for a HybridNonlinearFactorGraph.
99  */
102  auto nonlinearFactor = std::make_shared<BetweenFactor<double>>();
103  fg.push_back(nonlinearFactor);
104 
105  auto discreteFactor = std::make_shared<DecisionTreeFactor>();
106  fg.push_back(discreteFactor);
107 
108  auto dcFactor = std::make_shared<MixtureFactor>();
109  fg.push_back(dcFactor);
110 
111  EXPECT_LONGS_EQUAL(fg.size(), 3);
112 
113  fg.resize(0);
114  EXPECT_LONGS_EQUAL(fg.size(), 0);
115 }
116 
117 /***************************************************************************
118  * Test that the resize method works correctly for a
119  * HybridGaussianFactorGraph.
120  */
123  auto nonlinearFactor = std::make_shared<BetweenFactor<double>>(
124  X(0), X(1), 0.0, Isotropic::Sigma(1, 0.1));
125  nhfg.push_back(nonlinearFactor);
126  auto discreteFactor = std::make_shared<DecisionTreeFactor>();
127  nhfg.push_back(discreteFactor);
128 
129  KeyVector contKeys = {X(0), X(1)};
130  auto noise_model = noiseModel::Isotropic::Sigma(1, 1.0);
131  auto still = std::make_shared<MotionModel>(X(0), X(1), 0.0, noise_model),
132  moving = std::make_shared<MotionModel>(X(0), X(1), 1.0, noise_model);
133 
134  std::vector<MotionModel::shared_ptr> components = {still, moving};
135  auto dcFactor = std::make_shared<MixtureFactor>(
136  contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components);
137  nhfg.push_back(dcFactor);
138 
139  Values linearizationPoint;
140  linearizationPoint.insert<double>(X(0), 0);
141  linearizationPoint.insert<double>(X(1), 1);
142 
143  // Generate `HybridGaussianFactorGraph` by linearizing
144  HybridGaussianFactorGraph gfg = *nhfg.linearize(linearizationPoint);
145 
146  EXPECT_LONGS_EQUAL(gfg.size(), 3);
147 
148  gfg.resize(0);
149  EXPECT_LONGS_EQUAL(gfg.size(), 0);
150 }
151 
152 /***************************************************************************
153  * Test that the MixtureFactor reports correctly if the number of continuous
154  * keys provided do not match the keys in the factors.
155  */
157  auto nonlinearFactor = std::make_shared<BetweenFactor<double>>(
158  X(0), X(1), 0.0, Isotropic::Sigma(1, 0.1));
159  auto discreteFactor = std::make_shared<DecisionTreeFactor>();
160 
161  auto noise_model = noiseModel::Isotropic::Sigma(1, 1.0);
162  auto still = std::make_shared<MotionModel>(X(0), X(1), 0.0, noise_model),
163  moving = std::make_shared<MotionModel>(X(0), X(1), 1.0, noise_model);
164 
165  std::vector<MotionModel::shared_ptr> components = {still, moving};
166 
167  // Check for exception when number of continuous keys are under-specified.
168  KeyVector contKeys = {X(0)};
169  THROWS_EXCEPTION(std::make_shared<MixtureFactor>(
170  contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components));
171 
172  // Check for exception when number of continuous keys are too many.
173  contKeys = {X(0), X(1), X(2)};
174  THROWS_EXCEPTION(std::make_shared<MixtureFactor>(
175  contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, components));
176 }
177 
178 /*****************************************************************************
179  * Test push_back on HFG makes the correct distinction.
180  */
183 
184  auto nonlinearFactor = std::make_shared<BetweenFactor<double>>();
185  fg.push_back(nonlinearFactor);
186 
187  EXPECT_LONGS_EQUAL(fg.size(), 1);
188 
190 
191  auto discreteFactor = std::make_shared<DecisionTreeFactor>();
192  fg.push_back(discreteFactor);
193 
194  EXPECT_LONGS_EQUAL(fg.size(), 1);
195 
197 
198  auto dcFactor = std::make_shared<MixtureFactor>();
199  fg.push_back(dcFactor);
200 
201  EXPECT_LONGS_EQUAL(fg.size(), 1);
202 
203  // Now do the same with HybridGaussianFactorGraph
205 
206  auto gaussianFactor = std::make_shared<JacobianFactor>();
207  ghfg.push_back(gaussianFactor);
208 
209  EXPECT_LONGS_EQUAL(ghfg.size(), 1);
210 
211  ghfg = HybridGaussianFactorGraph();
212  ghfg.push_back(discreteFactor);
213 
214  EXPECT_LONGS_EQUAL(ghfg.size(), 1);
215 
216  ghfg = HybridGaussianFactorGraph();
217  ghfg.push_back(dcFactor);
218 
220  hgfg2.push_back(ghfg.begin(), ghfg.end());
221 
222  EXPECT_LONGS_EQUAL(ghfg.size(), 1);
223 
226  auto noise = noiseModel::Isotropic::Sigma(3, 1.0);
227  factors.emplace_shared<PriorFactor<Pose2>>(0, Pose2(0, 0, 0), noise);
228  factors.emplace_shared<PriorFactor<Pose2>>(1, Pose2(1, 0, 0), noise);
229  factors.emplace_shared<PriorFactor<Pose2>>(2, Pose2(2, 0, 0), noise);
230  // TODO(Varun) This does not currently work. It should work once HybridFactor
231  // becomes a base class of NonlinearFactor.
232  // hnfg.push_back(factors.begin(), factors.end());
233 
234  // EXPECT_LONGS_EQUAL(3, hnfg.size());
235 }
236 
237 /****************************************************************************
238  * Test construction of switching-like hybrid factor graph.
239  */
241  Switching self(3);
242 
243  EXPECT_LONGS_EQUAL(7, self.nonlinearFactorGraph.size());
244  EXPECT_LONGS_EQUAL(7, self.linearizedFactorGraph.size());
245 }
246 
247 /****************************************************************************
248  * Test linearization on a switching-like hybrid factor graph.
249  */
250 TEST(HybridFactorGraph, Linearization) {
251  Switching self(3);
252 
253  // Linearize here:
254  HybridGaussianFactorGraph actualLinearized =
255  *self.nonlinearFactorGraph.linearize(self.linearizationPoint);
256 
257  EXPECT_LONGS_EQUAL(7, actualLinearized.size());
258 }
259 
260 /****************************************************************************
261  * Test elimination tree construction
262  */
264  Switching self(3);
265 
266  // Create ordering.
268  for (size_t k = 0; k < self.K; k++) ordering.push_back(X(k));
269 
270  // Create elimination tree.
271  HybridEliminationTree etree(self.linearizedFactorGraph, ordering);
272  EXPECT_LONGS_EQUAL(1, etree.roots().size())
273 }
274 
275 /****************************************************************************
276  *Test elimination function by eliminating x0 in *-x0-*-x1 graph.
277  */
278 TEST(GaussianElimination, Eliminate_x0) {
279  Switching self(3);
280 
281  // Gather factors on x1, has a simple Gaussian and a mixture factor.
283  // Add gaussian prior
284  factors.push_back(self.linearizedFactorGraph[0]);
285  // Add first hybrid factor
286  factors.push_back(self.linearizedFactorGraph[1]);
287 
288  // Eliminate x0
289  const Ordering ordering{X(0)};
290 
291  auto result = EliminateHybrid(factors, ordering);
292  CHECK(result.first);
293  EXPECT_LONGS_EQUAL(1, result.first->nrFrontals());
294  CHECK(result.second);
295  // Has two keys, x2 and m1
296  EXPECT_LONGS_EQUAL(2, result.second->size());
297 }
298 
299 /****************************************************************************
300  * Test elimination function by eliminating x1 in x0-*-x1-*-x2 chain.
301  * m0/ \m1
302  */
303 TEST(HybridsGaussianElimination, Eliminate_x1) {
304  Switching self(3);
305 
306  // Gather factors on x1, will be two mixture factors (with x0 and x2, resp.).
308  factors.push_back(self.linearizedFactorGraph[1]); // involves m0
309  factors.push_back(self.linearizedFactorGraph[2]); // involves m1
310 
311  // Eliminate x1
312  const Ordering ordering{X(1)};
313 
314  auto result = EliminateHybrid(factors, ordering);
315  CHECK(result.first);
316  EXPECT_LONGS_EQUAL(1, result.first->nrFrontals());
317  CHECK(result.second);
318  // Note: separator keys should include m1, m2.
319  EXPECT_LONGS_EQUAL(4, result.second->size());
320 }
321 
322 /****************************************************************************
323  * Helper method to generate gaussian factor graphs with a specific mode.
324  */
326  Values linearizationPoint) {
328  graph.addPrior<double>(X(0), 0, Isotropic::Sigma(1, 0.1));
329 
330  auto between_x0_x1 = std::make_shared<MotionModel>(
331  X(0), X(1), between, Isotropic::Sigma(1, 1.0));
332 
333  graph.push_back(between_x0_x1);
334 
335  return graph.linearize(linearizationPoint);
336 }
337 
338 /****************************************************************************
339  * Test elimination function by eliminating x0 and x1 in graph.
340  */
341 TEST(HybridGaussianElimination, EliminateHybrid_2_Variable) {
342  Switching self(2, 1.0, 0.1);
343 
344  auto factors = self.linearizedFactorGraph;
345 
346  // Eliminate x0
347  const Ordering ordering{X(0), X(1)};
348 
349  const auto [hybridConditionalMixture, factorOnModes] =
351 
352  auto gaussianConditionalMixture =
353  dynamic_pointer_cast<GaussianMixture>(hybridConditionalMixture->inner());
354 
355  CHECK(gaussianConditionalMixture);
356  // Frontals = [x0, x1]
357  EXPECT_LONGS_EQUAL(2, gaussianConditionalMixture->nrFrontals());
358  // 1 parent, which is the mode
359  EXPECT_LONGS_EQUAL(1, gaussianConditionalMixture->nrParents());
360 
361  // This is now a discreteFactor
362  auto discreteFactor = dynamic_pointer_cast<DecisionTreeFactor>(factorOnModes);
363  CHECK(discreteFactor);
364  EXPECT_LONGS_EQUAL(1, discreteFactor->discreteKeys().size());
365  EXPECT(discreteFactor->root_->isLeaf() == false);
366 }
367 
368 /****************************************************************************
369  * Test partial elimination
370  */
371 TEST(HybridFactorGraph, Partial_Elimination) {
372  Switching self(3);
373 
374  auto linearizedFactorGraph = self.linearizedFactorGraph;
375 
376  // Create ordering of only continuous variables.
378  for (size_t k = 0; k < self.K; k++) ordering.push_back(X(k));
379 
380  // Eliminate partially i.e. only continuous part.
381  const auto [hybridBayesNet, remainingFactorGraph] =
382  linearizedFactorGraph.eliminatePartialSequential(ordering);
383 
384  CHECK(hybridBayesNet);
385  EXPECT_LONGS_EQUAL(3, hybridBayesNet->size());
386  EXPECT(hybridBayesNet->at(0)->frontals() == KeyVector{X(0)});
387  EXPECT(hybridBayesNet->at(0)->parents() == KeyVector({X(1), M(0)}));
388  EXPECT(hybridBayesNet->at(1)->frontals() == KeyVector{X(1)});
389  EXPECT(hybridBayesNet->at(1)->parents() == KeyVector({X(2), M(0), M(1)}));
390  EXPECT(hybridBayesNet->at(2)->frontals() == KeyVector{X(2)});
391  EXPECT(hybridBayesNet->at(2)->parents() == KeyVector({M(0), M(1)}));
392 
393  CHECK(remainingFactorGraph);
394  EXPECT_LONGS_EQUAL(3, remainingFactorGraph->size());
395  EXPECT(remainingFactorGraph->at(0)->keys() == KeyVector({M(0)}));
396  EXPECT(remainingFactorGraph->at(1)->keys() == KeyVector({M(1), M(0)}));
397  EXPECT(remainingFactorGraph->at(2)->keys() == KeyVector({M(0), M(1)}));
398 }
399 
400 /****************************************************************************
401  * Test full elimination
402  */
403 TEST(HybridFactorGraph, Full_Elimination) {
404  Switching self(3);
405 
406  auto linearizedFactorGraph = self.linearizedFactorGraph;
407 
408  // We first do a partial elimination
409  DiscreteBayesNet discreteBayesNet;
410 
411  {
412  // Create ordering.
414  for (size_t k = 0; k < self.K; k++) ordering.push_back(X(k));
415 
416  // Eliminate partially.
417  const auto [hybridBayesNet_partial, remainingFactorGraph_partial] =
418  linearizedFactorGraph.eliminatePartialSequential(ordering);
419 
420  DiscreteFactorGraph discrete_fg;
421  // TODO(Varun) Make this a function of HybridGaussianFactorGraph?
422  for (auto& factor : (*remainingFactorGraph_partial)) {
423  auto df = dynamic_pointer_cast<DecisionTreeFactor>(factor);
424  assert(df);
425  discrete_fg.push_back(df);
426  }
427 
428  ordering.clear();
429  for (size_t k = 0; k < self.K - 1; k++) ordering.push_back(M(k));
430  discreteBayesNet =
431  *discrete_fg.eliminateSequential(ordering, EliminateDiscrete);
432  }
433 
434  // Create ordering.
436  for (size_t k = 0; k < self.K; k++) ordering.push_back(X(k));
437  for (size_t k = 0; k < self.K - 1; k++) ordering.push_back(M(k));
438 
439  // Eliminate partially.
440  HybridBayesNet::shared_ptr hybridBayesNet =
441  linearizedFactorGraph.eliminateSequential(ordering);
442 
443  CHECK(hybridBayesNet);
444  EXPECT_LONGS_EQUAL(5, hybridBayesNet->size());
445  // p(x0 | x1, m0)
446  EXPECT(hybridBayesNet->at(0)->frontals() == KeyVector{X(0)});
447  EXPECT(hybridBayesNet->at(0)->parents() == KeyVector({X(1), M(0)}));
448  // p(x1 | x2, m0, m1)
449  EXPECT(hybridBayesNet->at(1)->frontals() == KeyVector{X(1)});
450  EXPECT(hybridBayesNet->at(1)->parents() == KeyVector({X(2), M(0), M(1)}));
451  // p(x2 | m0, m1)
452  EXPECT(hybridBayesNet->at(2)->frontals() == KeyVector{X(2)});
453  EXPECT(hybridBayesNet->at(2)->parents() == KeyVector({M(0), M(1)}));
454  // P(m0 | m1)
455  EXPECT(hybridBayesNet->at(3)->frontals() == KeyVector{M(0)});
456  EXPECT(hybridBayesNet->at(3)->parents() == KeyVector({M(1)}));
457  EXPECT(
458  dynamic_pointer_cast<DiscreteConditional>(hybridBayesNet->at(3)->inner())
459  ->equals(*discreteBayesNet.at(0)));
460  // P(m1)
461  EXPECT(hybridBayesNet->at(4)->frontals() == KeyVector{M(1)});
462  EXPECT_LONGS_EQUAL(0, hybridBayesNet->at(4)->nrParents());
463  EXPECT(
464  dynamic_pointer_cast<DiscreteConditional>(hybridBayesNet->at(4)->inner())
465  ->equals(*discreteBayesNet.at(1)));
466 }
467 
468 /****************************************************************************
469  * Test printing
470  */
472  Switching self(3);
473 
474  auto linearizedFactorGraph = self.linearizedFactorGraph;
475 
476  // Create ordering.
478  for (size_t k = 0; k < self.K; k++) ordering.push_back(X(k));
479 
480  // Eliminate partially.
481  const auto [hybridBayesNet, remainingFactorGraph] =
482  linearizedFactorGraph.eliminatePartialSequential(ordering);
483 
484  string expected_hybridFactorGraph = R"(
485 size: 7
486 factor 0:
487  A[x0] = [
488  10
489 ]
490  b = [ -10 ]
491  No noise model
492 factor 1:
493 Hybrid [x0 x1; m0]{
494  Choice(m0)
495  0 Leaf :
496  A[x0] = [
497  -1
498 ]
499  A[x1] = [
500  1
501 ]
502  b = [ -1 ]
503  No noise model
504 
505  1 Leaf :
506  A[x0] = [
507  -1
508 ]
509  A[x1] = [
510  1
511 ]
512  b = [ -0 ]
513  No noise model
514 
515 }
516 factor 2:
517 Hybrid [x1 x2; m1]{
518  Choice(m1)
519  0 Leaf :
520  A[x1] = [
521  -1
522 ]
523  A[x2] = [
524  1
525 ]
526  b = [ -1 ]
527  No noise model
528 
529  1 Leaf :
530  A[x1] = [
531  -1
532 ]
533  A[x2] = [
534  1
535 ]
536  b = [ -0 ]
537  No noise model
538 
539 }
540 factor 3:
541  A[x1] = [
542  10
543 ]
544  b = [ -10 ]
545  No noise model
546 factor 4:
547  A[x2] = [
548  10
549 ]
550  b = [ -10 ]
551  No noise model
552 factor 5: P( m0 ):
553  Leaf 0.5
554 
555 factor 6: P( m1 | m0 ):
556  Choice(m1)
557  0 Choice(m0)
558  0 0 Leaf 0.33333333
559  0 1 Leaf 0.6
560  1 Choice(m0)
561  1 0 Leaf 0.66666667
562  1 1 Leaf 0.4
563 
564 )";
565  EXPECT(assert_print_equal(expected_hybridFactorGraph, linearizedFactorGraph));
566 
567  // Expected output for hybridBayesNet.
568  string expected_hybridBayesNet = R"(
569 size: 3
570 conditional 0: Hybrid P( x0 | x1 m0)
571  Discrete Keys = (m0, 2),
572  Choice(m0)
573  0 Leaf p(x0 | x1)
574  R = [ 10.0499 ]
575  S[x1] = [ -0.0995037 ]
576  d = [ -9.85087 ]
577  No noise model
578 
579  1 Leaf p(x0 | x1)
580  R = [ 10.0499 ]
581  S[x1] = [ -0.0995037 ]
582  d = [ -9.95037 ]
583  No noise model
584 
585 conditional 1: Hybrid P( x1 | x2 m0 m1)
586  Discrete Keys = (m0, 2), (m1, 2),
587  Choice(m1)
588  0 Choice(m0)
589  0 0 Leaf p(x1 | x2)
590  R = [ 10.099 ]
591  S[x2] = [ -0.0990196 ]
592  d = [ -9.99901 ]
593  No noise model
594 
595  0 1 Leaf p(x1 | x2)
596  R = [ 10.099 ]
597  S[x2] = [ -0.0990196 ]
598  d = [ -9.90098 ]
599  No noise model
600 
601  1 Choice(m0)
602  1 0 Leaf p(x1 | x2)
603  R = [ 10.099 ]
604  S[x2] = [ -0.0990196 ]
605  d = [ -10.098 ]
606  No noise model
607 
608  1 1 Leaf p(x1 | x2)
609  R = [ 10.099 ]
610  S[x2] = [ -0.0990196 ]
611  d = [ -10 ]
612  No noise model
613 
614 conditional 2: Hybrid P( x2 | m0 m1)
615  Discrete Keys = (m0, 2), (m1, 2),
616  Choice(m1)
617  0 Choice(m0)
618  0 0 Leaf p(x2)
619  R = [ 10.0494 ]
620  d = [ -10.1489 ]
621  mean: 1 elements
622  x2: -1.0099
623  No noise model
624 
625  0 1 Leaf p(x2)
626  R = [ 10.0494 ]
627  d = [ -10.1479 ]
628  mean: 1 elements
629  x2: -1.0098
630  No noise model
631 
632  1 Choice(m0)
633  1 0 Leaf p(x2)
634  R = [ 10.0494 ]
635  d = [ -10.0504 ]
636  mean: 1 elements
637  x2: -1.0001
638  No noise model
639 
640  1 1 Leaf p(x2)
641  R = [ 10.0494 ]
642  d = [ -10.0494 ]
643  mean: 1 elements
644  x2: -1
645  No noise model
646 
647 )";
648  EXPECT(assert_print_equal(expected_hybridBayesNet, *hybridBayesNet));
649 }
650 
651 /****************************************************************************
652  * Simple PlanarSLAM example test with 2 poses and 2 landmarks (each pose
653  * connects to 1 landmark) to expose issue with default decision tree creation
654  * in hybrid elimination. The hybrid factor is between the poses X0 and X1.
655  * The issue arises if we eliminate a landmark variable first since it is not
656  * connected to a HybridFactor.
657  */
658 TEST(HybridFactorGraph, DefaultDecisionTree) {
660 
661  // Add a prior on pose x0 at the origin.
662  // A prior factor consists of a mean and a noise model (covariance matrix)
663  Pose2 prior(0.0, 0.0, 0.0); // prior mean is at origin
664  auto priorNoise = noiseModel::Diagonal::Sigmas(
665  Vector3(0.3, 0.3, 0.1)); // 30cm std on x,y, 0.1 rad on theta
667 
668  using PlanarMotionModel = BetweenFactor<Pose2>;
669 
670  // Add odometry factor
671  Pose2 odometry(2.0, 0.0, 0.0);
672  KeyVector contKeys = {X(0), X(1)};
673  auto noise_model = noiseModel::Isotropic::Sigma(3, 1.0);
674  auto still = std::make_shared<PlanarMotionModel>(X(0), X(1), Pose2(0, 0, 0),
675  noise_model),
676  moving = std::make_shared<PlanarMotionModel>(X(0), X(1), odometry,
677  noise_model);
678  std::vector<PlanarMotionModel::shared_ptr> motion_models = {still, moving};
680  contKeys, DiscreteKeys{gtsam::DiscreteKey(M(1), 2)}, motion_models);
681 
682  // Add Range-Bearing measurements to from X0 to L0 and X1 to L1.
683  // create a noise model for the landmark measurements
684  auto measurementNoise = noiseModel::Diagonal::Sigmas(
685  Vector2(0.1, 0.2)); // 0.1 rad std on bearing, 20cm on range
686  // create the measurement values - indices are (pose id, landmark id)
687  Rot2 bearing11 = Rot2::fromDegrees(45), bearing22 = Rot2::fromDegrees(90);
688  double range11 = std::sqrt(4.0 + 4.0), range22 = 2.0;
689 
690  // Add Bearing-Range factors
692  X(0), L(0), bearing11, range11, measurementNoise);
694  X(1), L(1), bearing22, range22, measurementNoise);
695 
696  // Create (deliberately inaccurate) initial estimate
697  Values initialEstimate;
698  initialEstimate.insert(X(0), Pose2(0.5, 0.0, 0.2));
699  initialEstimate.insert(X(1), Pose2(2.3, 0.1, -0.2));
700  initialEstimate.insert(L(0), Point2(1.8, 2.1));
701  initialEstimate.insert(L(1), Point2(4.1, 1.8));
702 
703  // We want to eliminate variables not connected to DCFactors first.
704  const Ordering ordering {L(0), L(1), X(0), X(1)};
705 
706  HybridGaussianFactorGraph linearized = *fg.linearize(initialEstimate);
707 
708  // This should NOT fail
709  const auto [hybridBayesNet, remainingFactorGraph] =
711  EXPECT_LONGS_EQUAL(4, hybridBayesNet->size());
712  EXPECT_LONGS_EQUAL(1, remainingFactorGraph->size());
713 }
714 
715 /* ************************************************************************* */
716 int main() {
717  TestResult tr;
718  return TestRegistry::runAllTests(tr);
719 }
720 /* ************************************************************************* */
Provides additional testing facilities for common data structures.
#define CHECK(condition)
Definition: Test.h:108
const FastVector< sharedNode > & roots() const
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
Main elimination function for DiscreteFactorGraph.
Nonlinear hybrid factor graph that uses type erasure.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
T between(const T &t1, const T &t2)
Definition: lieProxies.h:36
Factor Graph consisting of non-linear factors.
bool assert_print_equal(const std::string &expected, const V &actual, const std::string &s="")
Eigen::Matrix< double, 1, 1 > Vector1
Definition: testEvent.cpp:33
Point2 prior(const Point2 &x)
Prior on a single pose.
Definition: simulated2D.h:88
Vector2 Point2
Definition: Point2.h:32
EIGEN_DONT_INLINE Scalar zero()
Definition: svd_common.h:296
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:190
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
std::pair< std::shared_ptr< BayesNetType >, std::shared_ptr< FactorGraphType > > eliminatePartialSequential(const Ordering &ordering, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
const GaussianFactorGraph factors
MatrixXd L
Definition: LLT_example.cpp:6
Definition: BFloat16.h:88
Nonlinear Mixture factor of continuous and discrete.
NonlinearFactorGraph graph
static enum @1107 ordering
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
size_t size() const
Definition: FactorGraph.h:334
HybridGaussianFactorGraph linearizedFactorGraph
Definition: Switching.h:124
A conditional of gaussian mixtures indexed by discrete variables, as part of a Bayes Network...
#define THROWS_EXCEPTION(condition)
Definition: Test.h:112
Values result
GaussianFactorGraph::shared_ptr batchGFG(double between, Values linearizationPoint)
#define EXPECT(condition)
Definition: Test.h:150
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
size_t size() const
Definition: Values.h:178
std::shared_ptr< This > shared_ptr
shared_ptr to this class
NonlinearFactorGraph graph2()
traits
Definition: chartTesting.h:28
auto priorNoise
std::pair< HybridConditional::shared_ptr, std::shared_ptr< Factor > > EliminateHybrid(const HybridGaussianFactorGraph &factors, const Ordering &frontalKeys)
Main elimination function for HybridGaussianFactorGraph.
Eigen::Vector2d Vector2
Definition: Vector.h:42
virtual void resize(size_t size)
Definition: FactorGraph.h:389
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
Point2 f1(const Point3 &p, OptionalJacobian< 2, 3 > H)
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:343
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std::shared_ptr< HybridGaussianFactorGraph > linearize(const Values &continuousValues) const
Linearize all the continuous factors in the HybridNonlinearFactorGraph.
Chordal Bayes Net, the result of eliminating a factor graph.
void insert(Key j, const Value &val)
Definition: Values.cpp:155
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
Pose2 odometry(2.0, 0.0, 0.0)
Implementation of a discrete conditional mixture factor.
Definition: MixtureFactor.h:47
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
2D Pose
#define X
Definition: icosphere.cpp:20
TEST(HybridFactorGraph, GaussianFactorGraph)
double error(const HybridValues &values) const
std::shared_ptr< HybridBayesNet > shared_ptr
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:38:22