Marginals.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 
19 #include <gtsam/base/timing.h>
23 
24 using namespace std;
25 
26 namespace gtsam {
27 
28 /* ************************************************************************* */
29 Marginals::Marginals(const NonlinearFactorGraph& graph, const Values& solution, Factorization factorization)
30  : values_(solution), factorization_(factorization) {
31  gttic(MarginalsConstructor);
32  graph_ = *graph.linearize(solution);
34 }
35 
36 /* ************************************************************************* */
38  Factorization factorization)
39  : values_(solution), factorization_(factorization) {
40  gttic(MarginalsConstructor);
41  graph_ = *graph.linearize(solution);
42  computeBayesTree(ordering);
43 }
44 
45 /* ************************************************************************* */
46 Marginals::Marginals(const GaussianFactorGraph& graph, const Values& solution, Factorization factorization)
47  : graph_(graph), values_(solution), factorization_(factorization) {
48  gttic(MarginalsConstructor);
50 }
51 
52 /* ************************************************************************* */
54  Factorization factorization)
55  : graph_(graph), values_(solution), factorization_(factorization) {
56  gttic(MarginalsConstructor);
57  computeBayesTree(ordering);
58 }
59 
60 /* ************************************************************************* */
62  : graph_(graph), factorization_(factorization) {
63  gttic(MarginalsConstructor);
64  for (const auto& keyValue: solution) {
65  values_.insert(keyValue.first, keyValue.second);
66  }
68 }
69 
70 /* ************************************************************************* */
72  Factorization factorization)
73  : graph_(graph), factorization_(factorization) {
74  gttic(MarginalsConstructor);
75  for (const auto& keyValue: solution) {
76  values_.insert(keyValue.first, keyValue.second);
77  }
78  computeBayesTree(ordering);
79 }
80 
81 /* ************************************************************************* */
83  // Compute BayesTree
86  else if(factorization_ == QR)
88 }
89 
90 /* ************************************************************************* */
92  // Compute BayesTree
95  else if(factorization_ == QR)
97 }
98 
99 /* ************************************************************************* */
100 void Marginals::print(const std::string& str, const KeyFormatter& keyFormatter) const
101 {
102  graph_.print(str+"Graph: ");
103  values_.print(str+"Solution: ", keyFormatter);
104  bayesTree_.print(str+"Bayes Tree: ");
105 }
106 
107 /* ************************************************************************* */
110 
111  // Compute marginal factor
112  if(factorization_ == CHOLESKY)
114  else if(factorization_ == QR)
115  return bayesTree_.marginalFactor(variable, EliminateQR);
116  else
117  throw std::runtime_error("Marginals::marginalFactor: Unknown factorization");
118 }
119 
120 /* ************************************************************************* */
122 
123  // Get information matrix (only store upper-right triangle)
125  return marginalFactor(variable)->information();
126 }
127 
128 /* ************************************************************************* */
130  return marginalInformation(variable).inverse();
131 }
132 
133 /* ************************************************************************* */
137  return info;
138 }
139 
140 /* ************************************************************************* */
142 
143  // If 2 variables, we can use the BayesTree::joint function, otherwise we
144  // have to use sequential elimination.
145  if(variables.size() == 1)
146  {
147  Matrix info = marginalInformation(variables.front());
148  std::vector<size_t> dims;
149  dims.push_back(info.rows());
150  return JointMarginal(info, dims, variables);
151  }
152  else
153  {
154  // Compute joint marginal factor graph.
155  GaussianFactorGraph jointFG;
156  if(variables.size() == 2) {
157  if(factorization_ == CHOLESKY)
158  jointFG = *bayesTree_.joint(variables[0], variables[1], EliminatePreferCholesky);
159  else if(factorization_ == QR)
160  jointFG = *bayesTree_.joint(variables[0], variables[1], EliminateQR);
161  } else {
162  if(factorization_ == CHOLESKY)
164  else if(factorization_ == QR)
166  }
167 
168  // Get information matrix
169  Matrix augmentedInfo = jointFG.augmentedHessian();
170  Matrix info = augmentedInfo.topLeftCorner(augmentedInfo.rows()-1, augmentedInfo.cols()-1);
171 
172  // Information matrix will be returned with sorted keys
173  KeyVector variablesSorted = variables;
174  std::sort(variablesSorted.begin(), variablesSorted.end());
175 
176  // Get dimensions from factor graph
177  std::vector<size_t> dims;
178  dims.reserve(variablesSorted.size());
179  for(const auto& key: variablesSorted) {
180  dims.push_back(values_.at(key).dim());
181  }
182 
183  return JointMarginal(info, dims, variablesSorted);
184  }
185 }
186 
187 /* ************************************************************************* */
189  return bayesTree_.optimize();
190 }
191 
192 /* ************************************************************************* */
193 void JointMarginal::print(const std::string& s, const KeyFormatter& formatter) const {
194  cout << s << "Joint marginal on keys ";
195  bool first = true;
196  for(const auto& key: keys_) {
197  if(!first)
198  cout << ", ";
199  else
200  first = false;
201  cout << formatter(key);
202  }
203  cout << ". Use 'at' or 'operator()' to query matrix blocks." << endl;
204 }
205 
206 } /* namespace gtsam */
void computeBayesTree()
Definition: Marginals.cpp:82
GaussianFactorGraph graph_
Definition: Marginals.h:44
void insert(Key j, const Value &val)
Definition: Values.cpp:140
static enum @843 ordering
boost::shared_ptr< BayesTreeType > eliminateMultifrontal(OptionalOrderingType orderingType=boost::none, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
boost::shared_ptr< BayesTreeType > marginalMultifrontalBayesTree(boost::variant< const Ordering &, const KeyVector & > variables, const Eliminate &function=EliminationTraitsType::DefaultEliminate, OptionalVariableIndex variableIndex=boost::none) const
JointMarginal jointMarginalCovariance(const KeyVector &variables) const
Definition: Marginals.cpp:134
Definition: Half.h:150
NonlinearFactorGraph graph
Values values_
Definition: Marginals.h:45
std::pair< boost::shared_ptr< GaussianConditional >, boost::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
const KeyFormatter & formatter
VectorValues optimize() const
Definition: Marginals.cpp:188
sharedConditional marginalFactor(Key j, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
void invertInPlace()
Invert the entire active matrix in place.
else if n * info
#define gttic(label)
Definition: timing.h:280
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
GaussianBayesTree bayesTree_
Definition: Marginals.h:47
constexpr int first(int i)
Implementation details for constexpr functions.
SymmetricBlockMatrix blockMatrix_
Definition: Marginals.h:154
const ValueType at(Key j) const
Definition: Values-inl.h:342
Definition: pytypes.h:928
Marginals()
Default constructor only for wrappers.
Definition: Marginals.h:52
JointMarginal jointMarginalInformation(const KeyVector &variables) const
Definition: Marginals.cpp:141
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
Matrix augmentedHessian(const Ordering &ordering) const
Contains the HessianFactor class, a general quadratic factor.
RealScalar s
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
traits
Definition: chartTesting.h:28
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
virtual void print(const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const
print out graph
Factorization factorization_
Definition: Marginals.h:46
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const
Definition: Marginals.cpp:193
Matrix marginalCovariance(Key variable) const
Definition: Marginals.cpp:129
VectorValues optimize() const
A class for computing marginals in a NonlinearFactorGraph.
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
GaussianFactor::shared_ptr marginalFactor(Key variable) const
Definition: Marginals.cpp:108
void print(const std::string &str="Marginals: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Marginals.cpp:100
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Timing utilities.
sharedFactorGraph joint(Key j1, Key j2, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Matrix marginalInformation(Key variable) const
Definition: Marginals.cpp:121


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:45