DiscreteMarginals.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 
23 
24 namespace gtsam {
25 
26 /* ************************************************************************* */
28  bayesTree_ = graph.eliminateMultifrontal();
29 }
30 
31 /* ************************************************************************* */
33  // Compute marginal
34  DiscreteFactor::shared_ptr marginalFactor =
35  bayesTree_->marginalFactor(variable, &EliminateDiscrete);
36  return marginalFactor;
37 }
38 
39 /* ************************************************************************* */
41  // Compute marginal
42  DiscreteFactor::shared_ptr marginalFactor = this->operator()(key.first);
43 
44  // Create result
45  Vector vResult(key.second);
46  for (size_t state = 0; state < key.second; ++state) {
48  values[key.first] = state;
49  vResult(state) = (*marginalFactor)(values);
50  }
51  return vResult;
52 }
53 
54 /* ************************************************************************* */
55 void DiscreteMarginals::print(const std::string& s,
56  const KeyFormatter formatter) const {
57  std::cout << (s.empty() ? "Discrete Marginals of:" : s + " ") << std::endl;
58  bayesTree_->print("", formatter);
59 }
60 
61 } /* namespace gtsam */
gtsam::EliminateDiscrete
std::pair< DiscreteConditional::shared_ptr, DiscreteFactor::shared_ptr > EliminateDiscrete(const DiscreteFactorGraph &factors, const Ordering &frontalKeys)
Main elimination function for DiscreteFactorGraph.
Definition: DiscreteFactorGraph.cpp:202
gtsam::DiscreteMarginals::operator()
DiscreteFactor::shared_ptr operator()(Key variable) const
Definition: DiscreteMarginals.cpp:32
gtsam::DiscreteFactorGraph
Definition: DiscreteFactorGraph.h:99
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::DiscreteMarginals::DiscreteMarginals
DiscreteMarginals()
Definition: DiscreteMarginals.h:39
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:247
gtsam::DiscreteMarginals::bayesTree_
DiscreteBayesTree::shared_ptr bayesTree_
Definition: DiscreteMarginals.h:36
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::DiscreteMarginals::print
void print(const std::string &s="", const KeyFormatter formatter=DefaultKeyFormatter) const
Print details.
Definition: DiscreteMarginals.cpp:55
DiscreteMarginals.h
A class for computing marginals in a DiscreteFactorGraph.
key
const gtsam::Symbol key('X', 0)
gtsam
traits
Definition: ABC.h:17
gtsam::DiscreteFactor::shared_ptr
std::shared_ptr< DiscreteFactor > shared_ptr
shared_ptr to this class
Definition: DiscreteFactor.h:45
gtsam::DiscreteValues
Definition: DiscreteValues.h:34
gtsam::DiscreteKey
std::pair< Key, size_t > DiscreteKey
Definition: DiscreteKey.h:38
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::DiscreteMarginals::marginalProbabilities
Vector marginalProbabilities(const DiscreteKey &key) const
Definition: DiscreteMarginals.cpp:40
make_changelog.state
state
Definition: make_changelog.py:29


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:01:13