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


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:51