BayesTree-inst.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 
26 #include <gtsam/base/timing.h>
27 
28 #include <fstream>
29 #include <queue>
30 #include <cassert>
31 #include <unordered_set>
32 
33 namespace gtsam {
34 
35  /* ************************************************************************* */
36  template<class CLIQUE>
39  for (const sharedClique& root : roots_) getCliqueData(root, &stats);
40  return stats;
41  }
42 
43  /* ************************************************************************* */
44  template <class CLIQUE>
46  BayesTreeCliqueData* stats) const {
47  const auto conditional = clique->conditional();
48  stats->conditionalSizes.push_back(conditional->nrFrontals());
49  stats->separatorSizes.push_back(conditional->nrParents());
50  for (sharedClique c : clique->children) {
51  getCliqueData(c, stats);
52  }
53  }
54 
55  /* ************************************************************************* */
56  template<class CLIQUE>
58  size_t count = 0;
59  for(const sharedClique& root: roots_)
60  count += root->numCachedSeparatorMarginals();
61  return count;
62  }
63 
64  /* ************************************************************************* */
65  template <class CLIQUE>
66  void BayesTree<CLIQUE>::dot(std::ostream& os,
67  const KeyFormatter& keyFormatter) const {
68  if (roots_.empty())
69  throw std::invalid_argument(
70  "the root of Bayes tree has not been initialized!");
71  os << "digraph G{\n";
72  for (const sharedClique& root : roots_) dot(os, root, keyFormatter);
73  os << "}";
74  std::flush(os);
75  }
76 
77  /* ************************************************************************* */
78  template <class CLIQUE>
79  std::string BayesTree<CLIQUE>::dot(const KeyFormatter& keyFormatter) const {
80  std::stringstream ss;
81  dot(ss, keyFormatter);
82  return ss.str();
83  }
84 
85  /* ************************************************************************* */
86  template <class CLIQUE>
87  void BayesTree<CLIQUE>::saveGraph(const std::string& filename,
88  const KeyFormatter& keyFormatter) const {
89  std::ofstream of(filename.c_str());
90  dot(of, keyFormatter);
91  of.close();
92  }
93 
94  /* ************************************************************************* */
95  template <class CLIQUE>
96  void BayesTree<CLIQUE>::dot(std::ostream& s, sharedClique clique,
97  const KeyFormatter& keyFormatter,
98  int parentnum) const {
99  static int num = 0;
100  bool first = true;
101  std::stringstream out;
102  out << num;
103  std::string parent = out.str();
104  parent += "[label=\"";
105 
106  for (Key key : clique->conditional_->frontals()) {
107  if (!first) parent += ", ";
108  first = false;
109  parent += keyFormatter(key);
110  }
111 
112  if (clique->parent()) {
113  parent += " : ";
114  s << parentnum << "->" << num << "\n";
115  }
116 
117  first = true;
118  for (Key parentKey : clique->conditional_->parents()) {
119  if (!first) parent += ", ";
120  first = false;
121  parent += keyFormatter(parentKey);
122  }
123  parent += "\"];\n";
124  s << parent;
125  parentnum = num;
126 
127  for (sharedClique c : clique->children) {
128  num++;
129  dot(s, c, keyFormatter, parentnum);
130  }
131  }
132 
133  /* ************************************************************************* */
134  template<class CLIQUE>
135  size_t BayesTree<CLIQUE>::size() const {
136  size_t size = 0;
137  for(const sharedClique& clique: roots_)
138  size += clique->treeSize();
139  return size;
140  }
141 
142  /* ************************************************************************* */
143  template<class CLIQUE>
144  void BayesTree<CLIQUE>::addClique(const sharedClique& clique, const sharedClique& parent_clique) {
145  for(Key j: clique->conditional()->frontals())
146  nodes_[j] = clique;
147  if (parent_clique != nullptr) {
148  clique->parent_ = parent_clique;
149  parent_clique->children.push_back(clique);
150  } else {
151  roots_.push_back(clique);
152  }
153  }
154 
155  /* ************************************************************************* */
156  namespace {
157  template <class FACTOR, class CLIQUE>
158  struct _pushCliqueFunctor {
159  _pushCliqueFunctor(FactorGraph<FACTOR>* graph_) : graph(graph_) {}
160  FactorGraph<FACTOR>* graph;
161  int operator()(const std::shared_ptr<CLIQUE>& clique, int dummy) {
162  graph->push_back(clique->conditional_);
163  return 0;
164  }
165  };
166  } // namespace
167 
168  /* ************************************************************************* */
169  template <class CLIQUE>
171  FactorGraph<FactorType>* graph) const {
172  // Traverse the BayesTree and add all conditionals to this graph
173  int data = 0; // Unused
174  _pushCliqueFunctor<FactorType, CLIQUE> functor(graph);
175  treeTraversal::DepthFirstForest(*this, data, functor);
176  }
177 
178  /* ************************************************************************* */
179  template<class CLIQUE>
181  *this = other;
182  }
183 
184  /* ************************************************************************* */
185 
191  template<class CLIQUE>
193  /* Because tree nodes are hold by both root_ and nodes_, we need to clear nodes_ manually first and
194  * reduce the reference count of each node by 1. Otherwise, the nodes will not be properly deleted
195  * during the BFS process.
196  */
197  nodes_.clear();
198  for (auto&& root: roots_) {
199  std::queue<sharedClique> bfs_queue;
200 
201  // first, steal the root and move it to the queue. This invalidates root
202  bfs_queue.push(std::move(root));
203 
204  // do a BFS on the tree, for each node, add its children to the queue, and then delete it from the queue
205  // So if the reference count of the node is 1, it will be deleted, and because its children are in the queue,
206  // the deletion of the node will not trigger a recursive deletion of the children.
207  while (!bfs_queue.empty()) {
208  // move the ownership of the front node from the queue to the current variable, invalidating the sharedClique at the front of the queue
209  auto current = std::move(bfs_queue.front());
210  bfs_queue.pop();
211 
212  // add the children of the current node to the queue, so that the queue will also own the children nodes.
213  for (auto child: current->children) {
214  bfs_queue.push(std::move(child));
215  } // leaving the scope of current will decrease the reference count of the current node by 1, and if the reference count is 0,
216  // the node will be deleted. Because the children are in the queue, the deletion of the node will not trigger a recursive
217  // deletion of the children.
218  }
219  }
220  }
221 
222  /* ************************************************************************* */
223  namespace {
224  template<typename NODE>
225  std::shared_ptr<NODE>
226  BayesTreeCloneForestVisitorPre(const std::shared_ptr<NODE>& node, const std::shared_ptr<NODE>& parentPointer)
227  {
228  // Clone the current node and add it to its cloned parent
229  std::shared_ptr<NODE> clone = std::make_shared<NODE>(*node);
230  clone->children.clear();
231  clone->parent_ = parentPointer;
232  parentPointer->children.push_back(clone);
233  return clone;
234  }
235  }
236 
237  /* ************************************************************************* */
238  template<class CLIQUE>
240  this->clear();
241  std::shared_ptr<Clique> rootContainer = std::make_shared<Clique>();
242  treeTraversal::DepthFirstForest(other, rootContainer, BayesTreeCloneForestVisitorPre<Clique>);
243  for(const sharedClique& root: rootContainer->children) {
244  root->parent_ = typename Clique::weak_ptr(); // Reset the parent since it's set to the dummy clique
245  insertRoot(root);
246  }
247  return *this;
248  }
249 
250  /* ************************************************************************* */
251  template<class CLIQUE>
252  void BayesTree<CLIQUE>::print(const std::string& s, const KeyFormatter& keyFormatter) const {
253  std::cout << s << ": cliques: " << size() << ", variables: " << nodes_.size() << std::endl;
254  treeTraversal::PrintForest(*this, s, keyFormatter);
255  }
256 
257  /* ************************************************************************* */
258  // binary predicate to test equality of a pair for use in equals
259  template<class CLIQUE>
261  const std::pair<Key, typename BayesTree<CLIQUE>::sharedClique>& v1,
262  const std::pair<Key, typename BayesTree<CLIQUE>::sharedClique>& v2
263  ) {
264  return v1.first == v2.first &&
265  ((!v1.second && !v2.second) || (v1.second && v2.second && v1.second->equals(*v2.second)));
266  }
267 
268  /* ************************************************************************* */
269  template<class CLIQUE>
271  return size()==other.size() &&
272  std::equal(nodes_.begin(), nodes_.end(), other.nodes_.begin(), &check_sharedCliques<CLIQUE>);
273  }
274 
275  /* ************************************************************************* */
276  template<class CLIQUE>
277  template<class CONTAINER>
278  Key BayesTree<CLIQUE>::findParentClique(const CONTAINER& parents) const {
279  typename CONTAINER::const_iterator lowestOrderedParent = min_element(parents.begin(), parents.end());
280  assert(lowestOrderedParent != parents.end());
281  return *lowestOrderedParent;
282  }
283 
284  /* ************************************************************************* */
285  template<class CLIQUE>
287  // Add each frontal variable of this root node
288  for(const Key& j: subtree->conditional()->frontals()) {
289  bool inserted = nodes_.insert({j, subtree}).second;
290  assert(inserted); (void)inserted;
291  }
292  // Fill index for each child
294  for(const sharedClique& child: subtree->children) {
295  fillNodesIndex(child); }
296  }
297 
298  /* ************************************************************************* */
299  template<class CLIQUE>
301  roots_.push_back(subtree); // Add to roots
302  fillNodesIndex(subtree); // Populate nodes index
303  }
304 
305  /* ************************************************************************* */
306  // First finds clique marginal then marginalizes that
307  /* ************************************************************************* */
308  template<class CLIQUE>
311  {
312  gttic(BayesTree_marginalFactor);
313 
314  // get clique containing Key j
315  sharedClique clique = this->clique(j);
316 
317  // calculate or retrieve its marginal P(C) = P(F,S)
318  FactorGraphType cliqueMarginal = clique->marginal2(function);
319 
320  // Now, marginalize out everything that is not variable j
321  BayesNetType marginalBN =
322  *cliqueMarginal.marginalMultifrontalBayesNet(Ordering{j}, function);
323 
324  // The Bayes net should contain only one conditional for variable j, so return it
325  return marginalBN.front();
326  }
327 
328  /* ************************************************************************* */
329  // Find two cliques, their joint, then marginalizes
330  /* ************************************************************************* */
331  template<class CLIQUE>
333  BayesTree<CLIQUE>::joint(Key j1, Key j2, const Eliminate& function) const
334  {
335  gttic(BayesTree_joint);
336  return std::make_shared<FactorGraphType>(*jointBayesNet(j1, j2, function));
337  }
338 
339  /* ************************************************************************* */
340  // Find the lowest common ancestor of two cliques
341  // TODO(Varun): consider implementing this as a Range Minimum Query
342  template <class CLIQUE>
343  static std::shared_ptr<CLIQUE> findLowestCommonAncestor(
344  const std::shared_ptr<CLIQUE>& C1, const std::shared_ptr<CLIQUE>& C2) {
345  // Collect all ancestors of C1
346  std::unordered_set<std::shared_ptr<CLIQUE>> ancestors;
347  for (auto p = C1; p; p = p->parent()) {
348  ancestors.insert(p);
349  }
350 
351  // Find the first common ancestor in C2's lineage
352  std::shared_ptr<CLIQUE> B;
353  for (auto p = C2; p; p = p->parent()) {
354  if (ancestors.count(p)) {
355  return p; // Return the common ancestor when found
356  }
357  }
358 
359  return nullptr; // Return nullptr if no common ancestor is found
360  }
361 
362  /* ************************************************************************* */
363  // Given the clique P(F:S) and the ancestor clique B
364  // Return the Bayes tree P(S\B | S \cap B), where \cap is intersection
365  template <class CLIQUE>
366  static auto factorInto(
367  const std::shared_ptr<CLIQUE>& p_F_S, const std::shared_ptr<CLIQUE>& B,
368  const typename CLIQUE::FactorGraphType::Eliminate& eliminate) {
369  gttic(Full_root_factoring);
370 
371  // Get the shortcut P(S|B)
372  auto p_S_B = p_F_S->shortcut(B, eliminate);
373 
374  // Compute S\B
375  KeyVector S_setminus_B = p_F_S->separator_setminus_B(B);
376 
377  // Factor P(S|B) into P(S\B|S \cap B) and P(S \cap B)
378  auto [bayesTree, fg] =
379  typename CLIQUE::FactorGraphType(p_S_B).eliminatePartialMultifrontal(
380  Ordering(S_setminus_B), eliminate);
381  return bayesTree;
382  }
383 
384  /* ************************************************************************* */
385  template <class CLIQUE>
387  Key j1, Key j2, const Eliminate& eliminate) const {
388  gttic(BayesTree_jointBayesNet);
389  // get clique C1 and C2
390  sharedClique C1 = (*this)[j1], C2 = (*this)[j2];
391 
392  // Find the lowest common ancestor clique
393  auto B = findLowestCommonAncestor(C1, C2);
394 
395  // Build joint on all involved variables
396  FactorGraphType p_BC1C2;
397 
398  if (B) {
399  // Compute marginal on lowest common ancestor clique
400  FactorGraphType p_B = B->marginal2(eliminate);
401 
402  // Factor the shortcuts to be conditioned on lowest common ancestor
403  auto p_C1_B = factorInto(C1, B, eliminate);
404  auto p_C2_B = factorInto(C2, B, eliminate);
405 
406  p_BC1C2.push_back(p_B);
407  p_BC1C2.push_back(*p_C1_B);
408  p_BC1C2.push_back(*p_C2_B);
409  if (C1 != B) p_BC1C2.push_back(C1->conditional());
410  if (C2 != B) p_BC1C2.push_back(C2->conditional());
411  } else {
412  // The nodes have no common ancestor, they're in different trees, so
413  // they're joint is just the product of their marginals.
414  p_BC1C2.push_back(C1->marginal2(eliminate));
415  p_BC1C2.push_back(C2->marginal2(eliminate));
416  }
417 
418  // now, marginalize out everything that is not variable j1 or j2
419  return p_BC1C2.marginalMultifrontalBayesNet(Ordering{j1, j2}, eliminate);
420  }
421 
422  /* ************************************************************************* */
423  template<class CLIQUE>
425  // Remove all nodes and clear the root pointer
426  nodes_.clear();
427  roots_.clear();
428  }
429 
430  /* ************************************************************************* */
431  template<class CLIQUE>
433  for(const sharedClique& root: roots_) {
434  root->deleteCachedShortcuts();
435  }
436  }
437 
438  /* ************************************************************************* */
439  template<class CLIQUE>
441  {
442  if (clique->isRoot()) {
443  typename Roots::iterator root = std::find(roots_.begin(), roots_.end(), clique);
444  if(root != roots_.end())
445  roots_.erase(root);
446  } else { // detach clique from parent
447  sharedClique parent = clique->parent_.lock();
448  typename Roots::iterator child = std::find(parent->children.begin(), parent->children.end(), clique);
449  assert(child != parent->children.end());
450  parent->children.erase(child);
451  }
452 
453  // orphan my children
454  for(sharedClique child: clique->children)
455  child->parent_ = typename Clique::weak_ptr();
456 
457  for(Key j: clique->conditional()->frontals()) {
458  nodes_.unsafe_erase(j);
459  }
460  }
461 
462  /* ************************************************************************* */
463  template <class CLIQUE>
465  Cliques* orphans) {
466  // base case is nullptr, if so we do nothing and return empties above
467  if (clique) {
468  // remove the clique from orphans in case it has been added earlier
469  orphans->remove(clique);
470 
471  // remove me
472  this->removeClique(clique);
473 
474  // remove path above me
475  this->removePath(typename Clique::shared_ptr(clique->parent_.lock()), bn,
476  orphans);
477 
478  // add children to list of orphans (splice also removed them from
479  // clique->children_)
480  orphans->insert(orphans->begin(), clique->children.begin(),
481  clique->children.end());
482  clique->children.clear();
483 
484  bn->push_back(clique->conditional_);
485  }
486  }
487 
488  /* *************************************************************************
489  */
490  template <class CLIQUE>
492  Cliques* orphans) {
493  gttic(removetop);
494  // process each key of the new factor
495  for (const Key& j : keys) {
496  // get the clique
497  // TODO(frank): Nodes will be searched again in removeClique
498  typename Nodes::const_iterator node = nodes_.find(j);
499  if (node != nodes_.end()) {
500  // remove path from clique to root
501  this->removePath(node->second, bn, orphans);
502  }
503  }
504 
505  // Delete cachedShortcuts for each orphan subtree
506  // TODO(frank): Consider Improving
507  for (sharedClique& orphan : *orphans) orphan->deleteCachedShortcuts();
508  }
509 
510  /* ************************************************************************* */
511  template<class CLIQUE>
513  const sharedClique& subtree)
514  {
515  // Result clique list
516  Cliques cliques;
517  cliques.push_back(subtree);
518 
519  // Remove the first clique from its parents
520  if(!subtree->isRoot())
521  subtree->parent()->children.erase(std::find(
522  subtree->parent()->children.begin(), subtree->parent()->children.end(), subtree));
523  else
524  roots_.erase(std::find(roots_.begin(), roots_.end(), subtree));
525 
526  // Add all subtree cliques and erase the children and parent of each
527  for(typename Cliques::iterator clique = cliques.begin(); clique != cliques.end(); ++clique)
528  {
529  // Add children
530  for(const sharedClique& child: (*clique)->children) {
531  cliques.push_back(child); }
532 
533  // Delete cached shortcuts
534  (*clique)->deleteCachedShortcutsNonRecursive();
535 
536  // Remove this node from the nodes index
537  for(Key j: (*clique)->conditional()->frontals()) {
538  nodes_.unsafe_erase(j); }
539 
540  // Erase the parent and children pointers
541  (*clique)->parent_.reset();
542  (*clique)->children.clear();
543  }
544 
545  return cliques;
546  }
547 
548 }
timing.h
Timing utilities.
gtsam::BayesTree::insertRoot
void insertRoot(const sharedClique &subtree)
Definition: BayesTree-inst.h:300
gtsam::HybridBayesTreeClique::weak_ptr
std::weak_ptr< This > weak_ptr
Definition: HybridBayesTree.h:52
gtsam::HybridBayesTreeClique::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: HybridBayesTree.h:51
gtsam::BayesTree< HybridBayesTreeClique >::FactorGraphType
HybridBayesTreeClique ::FactorGraphType FactorGraphType
Definition: BayesTree.h:83
treeTraversal-inst.h
gtsam::BayesTree::fillNodesIndex
void fillNodesIndex(const sharedClique &subtree)
Definition: BayesTree-inst.h:286
gtsam::BayesTree< HybridBayesTreeClique >::Eliminate
FactorGraphType::Eliminate Eliminate
Definition: BayesTree.h:85
gtsam::BayesTree::~BayesTree
~BayesTree()
Definition: BayesTree-inst.h:192
s
RealScalar s
Definition: level1_cplx_impl.h:126
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::BayesTree::addFactorsToGraph
void addFactorsToGraph(FactorGraph< FactorType > *graph) const
Definition: BayesTree-inst.h:170
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
BayesTree.h
Bayes Tree is a tree of cliques of a Bayes Chain.
gtsam::BayesTree::getCliqueData
BayesTreeCliqueData getCliqueData() const
Definition: BayesTree-inst.h:37
B
Definition: test_numpy_dtypes.cpp:301
asia::bayesTree
static const DiscreteBayesTree bayesTree
Definition: testDiscreteSearch.cpp:40
gtsam::findLowestCommonAncestor
static std::shared_ptr< CLIQUE > findLowestCommonAncestor(const std::shared_ptr< CLIQUE > &C1, const std::shared_ptr< CLIQUE > &C2)
Definition: BayesTree-inst.h:343
Ordering.h
Variable ordering for the elimination algorithm.
gtsam::BayesTree::marginalFactor
sharedConditional marginalFactor(Key j, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Definition: BayesTree-inst.h:310
C2
Definition: test_operator_overloading.cpp:98
gtsam::BayesTree::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: BayesTree-inst.h:252
os
ofstream os("timeSchurFactors.csv")
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::BayesTree::addClique
void addClique(const sharedClique &clique, const sharedClique &parent_clique=sharedClique())
Definition: BayesTree-inst.h:144
gtsam::BayesTree::removeTop
void removeTop(const KeyVector &keys, BayesNetType *bn, Cliques *orphans)
Definition: BayesTree-inst.h:491
pybind_wrapper_test_script.dummy
dummy
Definition: pybind_wrapper_test_script.py:42
gtsam::check_sharedCliques
bool check_sharedCliques(const std::pair< Key, typename BayesTree< CLIQUE >::sharedClique > &v1, const std::pair< Key, typename BayesTree< CLIQUE >::sharedClique > &v2)
Definition: BayesTree-inst.h:260
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
ss
static std::stringstream ss
Definition: testBTree.cpp:31
gtsam::FactorGraph
Definition: BayesTree.h:34
gtsam::BayesTree::dot
void dot(std::ostream &os, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Output to graphviz format, stream version.
Definition: BayesTree-inst.h:66
gtsam::BayesTree::removeSubtree
Cliques removeSubtree(const sharedClique &subtree)
Definition: BayesTree-inst.h:512
gtsam::BayesTree::sharedFactorGraph
std::shared_ptr< FactorGraphType > sharedFactorGraph
Definition: BayesTree.h:84
gtsam::BayesTree::removePath
void removePath(sharedClique clique, BayesNetType *bn, Cliques *orphans)
Definition: BayesTree-inst.h:464
gtsam::BayesTree::BayesTree
BayesTree()
Definition: BayesTree.h:109
data
int data[]
Definition: Map_placement_new.cpp:1
gtsam::BayesTree< HybridBayesTreeClique >::BayesNetType
HybridBayesTreeClique ::BayesNetType BayesNetType
Definition: BayesTree.h:79
gtsam::BayesTree::sharedBayesNet
std::shared_ptr< BayesNetType > sharedBayesNet
Definition: BayesTree.h:80
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
stats
bool stats
Definition: SolverComparer.cpp:100
operator()
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
Definition: IndexedViewMethods.h:73
relicense.filename
filename
Definition: relicense.py:57
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
C1
Definition: test_operator_overloading.cpp:97
gtsam::BayesTree::operator=
This & operator=(const This &other)
Definition: BayesTree-inst.h:239
gtsam::treeTraversal::DepthFirstForest
void DepthFirstForest(FOREST &forest, DATA &rootData, VISITOR_PRE &visitorPre, VISITOR_POST &visitorPost)
Definition: treeTraversal-inst.h:77
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:196
gtsam::factorInto
static auto factorInto(const std::shared_ptr< CLIQUE > &p_F_S, const std::shared_ptr< CLIQUE > &B, const typename CLIQUE::FactorGraphType::Eliminate &eliminate)
Definition: BayesTree-inst.h:366
gtsam::BayesTree::deleteCachedShortcuts
void deleteCachedShortcuts()
Definition: BayesTree-inst.h:432
gtsam::BayesTree::jointBayesNet
sharedBayesNet jointBayesNet(Key j1, Key j2, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Definition: BayesTree-inst.h:386
gtsam::BayesTree::findParentClique
Key findParentClique(const CONTAINER &parents) const
Definition: BayesTree-inst.h:278
gtsam::FastList
Definition: FastList.h:43
gtsam::BayesTree::removeClique
void removeClique(sharedClique clique)
Definition: BayesTree-inst.h:440
out
std::ofstream out("Result.txt")
gtsam::BayesTreeCliqueData
Definition: BayesTree.h:48
key
const gtsam::Symbol key('X', 0)
gtsam::treeTraversal::PrintForest
void PrintForest(const FOREST &forest, std::string str, const KeyFormatter &keyFormatter)
Definition: treeTraversal-inst.h:221
gtsam
traits
Definition: SFMdata.h:40
gtsam::BayesTree< HybridBayesTreeClique >
gtsam::BayesTree::size
size_t size() const
Definition: BayesTree-inst.h:135
gtsam::BayesTree< HybridBayesTreeClique >::sharedClique
std::shared_ptr< Clique > sharedClique
Shared pointer to a clique.
Definition: BayesTree.h:74
p
float * p
Definition: Tutorial_Map_using.cpp:9
v2
Vector v2
Definition: testSerializationBase.cpp:39
gtsam::BayesTree::sharedConditional
std::shared_ptr< ConditionalType > sharedConditional
Definition: BayesTree.h:78
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::BayesTree::equals
bool equals(const This &other, double tol=1e-9) const
Definition: BayesTree-inst.h:270
gtsam::BayesTree::clear
void clear()
Definition: BayesTree-inst.h:424
gtsam::BayesTree::saveGraph
void saveGraph(const std::string &filename, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
output to file with graphviz format.
Definition: BayesTree-inst.h:87
gtsam::BayesTree::joint
sharedFactorGraph joint(Key j1, Key j2, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
Definition: BayesTree-inst.h:333
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::BayesTree::numCachedSeparatorMarginals
size_t numCachedSeparatorMarginals() const
Definition: BayesTree-inst.h:57
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::Ordering
Definition: inference/Ordering.h:33
j1
double j1(double x)
Definition: j1.c:174
gtsam::equal
bool equal(const T &obj1, const T &obj2, double tol)
Definition: Testable.h:85
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gttic
#define gttic(label)
Definition: timing.h:326
v1
Vector v1
Definition: testSerializationBase.cpp:38


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:18