testHybridEstimation.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 #include <gtsam/geometry/Pose2.h>
21 #include <gtsam/geometry/Pose3.h>
28 #include <gtsam/inference/Symbol.h>
37 
38 // Include for test suite
40 
41 #include <string>
42 
43 #include "Switching.h"
44 
45 using namespace std;
46 using namespace gtsam;
47 
50 
51 namespace estimation_fixture {
52 std::vector<double> measurements = {0, 1, 2, 2, 2, 2, 3, 4, 5, 6, 6,
53  7, 8, 9, 9, 9, 10, 11, 11, 11, 11};
54 // Ground truth discrete seq
55 std::vector<size_t> discrete_seq = {1, 1, 0, 0, 0, 1, 1, 1, 1, 0,
56  1, 1, 1, 0, 0, 1, 1, 0, 0, 0};
57 
59  const size_t K, const double between_sigma, const double measurement_sigma,
60  const std::vector<double>& measurements,
61  const std::string& transitionProbabilityTable,
63  Switching switching(K, between_sigma, measurement_sigma, measurements,
64  transitionProbabilityTable);
65 
66  // Add prior on M(0)
68 
69  // Add the X(0) prior
71  initial.insert(X(0), switching.linearizationPoint.at<double>(X(0)));
72 
73  return switching;
74 }
75 
76 } // namespace estimation_fixture
77 
78 TEST(HybridEstimation, Full) {
79  size_t K = 6;
80  std::vector<double> measurements = {0, 1, 2, 2, 2, 3};
81  // Ground truth discrete seq
82  std::vector<size_t> discrete_seq = {1, 1, 0, 0, 1};
83  // Switching example of robot moving in 1D
84  // with given measurements and equal mode priors.
85  Switching switching(K, 1.0, 0.1, measurements, "1/1 1/1");
87 
88  Ordering hybridOrdering;
89  for (size_t k = 0; k < K; k++) {
90  hybridOrdering.push_back(X(k));
91  }
92  for (size_t k = 0; k < K - 1; k++) {
93  hybridOrdering.push_back(M(k));
94  }
95 
96  HybridBayesNet::shared_ptr bayesNet = graph.eliminateSequential();
97 
98  EXPECT_LONGS_EQUAL(2 * K - 1, bayesNet->size());
99 
100  HybridValues delta = bayesNet->optimize();
101 
103  Values result = initial.retract(delta.continuous());
104 
105  DiscreteValues expected_discrete;
106  for (size_t k = 0; k < K - 1; k++) {
107  expected_discrete[M(k)] = discrete_seq[k];
108  }
109  EXPECT(assert_equal(expected_discrete, delta.discrete()));
110 
111  Values expected_continuous;
112  for (size_t k = 0; k < K; k++) {
113  expected_continuous.insert(X(k), measurements[k]);
114  }
115  EXPECT(assert_equal(expected_continuous, result));
116 }
117 
118 /****************************************************************************/
119 // Test approximate inference with an additional pruning step.
120 TEST(HybridEstimation, ISAM) {
121  using namespace estimation_fixture;
122 
123  size_t K = 15;
124 
125  // Switching example of robot moving in 1D
126  // with given measurements and equal mode priors.
128  Values initial;
130  "1/1 1/1", graph, initial);
132 
133  HybridGaussianFactorGraph linearized;
134 
135  const size_t maxNrLeaves = 3;
136  for (size_t k = 1; k < K; k++) {
137  if (k > 1) graph.push_back(switching.modeChain.at(k - 1)); // Mode chain
138  graph.push_back(switching.binaryFactors.at(k - 1)); // Motion Model
139  graph.push_back(switching.unaryFactors.at(k)); // Measurement
140 
141  initial.insert(X(k), switching.linearizationPoint.at<double>(X(k)));
142 
143  isam.update(graph, initial, maxNrLeaves);
144  // isam.saveGraph("NLiSAM" + std::to_string(k) + ".dot");
145  // GTSAM_PRINT(isam);
146 
147  graph.resize(0);
148  initial.clear();
149  }
150 
152  DiscreteValues assignment = isam.assignment();
153 
154  DiscreteValues expected_discrete;
155  for (size_t k = 0; k < K - 1; k++) {
156  expected_discrete[M(k)] = discrete_seq[k];
157  }
158  EXPECT(assert_equal(expected_discrete, assignment));
159 
160  Values expected_continuous;
161  for (size_t k = 0; k < K; k++) {
162  expected_continuous.insert(X(k), measurements[k]);
163  }
164  EXPECT(assert_equal(expected_continuous, result));
165 }
166 
179  Ordering continuous(graph.continuousKeySet());
180  const auto [bayesNet, remainingGraph] =
181  graph.eliminatePartialSequential(continuous);
182 
183  auto last_conditional = bayesNet->at(bayesNet->size() - 1);
184  DiscreteKeys discrete_keys = last_conditional->discreteKeys();
185 
186  const std::vector<DiscreteValues> assignments =
187  DiscreteValues::CartesianProduct(discrete_keys);
188 
189  std::reverse(discrete_keys.begin(), discrete_keys.end());
190 
191  vector<VectorValues::shared_ptr> vector_values;
192  for (const DiscreteValues& assignment : assignments) {
193  VectorValues values = bayesNet->optimize(assignment);
194  vector_values.push_back(std::make_shared<VectorValues>(values));
195  }
196  DecisionTree<Key, VectorValues::shared_ptr> delta_tree(discrete_keys,
197  vector_values);
198 
199  // Get the probPrime tree with the correct leaf probabilities
200  std::vector<double> probPrimes;
201  for (const DiscreteValues& assignment : assignments) {
202  VectorValues delta = *delta_tree(assignment);
203 
204  // If VectorValues is empty, it means this is a pruned branch.
205  // Set the probPrime to 0.0.
206  if (delta.size() == 0) {
207  probPrimes.push_back(0.0);
208  continue;
209  }
210 
211  double error = graph.error({delta, assignment});
212  probPrimes.push_back(exp(-error));
213  }
214  AlgebraicDecisionTree<Key> probPrimeTree(discrete_keys, probPrimes);
215  return probPrimeTree;
216 }
217 
218 /*********************************************************************************
219  * Test for correctness of different branches of the P'(Continuous | Discrete).
220  * The values should match those of P'(Continuous) for each discrete mode.
221  ********************************************************************************/
222 TEST(HybridEstimation, Probability) {
223  using namespace estimation_fixture;
224 
225  constexpr size_t K = 4;
226  double between_sigma = 1.0, measurement_sigma = 0.1;
227 
228  // Switching example of robot moving in 1D with
229  // given measurements and equal mode priors.
230  Switching switching(K, between_sigma, measurement_sigma, measurements,
231  "1/1 1/1");
233 
234  // Continuous elimination
235  Ordering continuous_ordering(graph.continuousKeySet());
236  auto [bayesNet, discreteGraph] =
237  graph.eliminatePartialSequential(continuous_ordering);
238 
239  // Discrete elimination
240  Ordering discrete_ordering(graph.discreteKeySet());
241  auto discreteBayesNet = discreteGraph->eliminateSequential(discrete_ordering);
242 
243  // Add the discrete conditionals to make it a full bayes net.
244  for (auto discrete_conditional : *discreteBayesNet) {
245  bayesNet->add(discrete_conditional);
246  }
247 
248  HybridValues hybrid_values = bayesNet->optimize();
249 
250  // This is the correct sequence as designed
251  DiscreteValues expectedSequence{{M(0), 1}, {M(1), 1}, {M(2), 0}};
252  EXPECT(assert_equal(expectedSequence, hybrid_values.discrete()));
253 }
254 
255 /****************************************************************************/
261 TEST(HybridEstimation, ProbabilityMultifrontal) {
262  using namespace estimation_fixture;
263 
264  constexpr size_t K = 4;
265 
266  double between_sigma = 1.0, measurement_sigma = 0.1;
267 
268  // Switching example of robot moving in 1D with given measurements and equal
269  // mode priors.
270  Switching switching(K, between_sigma, measurement_sigma, measurements,
271  "1/1 1/1");
273 
274  // Get the tree of unnormalized probabilities for each mode sequence.
275  AlgebraicDecisionTree<Key> expected_probPrimeTree = GetProbPrimeTree(graph);
276 
277  // Eliminate continuous
278  Ordering continuous_ordering(graph.continuousKeySet());
279  const auto [bayesTree, discreteGraph] =
280  graph.eliminatePartialMultifrontal(continuous_ordering);
281 
282  // Get the last continuous conditional which will have all the discrete keys
283  Key last_continuous_key =
284  continuous_ordering.at(continuous_ordering.size() - 1);
285  auto last_conditional = (*bayesTree)[last_continuous_key]->conditional();
286  DiscreteKeys discrete_keys = last_conditional->discreteKeys();
287 
288  Ordering discrete(graph.discreteKeySet());
289  auto discreteBayesTree = discreteGraph->eliminateMultifrontal(discrete);
290 
291  EXPECT_LONGS_EQUAL(1, discreteBayesTree->size());
292  // DiscreteBayesTree should have only 1 clique
293  auto discrete_clique = (*discreteBayesTree)[discrete.at(0)];
294 
295  std::set<HybridBayesTreeClique::shared_ptr> clique_set;
296  for (auto node : bayesTree->nodes()) {
297  clique_set.insert(node.second);
298  }
299 
300  // Set the root of the bayes tree as the discrete clique
301  for (auto clique : clique_set) {
302  if (clique->conditional()->parents() ==
303  discrete_clique->conditional()->frontals()) {
304  discreteBayesTree->addClique(clique, discrete_clique);
305 
306  } else {
307  // Remove the clique from the children of the parents since
308  // it will get added again in addClique.
309  auto clique_it = std::find(clique->parent()->children.begin(),
310  clique->parent()->children.end(), clique);
311  clique->parent()->children.erase(clique_it);
312  discreteBayesTree->addClique(clique, clique->parent());
313  }
314  }
315 
316  HybridValues hybrid_values = discreteBayesTree->optimize();
317 
318  // This is the correct sequence as designed
319  DiscreteValues expectedSequence{{M(0), 1}, {M(1), 1}, {M(2), 0}};
320  EXPECT(assert_equal(expectedSequence, hybrid_values.discrete()));
321 }
322 
323 /*********************************************************************************
324  // Create a hybrid nonlinear factor graph f(x0, x1, m0; z0, z1)
325  ********************************************************************************/
328 
329  constexpr double sigma = 0.5; // measurement noise
330  const auto noise_model = noiseModel::Isotropic::Sigma(1, sigma);
331 
332  // Add "measurement" factors:
335 
336  // Add hybrid nonlinear factor:
337  DiscreteKey m(M(0), 2);
338  const auto zero_motion =
339  std::make_shared<BetweenFactor<double>>(X(0), X(1), 0, noise_model);
340  const auto one_motion =
341  std::make_shared<BetweenFactor<double>>(X(0), X(1), 1, noise_model);
342  std::vector<NoiseModelFactor::shared_ptr> components = {zero_motion,
343  one_motion};
345 
346  return nfg;
347 }
348 
349 /*********************************************************************************
350  // Create a hybrid linear factor graph f(x0, x1, m0; z0, z1)
351  ********************************************************************************/
354 
355  Values initial;
356  double z0 = 0.0, z1 = 1.0;
357  initial.insert<double>(X(0), z0);
358  initial.insert<double>(X(1), z1);
359  return nfg.linearize(initial);
360 }
361 
362 /*********************************************************************************
363  * Do hybrid elimination and do regression test on discrete conditional.
364  ********************************************************************************/
365 TEST(HybridEstimation, EliminateSequentialRegression) {
366  // Create the factor graph from the nonlinear factor graph.
368 
369  // Create expected discrete conditional on m0.
370  DiscreteKey m(M(0), 2);
371  TableDistribution expected(m, "0.51341712 1"); // regression
372 
373  // Eliminate into BN using one ordering
374  const Ordering ordering1{X(0), X(1), M(0)};
375  HybridBayesNet::shared_ptr bn1 = fg->eliminateSequential(ordering1);
376 
377  // Check that the discrete conditional matches the expected.
378  auto dc1 = bn1->back()->asDiscrete<TableDistribution>();
379  EXPECT(assert_equal(expected, *dc1, 1e-9));
380 
381  // Eliminate into BN using a different ordering
382  const Ordering ordering2{X(0), X(1), M(0)};
383  HybridBayesNet::shared_ptr bn2 = fg->eliminateSequential(ordering2);
384 
385  // Check that the discrete conditional matches the expected.
386  auto dc2 = bn2->back()->asDiscrete<TableDistribution>();
387  EXPECT(assert_equal(expected, *dc2, 1e-9));
388 }
389 
390 /*********************************************************************************
391  * Test for correctness via sampling.
392  *
393  * Compute the conditional P(x0, m0, x1| z0, z1)
394  * with measurements z0, z1. To do so, we:
395  * 1. Start with the corresponding Factor Graph `FG`.
396  * 2. Eliminate the factor graph into a Bayes Net `BN`.
397  * 3. Sample from the Bayes Net.
398  * 4. Check that the ratio `BN(x)/FG(x) = constant` for all samples `x`.
399  ********************************************************************************/
400 TEST(HybridEstimation, CorrectnessViaSampling) {
401  // 1. Create the factor graph from the nonlinear factor graph.
402  const auto fg = CreateHybridGaussianFactorGraph();
403 
404  // 2. Eliminate into BN
405  const HybridBayesNet::shared_ptr bn = fg->eliminateSequential();
406 
407  // Set up sampling
408  std::mt19937_64 rng(11);
409 
410  // Compute the log-ratio between the Bayes net and the factor graph.
411  auto compute_ratio = [&](const HybridValues& sample) -> double {
412  return bn->evaluate(sample) / fg->probPrime(sample);
413  };
414 
415  // The error evaluated by the factor graph and the Bayes net should differ by
416  // the normalizing term computed via the Bayes net determinant.
417  const HybridValues sample = bn->sample(&rng);
418  double expected_ratio = compute_ratio(sample);
419 
420  // 3. Do sampling
421  constexpr int num_samples = 10;
422  for (size_t i = 0; i < num_samples; i++) {
423  // Sample from the bayes net
424  const HybridValues sample = bn->sample(&rng);
425 
426  // 4. Check that the ratio is constant.
427  EXPECT_DOUBLES_EQUAL(expected_ratio, compute_ratio(sample), 1e-6);
428  }
429 }
430 
431 /****************************************************************************/
432 TEST(HybridEstimation, ModeSelection) {
434  Values initial;
435 
436  auto measurement_model = noiseModel::Isotropic::Sigma(1, 0.1);
437  auto motion_model = noiseModel::Isotropic::Sigma(1, 1.0);
438 
439  graph.emplace_shared<PriorFactor<double>>(X(0), 0.0, measurement_model);
440  graph.emplace_shared<PriorFactor<double>>(X(1), 0.0, measurement_model);
441 
442  // The size of the noise model
443  size_t d = 1;
444  double noise_tight = 0.5, noise_loose = 5.0;
445 
446  auto model0 = std::make_shared<MotionModel>(
447  X(0), X(1), 0.0, noiseModel::Isotropic::Sigma(d, noise_loose)),
448  model1 = std::make_shared<MotionModel>(
449  X(0), X(1), 0.0, noiseModel::Isotropic::Sigma(d, noise_tight));
450  std::vector<NoiseModelFactor::shared_ptr> components = {model0, model1};
451 
453 
454  initial.insert(X(0), 0.0);
455  initial.insert(X(1), 0.0);
456 
457  auto gmf = mf.linearize(initial);
458  graph.add(gmf);
459 
460  auto gfg = graph.linearize(initial);
461 
462  HybridBayesNet::shared_ptr bayesNet = gfg->eliminateSequential();
463 
464  HybridValues delta = bayesNet->optimize();
465  EXPECT_LONGS_EQUAL(1, delta.discrete().at(M(0)));
466 
467  /**************************************************************/
468  HybridBayesNet bn;
469  const DiscreteKey mode(M(0), 2);
470 
471  bn.push_back(
472  GaussianConditional::sharedMeanAndStddev(Z(0), -I_1x1, X(0), Z_1x1, 0.1));
473  bn.push_back(
474  GaussianConditional::sharedMeanAndStddev(Z(0), -I_1x1, X(1), Z_1x1, 0.1));
475 
476  std::vector<std::pair<Vector, double>> parameters{{Z_1x1, noise_loose},
477  {Z_1x1, noise_tight}};
478  bn.emplace_shared<HybridGaussianConditional>(mode, Z(0), I_1x1, X(0), -I_1x1,
479  X(1), parameters);
480 
482  vv.insert(Z(0), Z_1x1);
483 
484  auto fg = bn.toFactorGraph(vv);
485  auto expected_posterior = fg.eliminateSequential();
486 
487  EXPECT(assert_equal(*expected_posterior, *bayesNet, 1e-6));
488 }
489 
490 /****************************************************************************/
491 TEST(HybridEstimation, ModeSelection2) {
492  using symbol_shorthand::Z;
493 
494  // The size of the noise model
495  size_t d = 3;
496  double noise_tight = 0.5, noise_loose = 5.0;
497 
498  HybridBayesNet bn;
499  const DiscreteKey mode(M(0), 2);
500 
501  bn.push_back(
502  GaussianConditional::sharedMeanAndStddev(Z(0), -I_3x3, X(0), Z_3x1, 0.1));
503  bn.push_back(
504  GaussianConditional::sharedMeanAndStddev(Z(0), -I_3x3, X(1), Z_3x1, 0.1));
505 
506  std::vector<std::pair<Vector, double>> parameters{{Z_3x1, noise_loose},
507  {Z_3x1, noise_tight}};
508  bn.emplace_shared<HybridGaussianConditional>(mode, Z(0), I_3x3, X(0), -I_3x3,
509  X(1), parameters);
510 
512  vv.insert(Z(0), Z_3x1);
513 
514  auto fg = bn.toFactorGraph(vv);
515 
516  auto expected_posterior = fg.eliminateSequential();
517 
518  // =====================================
519 
521  Values initial;
522 
523  auto measurement_model = noiseModel::Isotropic::Sigma(d, 0.1);
524  auto motion_model = noiseModel::Isotropic::Sigma(d, 1.0);
525 
526  graph.emplace_shared<PriorFactor<Vector3>>(X(0), Z_3x1, measurement_model);
527  graph.emplace_shared<PriorFactor<Vector3>>(X(1), Z_3x1, measurement_model);
528 
529  auto model0 = std::make_shared<BetweenFactor<Vector3>>(
530  X(0), X(1), Z_3x1, noiseModel::Isotropic::Sigma(d, noise_loose)),
532  X(0), X(1), Z_3x1, noiseModel::Isotropic::Sigma(d, noise_tight));
533  std::vector<NoiseModelFactor::shared_ptr> components = {model0, model1};
534 
536 
537  initial.insert<Vector3>(X(0), Z_3x1);
538  initial.insert<Vector3>(X(1), Z_3x1);
539 
540  auto gmf = mf.linearize(initial);
541  graph.add(gmf);
542 
543  auto gfg = graph.linearize(initial);
544 
545  HybridBayesNet::shared_ptr bayesNet = gfg->eliminateSequential();
546 
547  EXPECT(assert_equal(*expected_posterior, *bayesNet, 1e-6));
548 }
549 
550 /* ************************************************************************* */
551 int main() {
552  TestResult tr;
553  return TestRegistry::runAllTests(tr);
554 }
555 /* ************************************************************************* */
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::HybridGaussianFactorGraph::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to This
Definition: HybridGaussianFactorGraph.h:120
gtsam::EliminateableFactorGraph::eliminateSequential
std::shared_ptr< BayesNetType > eliminateSequential(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
Definition: EliminateableFactorGraph-inst.h:29
switching3::switching
const Switching switching(3)
TableDistribution.h
Pose2.h
2D Pose
DiscreteBayesNet.h
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::HybridValues
Definition: HybridValues.h:37
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
asia::bayesNet
static const DiscreteBayesNet bayesNet
Definition: testDiscreteSearch.cpp:30
CreateHybridGaussianFactorGraph
static HybridGaussianFactorGraph::shared_ptr CreateHybridGaussianFactorGraph()
Definition: testHybridEstimation.cpp:352
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Z_3x1
static const Eigen::MatrixBase< Vector3 >::ConstantReturnType Z_3x1
Definition: Vector.h:47
HybridNonlinearFactorGraph.h
Nonlinear hybrid factor graph that uses type erasure.
main
int main()
Definition: testHybridEstimation.cpp:551
TestHarness.h
gtsam::HybridBayesNet
Definition: HybridBayesNet.h:37
gtsam::HybridNonlinearFactorGraph
Definition: HybridNonlinearFactorGraph.h:33
gtsam::VectorValues::insert
iterator insert(const std::pair< Key, Vector > &key_value)
Definition: VectorValues.cpp:90
z1
Point2 z1
Definition: testTriangulationFactor.cpp:45
initial
Values initial
Definition: OdometryOptimize.cpp:2
Switching.h
asia::bayesTree
static const DiscreteBayesTree bayesTree
Definition: testDiscreteSearch.cpp:40
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
HybridBayesNet.h
A Bayes net of Gaussian Conditionals indexed by discrete keys.
estimation_fixture::discrete_seq
std::vector< size_t > discrete_seq
Definition: testHybridEstimation.cpp:55
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:247
gtsam::BayesTree::nodes
const Nodes & nodes() const
Definition: BayesTree.h:147
gtsam::NonlinearFactorGraph::linearize
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Definition: NonlinearFactorGraph.cpp:239
X
#define X
Definition: icosphere.cpp:20
gtsam::DiscreteKeys
DiscreteKeys is a set of keys that can be assembled using the & operator.
Definition: DiscreteKey.h:41
GaussianBayesNet.h
Chordal Bayes Net, the result of eliminating a factor graph.
vv
static const VectorValues vv
Definition: testHybridGaussianConditional.cpp:45
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
exp
const EIGEN_DEVICE_FUNC ExpReturnType exp() const
Definition: ArrayCwiseUnaryOps.h:97
result
Values result
Definition: OdometryOptimize.cpp:8
HybridGaussianFactor.h
A set of GaussianFactors, indexed by a set of discrete keys.
test_motion::noise_model
auto noise_model
Definition: testHybridNonlinearFactorGraph.cpp:120
gtsam::Switching::linearizedFactorGraph
HybridGaussianFactorGraph linearizedFactorGraph() const
Get the full linear factor graph.
Definition: Switching.h:220
HybridSmoother.h
An incremental smoother for hybrid factor graphs.
GetProbPrimeTree
AlgebraicDecisionTree< Key > GetProbPrimeTree(const HybridGaussianFactorGraph &graph)
Helper method to get the tree of unnormalized probabilities as per the elimination scheme.
Definition: testHybridEstimation.cpp:177
gtsam::NonlinearISAM::update
void update(const NonlinearFactorGraph &newFactors, const Values &initialValues)
Definition: NonlinearISAM.cpp:35
sampling::sigma
static const double sigma
Definition: testGaussianBayesNet.cpp:170
gtsam::AlgebraicDecisionTree< Key >
gtsam::Switching
ϕ(X(0)) .. ϕ(X(k),X(k+1)) .. ϕ(X(k);z_k) .. ϕ(M(0)) .. ϕ(M(K-3),M(K-2))
Definition: Switching.h:124
gtsam::FactorGraph::at
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:306
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
PriorFactor.h
estimation_fixture::InitializeEstimationProblem
Switching InitializeEstimationProblem(const size_t K, const double between_sigma, const double measurement_sigma, const std::vector< double > &measurements, const std::string &transitionProbabilityTable, HybridNonlinearFactorGraph &graph, Values &initial)
Definition: testHybridEstimation.cpp:58
gtsam::FactorGraph::resize
virtual void resize(size_t size)
Definition: FactorGraph.h:367
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::VectorValues
Definition: VectorValues.h:74
BetweenFactor.h
gtsam::TableDistribution
Definition: TableDistribution.h:39
mode
static const DiscreteKey mode(modeKey, 2)
parameters
static ConjugateGradientParameters parameters
Definition: testIterative.cpp:33
isam
NonlinearISAM isam(relinearizeInterval)
gtsam::make_shared
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, std::shared_ptr< T > > make_shared(Args &&... args)
Definition: make_shared.h:56
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:916
gtsam::HybridGaussianConditional
A conditional of gaussian conditionals indexed by discrete variables, as part of a Bayes Network....
Definition: HybridGaussianConditional.h:55
gtsam::HybridGaussianFactorGraph
Definition: HybridGaussianFactorGraph.h:106
mf
Matrix2f mf
Definition: MatrixBase_cast.cpp:2
gtsam::HybridNonlinearISAM
Definition: HybridNonlinearISAM.h:29
gtsam::NonlinearISAM::estimate
Values estimate() const
Definition: NonlinearISAM.cpp:80
Symbol.h
estimation_fixture
Definition: testHybridEstimation.cpp:51
TEST
TEST(HybridEstimation, Full)
Definition: testHybridEstimation.cpp:78
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
CreateHybridNonlinearFactorGraph
static HybridNonlinearFactorGraph CreateHybridNonlinearFactorGraph()
Definition: testHybridEstimation.cpp:326
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
TestResult
Definition: TestResult.h:26
JacobianFactor.h
estimation_fixture::measurements
std::vector< double > measurements
Definition: testHybridEstimation.cpp:52
gtsam::FactorGraph::size
size_t size() const
Definition: FactorGraph.h:297
gtsam::DecisionTree
a decision tree is a function from assignments to values.
Definition: DecisionTree.h:62
HybridNonlinearFactor.h
A set of nonlinear factors indexed by a set of discrete keys.
gtsam::HybridBayesNet::push_back
void push_back(std::shared_ptr< HybridConditional > conditional)
Add a hybrid conditional using a shared_ptr.
Definition: HybridBayesNet.h:76
gtsam::DiscreteBayesNet::add
void add(const DiscreteKey &key, const std::string &spec)
Definition: DiscreteBayesNet.h:85
gtsam::Switching::modeChain
HybridNonlinearFactorGraph modeChain
Definition: Switching.h:128
gtsam
traits
Definition: SFMdata.h:40
error
static double error
Definition: testRot3.cpp:37
NoiseModel.h
K
#define K
Definition: igam.h:8
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std
Definition: BFloat16.h:88
gtsam::Switching::linearizationPoint
Values linearizationPoint
Definition: Switching.h:130
gtsam::HybridValues::discrete
const DiscreteValues & discrete() const
Return the discrete values.
Definition: HybridValues.cpp:57
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:156
gtsam::HybridNonlinearFactorGraph::linearize
std::shared_ptr< HybridGaussianFactorGraph > linearize(const Values &continuousValues) const
Linearize all the continuous factors in the HybridNonlinearFactorGraph.
Definition: HybridNonlinearFactorGraph.cpp:139
GaussianBayesTree.h
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
HybridNonlinearISAM.h
initial
Definition: testScenarioRunner.cpp:148
gtsam::ISAM
Definition: ISAM.h:31
reverse
void reverse(const MatrixType &m)
Definition: array_reverse.cpp:16
test_motion::components
std::vector< NoiseModelFactor::shared_ptr > components
Definition: testHybridNonlinearFactorGraph.cpp:121
gtsam::HybridBayesNet::shared_ptr
std::shared_ptr< HybridBayesNet > shared_ptr
Definition: HybridBayesNet.h:42
gtsam::Switching::binaryFactors
HybridNonlinearFactorGraph binaryFactors
Definition: Switching.h:128
gtsam::HybridBayesNet::toFactorGraph
HybridGaussianFactorGraph toFactorGraph(const VectorValues &measurements) const
Definition: HybridBayesNet.cpp:270
gtsam::FactorGraph::add
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
Definition: FactorGraph.h:171
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
model1
noiseModel::Isotropic::shared_ptr model1
Definition: testEssentialMatrixFactor.cpp:26
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
Z
#define Z
Definition: icosphere.cpp:21
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::Switching::unaryFactors
HybridNonlinearFactorGraph unaryFactors
Definition: Switching.h:128
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::HybridNonlinearFactor
Implementation of a discrete-conditioned hybrid factor.
Definition: HybridNonlinearFactor.h:58
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::HybridBayesNet::emplace_shared
void emplace_shared(Args &&...args)
Definition: HybridBayesNet.h:116
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:06:50