DiscreteMarginals.h
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 
21 #pragma once
22 
25 #include <gtsam/base/Vector.h>
26 
27 namespace gtsam {
28 
34 
35  protected:
36 
38 
39  public:
40 
42 
47  bayesTree_ = graph.eliminateMultifrontal();
48  }
49 
52  // Compute marginal
53  DiscreteFactor::shared_ptr marginalFactor;
54  marginalFactor = bayesTree_->marginalFactor(variable, &EliminateDiscrete);
55  return marginalFactor;
56  }
57 
63  // Compute marginal
64  DiscreteFactor::shared_ptr marginalFactor;
65  marginalFactor = bayesTree_->marginalFactor(key.first, &EliminateDiscrete);
66 
67  //Create result
68  Vector vResult(key.second);
69  for (size_t state = 0; state < key.second ; ++ state) {
71  values[key.first] = state;
72  vResult(state) = (*marginalFactor)(values);
73  }
74  return vResult;
75  }
76 
77  };
78 
79 } /* namespace gtsam */
const gtsam::Symbol key('X', 0)
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
Main elimination function for DiscreteFactorGraph.
leaf::MyValues values
NonlinearFactorGraph graph
Eigen::VectorXd Vector
Definition: Vector.h:38
DiscreteFactor::shared_ptr operator()(Key variable) const
DiscreteMarginals(const DiscreteFactorGraph &graph)
Vector marginalProbabilities(const DiscreteKey &key) const
Discrete Bayes Tree, the result of eliminating a DiscreteJunctionTree.
std::shared_ptr< DiscreteFactor > shared_ptr
shared_ptr to this class
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
std::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType={}, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex={}) const
std::shared_ptr< This > shared_ptr
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
DiscreteBayesTree::shared_ptr bayesTree_


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:10