ClusterTree-inst.h
Go to the documentation of this file.
1 
10 #pragma once
11 
15 #include <gtsam/base/timing.h>
17 
18 #ifdef GTSAM_USE_TBB
19 #include <mutex>
20 #endif
21 #include <queue>
22 
23 namespace gtsam {
24 
25 /* ************************************************************************* */
26 template<class GRAPH>
27 void ClusterTree<GRAPH>::Cluster::print(const std::string& s,
28  const KeyFormatter& keyFormatter) const {
29  std::cout << s << " (" << problemSize_ << ")";
31 }
32 
33 /* ************************************************************************* */
34 template <class GRAPH>
36  std::vector<size_t> nrFrontals;
37  nrFrontals.reserve(nrChildren());
38  for (const sharedNode& child : children)
39  nrFrontals.push_back(child->nrFrontals());
40  return nrFrontals;
41 }
42 
43 /* ************************************************************************* */
44 template <class GRAPH>
45 void ClusterTree<GRAPH>::Cluster::merge(const std::shared_ptr<Cluster>& cluster) {
46  // Merge keys. For efficiency, we add keys in reverse order at end, calling reverse after..
47  orderedFrontalKeys.insert(orderedFrontalKeys.end(), cluster->orderedFrontalKeys.rbegin(),
48  cluster->orderedFrontalKeys.rend());
49  factors.push_back(cluster->factors);
50  children.insert(children.end(), cluster->children.begin(), cluster->children.end());
51  // Increment problem size
52  problemSize_ = std::max(problemSize_, cluster->problemSize_);
53 }
54 
55 /* ************************************************************************* */
56 template<class GRAPH>
58  const std::vector<bool>& merge) {
59  gttic(Cluster_mergeChildren);
60  assert(merge.size() == this->children.size());
61 
62  // Count how many keys, factors and children we'll end up with
63  size_t nrKeys = orderedFrontalKeys.size();
64  size_t nrFactors = factors.size();
65  size_t nrNewChildren = 0;
66  // Loop over children
67  size_t i = 0;
68  for(const sharedNode& child: this->children) {
69  if (merge[i]) {
70  nrKeys += child->orderedFrontalKeys.size();
71  nrFactors += child->factors.size();
72  nrNewChildren += child->nrChildren();
73  } else {
74  nrNewChildren += 1; // we keep the child
75  }
76  ++i;
77  }
78 
79  // now reserve space, and really merge
80  auto oldChildren = this->children;
81  this->children.clear();
82  this->children.reserve(nrNewChildren);
83  orderedFrontalKeys.reserve(nrKeys);
84  factors.reserve(nrFactors);
85  i = 0;
86  for (const sharedNode& child : oldChildren) {
87  if (merge[i]) {
88  this->merge(child);
89  } else {
90  this->addChild(child); // we keep the child
91  }
92  ++i;
93  }
95 }
96 
97 /* ************************************************************************* */
98 template <class GRAPH>
99 void ClusterTree<GRAPH>::print(const std::string& s, const KeyFormatter& keyFormatter) const {
100  treeTraversal::PrintForest(*this, s, keyFormatter);
101 }
102 
103 /* ************************************************************************* */
104 
105 /* Destructor.
106  * Using default destructor causes stack overflow for large trees due to recursive destruction of nodes;
107  * so we manually decrease the reference count of each node in the tree through a BFS, and the nodes with
108  * reference count 0 will be deleted. Please see [PR-1441](https://github.com/borglab/gtsam/pull/1441) for more details.
109  */
110 template <class GRAPH>
112  // For each tree, we first move the root into a queue; then we do a BFS on the tree with the queue;
113 
114  for (auto&& root : roots_) {
115  std::queue<sharedNode> bfs_queue;
116  // first, move the root to the queue
117  bfs_queue.push(root);
118  root = nullptr; // now the root node is owned by the queue
119 
120  // for each node iterated, if its reference count is 1, it will be deleted while its children are still in the queue.
121  // so that the recursive deletion will not happen.
122  while (!bfs_queue.empty()) {
123  // move the ownership of the front node from the queue to the current variable
124  auto node = bfs_queue.front();
125  bfs_queue.pop();
126 
127  // add the children of the current node to the queue, so that the queue will also own the children nodes.
128  for (auto child : node->children) {
129  bfs_queue.push(child);
130  } // leaving the scope of current will decrease the reference count of the current node by 1, and if the reference count is 0,
131  // the node will be deleted. Because the children are in the queue, the deletion of the node will not trigger a recursive
132  // deletion of the children.
133  }
134  }
135 
136 }
137 
138 /* ************************************************************************* */
139 template <class GRAPH>
141  // Start by duplicating the tree.
143  return *this;
144 }
145 
146 /* ************************************************************************* */
147 // Elimination traversal data - stores a pointer to the parent data and collects
148 // the factors resulting from elimination of the children. Also sets up BayesTree
149 // cliques with parent and child pointers.
150 template<class CLUSTERTREE>
152  // Typedefs
153  typedef typename CLUSTERTREE::sharedFactor sharedFactor;
154  typedef typename CLUSTERTREE::FactorType FactorType;
155  typedef typename CLUSTERTREE::FactorGraphType FactorGraphType;
156  typedef typename CLUSTERTREE::ConditionalType ConditionalType;
158 
162  std::shared_ptr<BTNode> bayesTreeNode;
163 #ifdef GTSAM_USE_TBB
164  std::shared_ptr<std::mutex> writeLock;
165 #endif
166 
167  EliminationData(EliminationData* _parentData, size_t nChildren) :
168  parentData(_parentData), bayesTreeNode(std::make_shared<BTNode>())
169 #ifdef GTSAM_USE_TBB
170  , writeLock(std::make_shared<std::mutex>())
171 #endif
172  {
173  if (parentData) {
174 #ifdef GTSAM_USE_TBB
175  parentData->writeLock->lock();
176 #endif
177  myIndexInParent = parentData->childFactors.size();
178  parentData->childFactors.push_back(sharedFactor());
179 #ifdef GTSAM_USE_TBB
180  parentData->writeLock->unlock();
181 #endif
182  } else {
183  myIndexInParent = 0;
184  }
185  // Set up BayesTree parent and child pointers
186  if (parentData) {
187  if (parentData->parentData) // If our parent is not the dummy node
188  bayesTreeNode->parent_ = parentData->bayesTreeNode;
189  parentData->bayesTreeNode->children.push_back(bayesTreeNode);
190  }
191  }
192 
193  // Elimination pre-order visitor - creates the EliminationData structure for the visited node.
195  const typename CLUSTERTREE::sharedNode& node,
196  EliminationData& parentData) {
197  assert(node);
198  EliminationData myData(&parentData, node->nrChildren());
199  myData.bayesTreeNode->problemSize_ = node->problemSize();
200  return myData;
201  }
202 
203  // Elimination post-order visitor - combine the child factors with our own factors, add the
204  // resulting conditional to the BayesTree, and add the remaining factor to the parent.
206  const typename CLUSTERTREE::Eliminate& eliminationFunction_;
207  typename CLUSTERTREE::BayesTreeType::Nodes& nodesIndex_;
208 
209  public:
210  // Construct functor
212  const typename CLUSTERTREE::Eliminate& eliminationFunction,
213  typename CLUSTERTREE::BayesTreeType::Nodes& nodesIndex) :
214  eliminationFunction_(eliminationFunction), nodesIndex_(nodesIndex) {
215  }
216 
217  // Function that does the HEAVY lifting
218  void operator()(const typename CLUSTERTREE::sharedNode& node, EliminationData& myData) {
219  assert(node);
220 
221  // Gather factors
222  FactorGraphType gatheredFactors;
223  gatheredFactors.reserve(node->factors.size() + node->nrChildren());
224  gatheredFactors.push_back(node->factors);
225  gatheredFactors.push_back(myData.childFactors);
226 
227  // Check for Bayes tree orphan subtrees, and add them to our children
228  // TODO(frank): should this really happen here?
229  for (const sharedFactor& factor: node->factors) {
230  auto asSubtree = dynamic_cast<const BayesTreeOrphanWrapper<BTNode>*>(factor.get());
231  if (asSubtree) {
232  myData.bayesTreeNode->children.push_back(asSubtree->clique);
233  asSubtree->clique->parent_ = myData.bayesTreeNode;
234  }
235  }
236 
237  // >>>>>>>>>>>>>> Do dense elimination step >>>>>>>>>>>>>>>>>>>>>>>>>>>>>
238  auto eliminationResult = eliminationFunction_(gatheredFactors, node->orderedFrontalKeys);
239  // <<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<
240 
241  // Store conditional in BayesTree clique, and in the case of ISAM2Clique also store the
242  // remaining factor
243  myData.bayesTreeNode->setEliminationResult(eliminationResult);
244 
245  // Fill nodes index - we do this here instead of calling insertRoot at the end to avoid
246  // putting orphan subtrees in the index - they'll already be in the index of the ISAM2
247  // object they're added to.
248  for (const Key& j : myData.bayesTreeNode->conditional()->frontals()) {
249 #ifdef GTSAM_USE_TBB
250  nodesIndex_.insert({j, myData.bayesTreeNode});
251 #else
252  nodesIndex_.emplace(j, myData.bayesTreeNode);
253 #endif
254  }
255  // Store remaining factor in parent's gathered factors
256  if (!eliminationResult.second->empty()) {
257 #ifdef GTSAM_USE_TBB
258  myData.parentData->writeLock->lock();
259 #endif
260  myData.parentData->childFactors[myData.myIndexInParent] = eliminationResult.second;
261 #ifdef GTSAM_USE_TBB
262  myData.parentData->writeLock->unlock();
263 #endif
264  }
265  }
266  };
267 };
268 
269 /* ************************************************************************* */
270 template<class BAYESTREE, class GRAPH>
272  const This& other) {
274 
275  // Assign the remaining factors - these are pointers to factors in the original factor graph and
276  // we do not clone them.
277  remainingFactors_ = other.remainingFactors_;
278 
279  return *this;
280 }
281 
282 /* ************************************************************************* */
283 template <class BAYESTREE, class GRAPH>
284 std::pair<std::shared_ptr<BAYESTREE>, std::shared_ptr<GRAPH> >
286  gttic(ClusterTree_eliminate);
287  // Do elimination (depth-first traversal). The rootsContainer stores a 'dummy' BayesTree node
288  // that contains all of the roots as its children. rootsContainer also stores the remaining
289  // un-eliminated factors passed up from the roots.
290  std::shared_ptr<BayesTreeType> result = std::make_shared<BayesTreeType>();
291 
292  typedef EliminationData<This> Data;
293  Data rootsContainer(0, this->nrRoots());
294 
295  typename Data::EliminationPostOrderVisitor visitorPost(function, result->nodes_);
296  {
297  TbbOpenMPMixedScope threadLimiter; // Limits OpenMP threads since we're mixing TBB and OpenMP
298  treeTraversal::DepthFirstForestParallel(*this, rootsContainer, Data::EliminationPreOrderVisitor,
299  visitorPost, 10);
300  }
301 
302  // Create BayesTree from roots stored in the dummy BayesTree node.
303  result->roots_.insert(result->roots_.end(), rootsContainer.bayesTreeNode->children.begin(),
304  rootsContainer.bayesTreeNode->children.end());
305 
306  // Add remaining factors that were not involved with eliminated variables
307  std::shared_ptr<FactorGraphType> remaining = std::make_shared<FactorGraphType>();
308  remaining->reserve(remainingFactors_.size() + rootsContainer.childFactors.size());
309  remaining->push_back(remainingFactors_.begin(), remainingFactors_.end());
310  for (const sharedFactor& factor : rootsContainer.childFactors) {
311  if (factor)
312  remaining->push_back(factor);
313  }
314 
315  // Return result
316  return {result, remaining};
317 }
318 
319 } // namespace gtsam
SymbolicEliminationTree::sharedNode sharedNode
void PrintKeyVector(const KeyVector &keys, const string &s, const KeyFormatter &keyFormatter)
Utility function to print sets of keys with optional prefix.
Definition: Key.cpp:80
#define max(a, b)
Definition: datatypes.h:20
FactorGraphType factors
Factors associated with this node.
Definition: ClusterTree.h:43
FastVector< sharedNode > roots_
Definition: ClusterTree.h:116
std::pair< std::shared_ptr< BayesTreeType >, std::shared_ptr< FactorGraphType > > eliminate(const Eliminate &function) const
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
void merge(const std::shared_ptr< Cluster > &cluster)
Merge in given cluster.
sharedCluster sharedNode
Definition: ClusterTree.h:110
void addChild(const std::shared_ptr< Cluster > &cluster)
Add a child cluster.
Definition: ClusterTree.h:71
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: BFloat16.h:88
void operator()(const typename CLUSTERTREE::sharedNode &node, EliminationData &myData)
This & operator=(const This &other)
size_t nrFrontals() const
Definition: ClusterTree.h:84
EliminationData *const parentData
CLUSTERTREE::FactorGraphType FactorGraphType
size_t nrChildren() const
Definition: ClusterTree.h:76
static const size_t nrKeys
#define gttic(label)
Definition: timing.h:295
Values result
gtsam::enable_if_t< needs_eigen_aligned_allocator< T >::value, std::shared_ptr< T > > make_shared(Args &&... args)
Definition: make_shared.h:56
void DepthFirstForestParallel(FOREST &forest, DATA &rootData, VISITOR_PRE &visitorPre, VISITOR_POST &visitorPost, int problemSizeThreshold=10)
EliminationData(EliminationData *_parentData, size_t nChildren)
std::vector< size_t > nrFrontalsOfChildren() const
Return a vector with nrFrontal keys for each child.
RealScalar s
CLUSTERTREE::ConditionalType ConditionalType
void PrintForest(const FOREST &forest, std::string str, const KeyFormatter &keyFormatter)
CLUSTERTREE::FactorType FactorType
EliminationPostOrderVisitor(const typename CLUSTERTREE::Eliminate &eliminationFunction, typename CLUSTERTREE::BayesTreeType::Nodes &nodesIndex)
static sharedNode Node(Key key, const SymbolicFactorGraph &factors, const ChildNodes::Result &children)
std::shared_ptr< BTNode > bayesTreeNode
static EliminationData EliminationPreOrderVisitor(const typename CLUSTERTREE::sharedNode &node, EliminationData &parentData)
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
FastVector< sharedFactor > childFactors
Bayes Tree is a tree of cliques of a Bayes Chain.
size_t nrRoots() const
Definition: ClusterTree.h:154
size_t nrFactors() const
Definition: ClusterTree.h:80
FastVector< std::shared_ptr< typename FOREST::Node > > CloneForest(const FOREST &forest)
Keys orderedFrontalKeys
Frontal keys of this node.
Definition: ClusterTree.h:41
traits
Definition: chartTesting.h:28
CLUSTERTREE::BayesTreeType::Node BTNode
This & operator=(const This &other)
Children children
sub-trees
Definition: ClusterTree.h:38
const TREE::Eliminate & eliminationFunction
void reverse(const MatrixType &m)
std::shared_ptr< FactorType > sharedFactor
Shared pointer to a factor.
Definition: ClusterTree.h:32
CLUSTERTREE::sharedFactor sharedFactor
CLUSTERTREE::BayesTreeType::Nodes & nodesIndex_
SymbolicFactorGraph ::Eliminate Eliminate
Typedef for an eliminate subroutine.
Definition: ClusterTree.h:197
FastVector< sharedFactor > remainingFactors_
Definition: ClusterTree.h:202
void mergeChildren(const std::vector< bool > &merge)
Merge all children for which bit is set into this node.
std::shared_ptr< FactorType > sharedFactor
Shared pointer to a factor.
Definition: ClusterTree.h:199
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
std::ptrdiff_t j
Collects factorgraph fragments defined on variable clusters, arranged in a tree.
Timing utilities.
virtual void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
print this node


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:01