coal/broadphase/detail/hierarchy_tree.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2016, Open Source Robotics Foundation
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef COAL_HIERARCHY_TREE_H
39 #define COAL_HIERARCHY_TREE_H
40 
41 #include <vector>
42 #include <map>
43 #include <functional>
44 #include <iostream>
45 #include "coal/warning.hh"
46 #include "coal/BV/AABB.h"
49 
50 namespace coal {
51 
52 namespace detail {
53 
55 template <typename BV>
57  public:
58  typedef NodeBase<BV> Node;
59 
65  HierarchyTree(int bu_threshold_ = 16, int topdown_level_ = 0);
66 
68 
71  void init(std::vector<Node*>& leaves, int level = 0);
72 
74  Node* insert(const BV& bv, void* data);
75 
77  void remove(Node* leaf);
78 
80  void clear();
81 
83  bool empty() const;
84 
96  void update(Node* leaf, int lookahead_level = -1);
97 
100  bool update(Node* leaf, const BV& bv);
101 
103  bool update(Node* leaf, const BV& bv, const Vec3s& vel, CoalScalar margin);
104 
106  bool update(Node* leaf, const BV& bv, const Vec3s& vel);
107 
109  size_t getMaxHeight() const;
110 
112  size_t getMaxDepth() const;
113 
115  void balanceBottomup();
116 
118  void balanceTopdown();
119 
121  void balanceIncremental(int iterations);
122 
125  void refit();
126 
128  void extractLeaves(const Node* root, std::vector<Node*>& leaves) const;
129 
131  size_t size() const;
132 
134  Node* getRoot() const;
135 
136  Node*& getRoot();
137 
139  void print(Node* root, int depth);
140 
141  private:
142  typedef typename std::vector<NodeBase<BV>*>::iterator NodeVecIterator;
143  typedef
144  typename std::vector<NodeBase<BV>*>::const_iterator NodeVecConstIterator;
145 
146  struct SortByMorton {
147  bool operator()(const Node* a, const Node* b) const {
148  return a->code < b->code;
149  }
150  };
151 
153  void bottomup(const NodeVecIterator lbeg, const NodeVecIterator lend);
154 
156  Node* topdown(const NodeVecIterator lbeg, const NodeVecIterator lend);
157 
159  size_t getMaxHeight(Node* node) const;
160 
162  void getMaxDepth(Node* node, size_t depth, size_t& max_depth) const;
163 
169  Node* topdown_0(const NodeVecIterator lbeg, const NodeVecIterator lend);
170 
177  Node* topdown_1(const NodeVecIterator lbeg, const NodeVecIterator lend);
178 
181  void init_0(std::vector<Node*>& leaves);
182 
187  void init_1(std::vector<Node*>& leaves);
188 
193  void init_2(std::vector<Node*>& leaves);
194 
198  void init_3(std::vector<Node*>& leaves);
199 
200  Node* mortonRecurse_0(const NodeVecIterator lbeg, const NodeVecIterator lend,
201  const uint32_t& split, int bits);
202 
203  Node* mortonRecurse_1(const NodeVecIterator lbeg, const NodeVecIterator lend,
204  const uint32_t& split, int bits);
205 
206  Node* mortonRecurse_2(const NodeVecIterator lbeg, const NodeVecIterator lend);
207 
209  void update_(Node* leaf, const BV& bv);
210 
212  Node* sort(Node* n, Node*& r);
213 
219  // leaf node.
220  void insertLeaf(Node* const sub_root, Node* const leaf);
221 
228  // adjusted.
229  Node* removeLeaf(Node* const leaf);
230 
233  void fetchLeaves(Node* root, std::vector<Node*>& leaves, int depth = -1);
234 
235  static size_t indexOf(Node* node);
236 
238  Node* createNode(Node* parent, const BV& bv, void* data);
239 
240  Node* createNode(Node* parent, const BV& bv1, const BV& bv2, void* data);
241 
242  Node* createNode(Node* parent, void* data);
243 
244  void deleteNode(Node* node);
245 
246  void recurseDeleteNode(Node* node);
247 
248  void recurseRefit(Node* node);
249 
250  protected:
252 
253  size_t n_leaves;
254 
255  unsigned int opath;
256 
260 
262 
263  public:
266 
269 };
270 
272 template <typename BV>
273 bool nodeBaseLess(NodeBase<BV>* a, NodeBase<BV>* b, int d);
274 
277 template <typename BV>
278 size_t select(const NodeBase<BV>& query, const NodeBase<BV>& node1,
279  const NodeBase<BV>& node2);
280 
283 template <typename BV>
284 size_t select(const BV& query, const NodeBase<BV>& node1,
285  const NodeBase<BV>& node2);
286 
287 } // namespace detail
288 } // namespace coal
289 
291 
292 #endif
coal::detail::HierarchyTree::deleteNode
void deleteNode(Node *node)
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:898
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::detail::HierarchyTree::init_2
void init_2(std::vector< Node * > &leaves)
init tree from leaves using morton code. It uses morton_0, i.e., for nodes which is of depth more tha...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:500
coal::detail::HierarchyTree::NodeVecIterator
std::vector< NodeBase< BV > * >::iterator NodeVecIterator
Definition: coal/broadphase/detail/hierarchy_tree.h:142
hierarchy_tree-inl.h
coal::detail::HierarchyTree::NodeVecConstIterator
std::vector< NodeBase< BV > * >::const_iterator NodeVecConstIterator
Definition: coal/broadphase/detail/hierarchy_tree.h:144
coal::detail::HierarchyTree::insert
Node * insert(const BV &bv, void *data)
Insest a node.
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:88
coal::detail::HierarchyTree::print
void print(Node *root, int depth)
print the tree in a recursive way
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:285
coal::detail::HierarchyTree::getMaxDepth
size_t getMaxDepth() const
get the max depth of the tree
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:199
coal::detail::HierarchyTree::root_node
Node * root_node
Definition: coal/broadphase/detail/hierarchy_tree.h:251
coal::detail::HierarchyTree::recurseDeleteNode
void recurseDeleteNode(Node *node)
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:907
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::detail::HierarchyTree::update
void update(Node *leaf, int lookahead_level=-1)
Updates a leaf node. A use case is when the bounding volume of an object changes. Ensure every parent...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:123
coal::detail::HierarchyTree::mortonRecurse_0
Node * mortonRecurse_0(const NodeVecIterator lbeg, const NodeVecIterator lend, const uint32_t &split, int bits)
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:547
coal::detail::HierarchyTree::balanceIncremental
void balanceIncremental(int iterations)
balance the tree in an incremental way
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:232
octree.r
r
Definition: octree.py:9
coal::detail::HierarchyTree::recurseRefit
void recurseRefit(Node *node)
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:919
coal::detail::HierarchyTree::opath
unsigned int opath
Definition: coal/broadphase/detail/hierarchy_tree.h:255
coal::detail::HierarchyTree::getMaxHeight
size_t getMaxHeight() const
get the max height of the tree
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:192
a
list a
coal::detail::HierarchyTree::Node
NodeBase< BV > Node
Definition: coal/broadphase/detail/hierarchy_tree.h:58
coal::detail::HierarchyTree::refit
void refit()
refit the tree, i.e., when the leaf nodes' bounding volumes change, update the entire tree in a botto...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:250
coal::detail::HierarchyTree::topdown_1
Node * topdown_1(const NodeVecIterator lbeg, const NodeVecIterator lend)
construct a tree from a list of nodes stored in [lbeg, lend) in a topdown manner. During construction...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:406
coal::detail::HierarchyTree::createNode
Node * createNode(Node *parent, const BV &bv, void *data)
create one node (leaf or internal)
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:861
coal::detail::HierarchyTree::mortonRecurse_1
Node * mortonRecurse_1(const NodeVecIterator lbeg, const NodeVecIterator lend, const uint32_t &split, int bits)
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:587
coal::detail::HierarchyTree::free_node
Node * free_node
Definition: coal/broadphase/detail/hierarchy_tree.h:259
coal::detail::HierarchyTree::indexOf
static size_t indexOf(Node *node)
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:854
coal::detail::HierarchyTree::balanceTopdown
void balanceTopdown()
balance the tree from top
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:221
coal::detail::HierarchyTree::max_lookahead_level
int max_lookahead_level
Definition: coal/broadphase/detail/hierarchy_tree.h:261
coal::detail::HierarchyTree::clear
void clear()
Clear the tree.
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:106
coal::detail::HierarchyTree::sort
Node * sort(Node *n, Node *&r)
sort node n and its parent according to their memory position
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:667
coal::detail::HierarchyTree::bottomup
void bottomup(const NodeVecIterator lbeg, const NodeVecIterator lend)
construct a tree for a set of leaves from bottom – very heavy way
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:299
coal::detail::HierarchyTree::bu_threshold
int bu_threshold
decide the depth to use expensive bottom-up algorithm
Definition: coal/broadphase/detail/hierarchy_tree.h:268
coal::detail::select
size_t select(const NodeBase< BV > &query, const NodeBase< BV > &node1, const NodeBase< BV > &node2)
select from node1 and node2 which is close to a given query. 0 for node1 and 1 for node2
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:952
coal::detail::HierarchyTree::getRoot
Node * getRoot() const
get the root of the tree
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:273
coal::detail::HierarchyTree::n_leaves
size_t n_leaves
Definition: coal/broadphase/detail/hierarchy_tree.h:253
coal::detail::HierarchyTree::removeLeaf
Node * removeLeaf(Node *const leaf)
Remove a leaf. Maintain the tree as a full binary tree (every interior node has exactly two children)...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:776
coal::detail::HierarchyTree
Class for hierarchy tree structure.
Definition: coal/broadphase/detail/hierarchy_tree.h:56
morton.h
coal::detail::HierarchyTree::mortonRecurse_2
Node * mortonRecurse_2(const NodeVecIterator lbeg, const NodeVecIterator lend)
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:633
coal::detail::HierarchyTree::empty
bool empty() const
Whether the tree is empty.
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:117
coal::detail::HierarchyTree::topdown_level
int topdown_level
decide which topdown algorithm to use
Definition: coal/broadphase/detail/hierarchy_tree.h:265
coal::detail::HierarchyTree::topdown
Node * topdown(const NodeVecIterator lbeg, const NodeVecIterator lend)
construct a tree for a set of leaves from top
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:333
coal::detail::HierarchyTree::SortByMorton::operator()
bool operator()(const Node *a, const Node *b) const
Definition: coal/broadphase/detail/hierarchy_tree.h:147
coal::detail::HierarchyTree::fetchLeaves
void fetchLeaves(Node *root, std::vector< Node * > &leaves, int depth=-1)
Delete all internal nodes and return all leaves nodes with given depth from root.
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:841
coal::detail::HierarchyTree::~HierarchyTree
~HierarchyTree()
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:61
coal::detail::HierarchyTree::update_
void update_(Node *leaf, const BV &bv)
update one leaf node's bounding volume
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:651
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::detail::HierarchyTree::insertLeaf
void insertLeaf(Node *const sub_root, Node *const leaf)
Insert a leaf node and also update its ancestors. Maintain the tree as a full binary tree (every inte...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:695
coal::detail::HierarchyTree::extractLeaves
void extractLeaves(const Node *root, std::vector< Node * > &leaves) const
extract all the leaves of the tree
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:256
coal::detail::HierarchyTree::topdown_0
Node * topdown_0(const NodeVecIterator lbeg, const NodeVecIterator lend)
construct a tree from a list of nodes stored in [lbeg, lend) in a topdown manner. During construction...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:371
coal::detail::HierarchyTree::init_1
void init_1(std::vector< Node * > &leaves)
init tree from leaves using morton code. It uses morton_0, i.e., for nodes which is of depth more tha...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:476
coal::detail::HierarchyTree::size
size_t size() const
number of leaves in the tree
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:267
coal::detail::HierarchyTree::init
void init(std::vector< Node * > &leaves, int level=0)
Initialize the tree by a set of leaves using algorithm with a given level.
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:67
coal::detail::HierarchyTree::init_0
void init_0(std::vector< Node * > &leaves)
init tree from leaves in the topdown manner (topdown_0 or topdown_1)
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:466
coal::detail::HierarchyTree::HierarchyTree
HierarchyTree(int bu_threshold_=16, int topdown_level_=0)
Create hierarchy tree with suitable setting. bu_threshold decides the height of tree node to start bo...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:49
coal::detail::nodeBaseLess
bool nodeBaseLess(NodeBase< BV > *a, NodeBase< BV > *b, int d)
Compare two nodes accoording to the d-th dimension of node center.
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:930
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::detail::HierarchyTree::balanceBottomup
void balanceBottomup()
balance the tree from bottom
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:209
coal::detail::NodeBase
dynamic AABB tree node
Definition: coal/broadphase/detail/node_base.h:49
coal::detail::HierarchyTree::SortByMorton
Definition: coal/broadphase/detail/hierarchy_tree.h:146
node_base.h
coal::detail::HierarchyTree::remove
void remove(Node *leaf)
Remove a leaf node.
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:98
AABB.h
coal::detail::HierarchyTree::init_3
void init_3(std::vector< Node * > &leaves)
init tree from leaves using morton code. It uses morton_2, i.e., for all nodes, we simply divide the ...
Definition: coal/broadphase/detail/hierarchy_tree-inl.h:524


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:58