JunctionTree-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 
27 
28 namespace gtsam {
29 
30 template<class BAYESTREE, class GRAPH, class ETREE_NODE>
34 
39 
40  // Small inner class to store symbolic factors
41  class SymbolicFactors: public FactorGraph<Factor> {
42  };
43 
45  parentData(_parentData) {
46  }
47 
48  // Pre-order visitor function
50  const std::shared_ptr<ETREE_NODE>& node,
52  // On the pre-order pass, before children have been visited, we just set up
53  // a traversal data structure with its own JT node, and create a child
54  // pointer in its parent.
56  myData.junctionTreeNode =
57  std::make_shared<Node>(node->key, node->factors);
59  return myData;
60  }
61 
62  // Post-order visitor function
64  const std::shared_ptr<ETREE_NODE>& ETreeNode,
65  const ConstructorTraversalData& myData) {
66  // In this post-order visitor, we combine the symbolic elimination results
67  // from the elimination tree children and symbolically eliminate the current
68  // elimination tree node. We then check whether each of our elimination
69  // tree child nodes should be merged with us. The check for this is that
70  // our number of symbolic elimination parents is exactly 1 less than
71  // our child's symbolic elimination parents - this condition indicates that
72  // eliminating the current node did not introduce any parents beyond those
73  // already in the child->
74 
75  // Do symbolic elimination for this node
76  SymbolicFactors symbolicFactors;
77  symbolicFactors.reserve(
78  ETreeNode->factors.size() + myData.childSymbolicFactors.size());
79  // Add ETree node factors
80  symbolicFactors.push_back(ETreeNode->factors);
81  // Add symbolic factors passed up from children
82  symbolicFactors.push_back(myData.childSymbolicFactors);
83 
84  Ordering keyAsOrdering;
85  keyAsOrdering.push_back(ETreeNode->key);
86  const auto [myConditional, mySeparatorFactor] =
87  internal::EliminateSymbolic(symbolicFactors, keyAsOrdering);
88 
89  // Store symbolic elimination results in the parent
90  myData.parentData->childSymbolicConditionals.push_back(myConditional);
91  myData.parentData->childSymbolicFactors.push_back(mySeparatorFactor);
92 
93  sharedNode node = myData.junctionTreeNode;
94  const FastVector<SymbolicConditional::shared_ptr>& childConditionals =
96  node->problemSize_ = (int) (myConditional->size() * symbolicFactors.size());
97 
98  // Merge our children if they are in our clique - if our conditional has
99  // exactly one fewer parent than our child's conditional.
100  const size_t myNrParents = myConditional->nrParents();
101  const size_t nrChildren = node->nrChildren();
102  assert(childConditionals.size() == nrChildren);
103 
104  // decide which children to merge, as index into children
105  std::vector<size_t> nrFrontals = node->nrFrontalsOfChildren();
106  std::vector<bool> merge(nrChildren, false);
107  size_t myNrFrontals = 1;
108  for (size_t i = 0;i<nrChildren;i++){
109  // Check if we should merge the i^th child
110  if (myNrParents + myNrFrontals == childConditionals[i]->nrParents()) {
111  // Increment number of frontal variables
112  myNrFrontals += nrFrontals[i];
113  merge[i] = true;
114  }
115  }
116 
117  // now really merge
118  node->mergeChildren(merge);
119  }
120 };
121 
122 /* ************************************************************************* */
123 template<class BAYESTREE, class GRAPH>
124 template<class ETREE_BAYESNET, class ETREE_GRAPH>
126  const EliminationTree<ETREE_BAYESNET, ETREE_GRAPH>& eliminationTree) {
127  gttic(JunctionTree_FromEliminationTree);
128  // Here we rely on the BayesNet having been produced by this elimination tree,
129  // such that the conditionals are arranged in DFS post-order. We traverse the
130  // elimination tree, and inspect the symbolic conditional corresponding to
131  // each node. The elimination tree node is added to the same clique with its
132  // parent if it has exactly one more Bayes net conditional parent than
133  // does its elimination tree parent.
134 
135  // Traverse the elimination tree, doing symbolic elimination and merging nodes
136  // as we go. Gather the created junction tree roots in a dummy Node.
137  typedef typename EliminationTree<ETREE_BAYESNET, ETREE_GRAPH>::Node ETreeNode;
139  Data rootData(0);
140  // Make a dummy node to gather the junction tree roots
141  rootData.junctionTreeNode = std::make_shared<typename Base::Node>();
142  treeTraversal::DepthFirstForest(eliminationTree, rootData,
143  Data::ConstructorTraversalVisitorPre,
144  Data::ConstructorTraversalVisitorPostAlg2);
145 
146  // Assign roots from the dummy node
147  this->addChildrenAsRoots(rootData.junctionTreeNode);
148 
149  // Transfer remaining factors from elimination tree
150  Base::remainingFactors_ = eliminationTree.remainingFactors();
151 }
152 
153 } // namespace gtsam
gtsam.examples.DogLegOptimizerExample.int
int
Definition: DogLegOptimizerExample.py:111
gtsam::ConstructorTraversalData::ConstructorTraversalData
ConstructorTraversalData(ConstructorTraversalData *_parentData)
Definition: JunctionTree-inst.h:44
gtsam::ConstructorTraversalData::parentData
ConstructorTraversalData *const parentData
Definition: JunctionTree-inst.h:35
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
gtsam::EliminationTree
Definition: EliminationTree.h:51
gtsam::EliminationTree::Node
Definition: EliminationTree.h:66
SymbolicConditional.h
JunctionTree.h
The junction tree.
gtsam::ConstructorTraversalData::childSymbolicFactors
FastVector< SymbolicFactor::shared_ptr > childSymbolicFactors
Definition: JunctionTree-inst.h:38
gtsam::FactorGraph
Definition: BayesTree.h:34
gtsam::internal::EliminateSymbolic
std::pair< std::shared_ptr< SymbolicConditional >, std::shared_ptr< SymbolicFactor > > EliminateSymbolic(const FactorGraph< FACTOR > &factors, const Ordering &keys)
Definition: SymbolicFactor-inst.h:38
gtsam::ConstructorTraversalData
Definition: JunctionTree-inst.h:31
gtsam::ConstructorTraversalData::childSymbolicConditionals
FastVector< SymbolicConditional::shared_ptr > childSymbolicConditionals
Definition: JunctionTree-inst.h:37
gtsam::treeTraversal::DepthFirstForest
void DepthFirstForest(FOREST &forest, DATA &rootData, VISITOR_PRE &visitorPre, VISITOR_POST &visitorPost)
Definition: treeTraversal-inst.h:77
gtsam::ConstructorTraversalData::ConstructorTraversalVisitorPostAlg2
static void ConstructorTraversalVisitorPostAlg2(const std::shared_ptr< ETREE_NODE > &ETreeNode, const ConstructorTraversalData &myData)
Definition: JunctionTree-inst.h:63
SymbolicFactor-inst.h
gtsam::FactorGraph::size
size_t size() const
Definition: FactorGraph.h:297
gtsam::ConstructorTraversalData::ConstructorTraversalVisitorPre
static ConstructorTraversalData ConstructorTraversalVisitorPre(const std::shared_ptr< ETREE_NODE > &node, ConstructorTraversalData &parentData)
Definition: JunctionTree-inst.h:49
gtsam
traits
Definition: chartTesting.h:28
gtsam::ConstructorTraversalData::SymbolicFactors
Definition: JunctionTree-inst.h:41
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::ConstructorTraversalData::junctionTreeNode
sharedNode junctionTreeNode
Definition: JunctionTree-inst.h:36
gtsam::JunctionTree
Definition: JunctionTree.h:50
gtsam::ConstructorTraversalData::sharedNode
JunctionTree< BAYESTREE, GRAPH >::sharedNode sharedNode
Definition: JunctionTree-inst.h:33
gtsam::FactorGraph::reserve
void reserve(size_t size)
Definition: FactorGraph.h:143
gtsam::JunctionTree::JunctionTree
JunctionTree()
Definition: JunctionTree.h:76
ClusterTree-inst.h
Collects factorgraph fragments defined on variable clusters, arranged in a tree.
gtsam::Ordering
Definition: inference/Ordering.h:33
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gttic
#define gttic(label)
Definition: timing.h:295
gtsam::EliminationTree::remainingFactors
const FastVector< sharedFactor > & remainingFactors() const
Definition: EliminationTree.h:155
gtsam::ConstructorTraversalData::Node
JunctionTree< BAYESTREE, GRAPH >::Node Node
Definition: JunctionTree-inst.h:32


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:02:53