EliminationTree-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 
18 #pragma once
19 
20 #include <stack>
21 #include <queue>
22 #include <cassert>
23 
24 #include <gtsam/base/timing.h>
30 
31 namespace gtsam {
32 
33  /* ************************************************************************* */
34  template<class BAYESNET, class GRAPH>
37  const std::shared_ptr<BayesNetType>& output,
38  const Eliminate& function, const FastVector<sharedFactor>& childrenResults) const
39  {
40  // This function eliminates one node (Node::eliminate) - see below eliminate for the whole tree.
41 
42  assert(childrenResults.size() == children.size());
43 
44  // Gather factors
45  FactorGraphType gatheredFactors;
46  gatheredFactors.reserve(factors.size() + children.size());
47  gatheredFactors.push_back(factors.begin(), factors.end());
48  gatheredFactors.push_back(childrenResults.begin(), childrenResults.end());
49 
50  // Do dense elimination step
51  KeyVector keyAsVector(1); keyAsVector[0] = key;
52  auto eliminationResult = function(gatheredFactors, Ordering(keyAsVector));
53 
54  // Add conditional to BayesNet
55  output->push_back(eliminationResult.first);
56 
57  // Return result
58  return eliminationResult.second;
59  }
60 
61  /* ************************************************************************* */
62  template<class BAYESNET, class GRAPH>
64  const std::string& str, const KeyFormatter& keyFormatter) const
65  {
66  std::cout << str << "(" << keyFormatter(key) << ")\n";
67  for(const sharedFactor& factor: factors) {
68  if(factor)
69  factor->print(str);
70  else
71  std::cout << str << "null factor\n";
72  }
73  }
74 
75 
76  /* ************************************************************************* */
77  template<class BAYESNET, class GRAPH>
79  const VariableIndex& structure, const Ordering& order)
80  {
81  gttic(EliminationTree_Contructor);
82 
83  // Number of factors and variables - NOTE in the case of partial elimination, n here may
84  // be fewer variables than are actually present in the graph.
85  const size_t m = graph.size();
86  const size_t n = order.size();
87 
88  static const size_t none = std::numeric_limits<size_t>::max();
89 
90  // Allocate result parent vector and vector of last factor columns
92  FastVector<size_t> parents(n, none);
93  FastVector<size_t> prevCol(m, none);
94  FastVector<bool> factorUsed(m, false);
95 
96  try {
97  // for column j \in 1 to n do
98  for (size_t j = 0; j < n; j++)
99  {
100  // Retrieve the factors involving this variable and create the current node
101  const FactorIndices& factors = structure[order[j]];
102  const sharedNode node = std::make_shared<Node>();
103  node->key = order[j];
104 
105  // for row i \in Struct[A*j] do
106  node->children.reserve(factors.size());
107  node->factors.reserve(factors.size());
108  for(const size_t i: factors) {
109  // If we already hit a variable in this factor, make the subtree containing the previous
110  // variable in this factor a child of the current node. This means that the variables
111  // eliminated earlier in the factor depend on the later variables in the factor. If we
112  // haven't yet hit a variable in this factor, we add the factor to the current node.
113  // TODO: Store root shortcuts instead of parents.
114  if (prevCol[i] != none) {
115  size_t k = prevCol[i];
116  // Find root r of the current tree that contains k. Use raw pointers in computing the
117  // parents to avoid changing the reference counts while traversing up the tree.
118  size_t r = k;
119  while (parents[r] != none)
120  r = parents[r];
121  // If the root of the subtree involving this node is actually the current node,
122  // TODO: what does this mean? forest?
123  if (r != j) {
124  // Now that we found the root, hook up parent and child pointers in the nodes.
125  parents[r] = j;
126  node->children.push_back(nodes[r]);
127  }
128  } else {
129  // Add the factor to the current node since we are at the first variable in this factor.
130  node->factors.push_back(graph[i]);
131  factorUsed[i] = true;
132  }
133  prevCol[i] = j;
134  }
135  nodes[j] = node;
136  }
137  } catch(std::invalid_argument& e) {
138  // If this is thrown from structure[order[j]] above, it means that it was requested to
139  // eliminate a variable not present in the graph, so throw a more informative error message.
140  (void)e; // Prevent unused variable warning
141  throw std::invalid_argument("EliminationTree: given ordering contains variables that are not involved in the factor graph");
142  } catch(...) {
143  throw;
144  }
145 
146  // Find roots
147  assert(parents.empty() || parents.back() == none); // We expect the last-eliminated node to be a root no matter what
148  for(size_t j = 0; j < n; ++j)
149  if(parents[j] == none)
150  roots_.push_back(nodes[j]);
151 
152  // Gather remaining factors (exclude null factors)
153  for(size_t i = 0; i < m; ++i)
154  if(!factorUsed[i] && graph[i])
155  remainingFactors_.push_back(graph[i]);
156  }
157 
158  /* ************************************************************************* */
159  template<class BAYESNET, class GRAPH>
161  const FactorGraphType& factorGraph, const Ordering& order)
162  {
163  gttic(ET_Create2);
164  // Build variable index first
165  const VariableIndex variableIndex(factorGraph);
166  This temp(factorGraph, variableIndex, order);
167  this->swap(temp); // Swap in the tree, and temp will be deleted
168  }
169 
170  /* ************************************************************************* */
171  template<class BAYESNET, class GRAPH>
174  {
175  // Start by duplicating the tree.
177 
178  // Assign the remaining factors - these are pointers to factors in the original factor graph and
179  // we do not clone them.
180  remainingFactors_ = other.remainingFactors_;
181 
182  return *this;
183  }
184 
185  /* ************************************************************************* */
186 
192  template<class BAYESNET, class GRAPH>
194  {
195  // For each tree, we first move the root into a queue; then we do a BFS on the tree with the queue;
196 
197  for (auto&& root : roots_) {
198  std::queue<sharedNode> bfs_queue;
199 
200  // first, move the root to the queue
201  bfs_queue.push(root);
202  root = nullptr; // now the root node is owned by the queue
203 
204  // for each node iterated, if its reference count is 1, it will be deleted while its children are still in the queue.
205  // so that the recursive deletion will not happen.
206  while (!bfs_queue.empty()) {
207  // move the ownership of the front node from the queue to the current variable
208  auto node = bfs_queue.front();
209  bfs_queue.pop();
210 
211  // add the children of the current node to the queue, so that the queue will also own the children nodes.
212  for (auto&& child : node->children) {
213  bfs_queue.push(child);
214  } // leaving the scope of current will decrease the reference count of the current node by 1, and if the reference count is 0,
215  // the node will be deleted. Because the children are in the queue, the deletion of the node will not trigger a recursive
216  // deletion of the children.
217  }
218  }
219  }
220 
221 
222  /* ************************************************************************* */
223  template<class BAYESNET, class GRAPH>
224  std::pair<std::shared_ptr<BAYESNET>, std::shared_ptr<GRAPH> >
226  {
227  gttic(EliminationTree_eliminate);
228  // Allocate result
229  auto result = std::make_shared<BayesNetType>();
230 
231  // Run tree elimination algorithm
233 
234  // Add remaining factors that were not involved with eliminated variables
235  auto allRemainingFactors = std::make_shared<FactorGraphType>();
236  allRemainingFactors->push_back(remainingFactors_.begin(), remainingFactors_.end());
237  allRemainingFactors->push_back(remainingFactors.begin(), remainingFactors.end());
238 
239  // Return result
240  return {result, allRemainingFactors};
241  }
242 
243  /* ************************************************************************* */
244  template<class BAYESNET, class GRAPH>
245  void EliminationTree<BAYESNET,GRAPH>::print(const std::string& name, const KeyFormatter& formatter) const
246  {
248  }
249 
250  /* ************************************************************************* */
251  template<class BAYESNET, class GRAPH>
253  {
254  // Depth-first-traversal stacks
255  std::stack<sharedNode, FastVector<sharedNode> > stack1, stack2;
256 
257  // Add roots in sorted order
258  {
260  for(const sharedNode& root: this->roots_) { keys.emplace(root->key, root); }
261  typedef typename FastMap<Key,sharedNode>::value_type Key_Node;
262  for(const Key_Node& key_node: keys) { stack1.push(key_node.second); }
263  }
264  {
266  for(const sharedNode& root: expected.roots_) { keys.emplace(root->key, root); }
267  typedef typename FastMap<Key,sharedNode>::value_type Key_Node;
268  for(const Key_Node& key_node: keys) { stack2.push(key_node.second); }
269  }
270 
271  // Traverse, adding children in sorted order
272  while(!stack1.empty() && !stack2.empty()) {
273  // Pop nodes
274  sharedNode node1 = stack1.top();
275  stack1.pop();
276  sharedNode node2 = stack2.top();
277  stack2.pop();
278 
279  // Compare nodes
280  if(node1->key != node2->key)
281  return false;
282  if(node1->factors.size() != node2->factors.size()) {
283  return false;
284  } else {
285  for(typename Node::Factors::const_iterator it1 = node1->factors.begin(), it2 = node2->factors.begin();
286  it1 != node1->factors.end(); ++it1, ++it2) // Only check it1 == end because we already returned false for different counts
287  {
288  if(*it1 && *it2) {
289  if(!(*it1)->equals(**it2, tol))
290  return false;
291  } else if((*it1 && !*it2) || (*it2 && !*it1)) {
292  return false;
293  }
294  }
295  }
296 
297  // Add children in sorted order
298  {
300  for(const sharedNode& node: node1->children) { keys.emplace(node->key, node); }
301  typedef typename FastMap<Key,sharedNode>::value_type Key_Node;
302  for(const Key_Node& key_node: keys) { stack1.push(key_node.second); }
303  }
304  {
306  for(const sharedNode& node: node2->children) { keys.emplace(node->key, node); }
307  typedef typename FastMap<Key,sharedNode>::value_type Key_Node;
308  for(const Key_Node& key_node: keys) { stack2.push(key_node.second); }
309  }
310  }
311 
312  // If either stack is not empty, the number of nodes differed
313  if(!stack1.empty() || !stack2.empty())
314  return false;
315 
316  return true;
317  }
318 
319  /* ************************************************************************* */
320  template<class BAYESNET, class GRAPH>
322  roots_.swap(other.roots_);
323  remainingFactors_.swap(other.remainingFactors_);
324  }
325 
326 
327 }
timing.h
Timing utilities.
gtsam::EliminationTree::Node::factors
Factors factors
factors associated with root
Definition: EliminationTree.h:71
name
Annotation for function names.
Definition: attr.h:51
gtsam::EliminationTree::roots_
FastVector< sharedNode > roots_
Definition: EliminationTree.h:86
gtsam::EliminationTree::Eliminate
GRAPH::Eliminate Eliminate
Definition: EliminationTree.h:64
treeTraversal-inst.h
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::EliminationTree::remainingFactors_
FastVector< sharedFactor > remainingFactors_
Definition: EliminationTree.h:87
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
inference-inst.h
Contains generic inference algorithms that convert between templated graphical models,...
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
gtsam::EliminationTree::~EliminationTree
~EliminationTree()
Definition: EliminationTree-inst.h:193
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::EliminationTree::swap
void swap(This &other)
Definition: EliminationTree-inst.h:321
gtsam::FastMap
Definition: FastMap.h:39
gtsam::EliminationTree::print
void print(const std::string &name="EliminationTree: ", const KeyFormatter &formatter=DefaultKeyFormatter) const
Definition: EliminationTree-inst.h:245
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
Ordering.h
Variable ordering for the elimination algorithm.
gtsam::EliminationTree< GaussianBayesNet, GaussianFactorGraph >
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::EliminationTree::Node::children
Children children
sub-trees
Definition: EliminationTree.h:72
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::EliminationTree::Node::eliminate
sharedFactor eliminate(const std::shared_ptr< BayesNetType > &output, const Eliminate &function, const FastVector< sharedFactor > &childrenFactors) const
Definition: EliminationTree-inst.h:36
pruning_fixture::factor
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
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::EliminationTree::Node::key
Key key
key associated with root
Definition: EliminationTree.h:70
gtsam::EliminationTree::EliminationTree
EliminationTree()
Protected default constructor.
Definition: EliminationTree.h:162
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::EliminationTree::eliminate
std::pair< std::shared_ptr< BayesNetType >, std::shared_ptr< FactorGraphType > > eliminate(Eliminate function) const
Definition: EliminationTree-inst.h:225
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::VariableIndex
Definition: VariableIndex.h:41
gtsam::EliminationTree< GaussianBayesNet, GaussianFactorGraph >::sharedNode
std::shared_ptr< Node > sharedNode
Shared pointer to Node.
Definition: EliminationTree.h:80
str
Definition: pytypes.h:1558
key
const gtsam::Symbol key('X', 0)
gtsam::inference::EliminateTree
FastVector< typename TREE::sharedFactor > EliminateTree(RESULT &result, const TREE &tree, const typename TREE::Eliminate &function)
Definition: inference-inst.h:74
nodes
KeyVector nodes
Definition: testMFAS.cpp:28
gtsam::EliminationTree::FactorGraphType
GRAPH FactorGraphType
The factor graph type.
Definition: EliminationTree.h:58
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::EliminationTree::Node::print
void print(const std::string &str, const KeyFormatter &keyFormatter) const
Definition: EliminationTree-inst.h:63
gtsam::treeTraversal::CloneForest
FastVector< std::shared_ptr< typename FOREST::Node > > CloneForest(const FOREST &forest)
Definition: treeTraversal-inst.h:191
VariableIndex.h
gtsam::EliminationTree::operator=
This & operator=(const This &other)
Definition: EliminationTree-inst.h:173
gtsam::EliminationTree::sharedFactor
std::shared_ptr< FactorType > sharedFactor
Shared pointer to a factor.
Definition: EliminationTree.h:60
gtsam::tol
const G double tol
Definition: Group.h:79
EliminationTree.h
none
Definition: pytypes.h:1786
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
max
#define max(a, b)
Definition: datatypes.h:20
gtsam::EliminationTree::equals
bool equals(const This &other, double tol=1e-9) const
Definition: EliminationTree-inst.h:252
gtsam::Ordering
Definition: inference/Ordering.h:33
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gttic
#define gttic(label)
Definition: timing.h:295
gtsam::FactorIndices
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:37
gtsam::EliminationTree::remainingFactors
const FastVector< sharedFactor > & remainingFactors() const
Definition: EliminationTree.h:155


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