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 
33 
34  protected:
35 
37 
38  public:
39 
44  bayesTree_ = graph.eliminateMultifrontal();
45  }
46 
49  // Compute marginal
50  DiscreteFactor::shared_ptr marginalFactor;
51  marginalFactor = bayesTree_->marginalFactor(variable, &EliminateDiscrete);
52  return marginalFactor;
53  }
54 
60  // Compute marginal
61  DiscreteFactor::shared_ptr marginalFactor;
62  marginalFactor = bayesTree_->marginalFactor(key.first, &EliminateDiscrete);
63 
64  //Create result
65  Vector vResult(key.second);
66  for (size_t state = 0; state < key.second ; ++ state) {
68  values[key.first] = state;
69  vResult(state) = (*marginalFactor)(values);
70  }
71  return vResult;
72  }
73 
74  };
75 
76 } /* namespace gtsam */
Vector marginalProbabilities(const DiscreteKey &key) const
boost::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
leaf::MyValues values
NonlinearFactorGraph graph
Eigen::VectorXd Vector
Definition: Vector.h:38
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:34
DiscreteMarginals(const DiscreteFactorGraph &graph)
Discrete Bayes Tree, the result of eliminating a DiscreteJunctionTree.
std::pair< DiscreteConditional::shared_ptr, DecisionTreeFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
boost::shared_ptr< DiscreteFactor > shared_ptr
shared_ptr to this class
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
boost::shared_ptr< This > shared_ptr
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
DiscreteFactor::shared_ptr operator()(Key variable) const
DiscreteBayesTree::shared_ptr bayesTree_


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:59