coal/broadphase/detail/hierarchy_tree_array.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_ARRAY_H
39 #define COAL_HIERARCHY_TREE_ARRAY_H
40 
41 #include <vector>
42 #include <map>
43 #include <functional>
44 
45 #include "coal/fwd.hh"
46 #include "coal/BV/AABB.h"
49 
50 namespace coal {
51 
52 namespace detail {
53 
54 namespace implementation_array {
55 
57 template <typename BV>
59  public:
60  typedef NodeBase<BV> Node;
61 
62  private:
63  struct SortByMorton {
64  SortByMorton(Node* nodes_in) : nodes(nodes_in) {}
65  SortByMorton(Node* nodes_in, uint32_t split_in)
66  : nodes(nodes_in), split(split_in) {}
67  bool operator()(size_t a, size_t b) const {
68  if ((a != NULL_NODE) && (b != NULL_NODE))
69  return nodes[a].code < nodes[b].code;
70  else if (a == NULL_NODE)
71  return split < nodes[b].code;
72  else if (b == NULL_NODE)
73  return nodes[a].code < split;
74 
75  return false;
76  }
77 
78  Node* nodes{};
80  };
81 
82  public:
88  HierarchyTree(int bu_threshold_ = 16, int topdown_level_ = 0);
89 
91 
94  void init(Node* leaves, int n_leaves_, int level = 0);
95 
98  size_t insert(const BV& bv, void* data);
99 
101  void remove(size_t leaf);
102 
104  void clear();
105 
107  bool empty() const;
108 
110  void update(size_t leaf, int lookahead_level = -1);
111 
114  bool update(size_t leaf, const BV& bv);
115 
117  bool update(size_t leaf, const BV& bv, const Vec3s& vel, CoalScalar margin);
118 
120  bool update(size_t leaf, const BV& bv, const Vec3s& vel);
121 
123  size_t getMaxHeight() const;
124 
126  size_t getMaxDepth() const;
127 
129  void balanceBottomup();
130 
132  void balanceTopdown();
133 
135  void balanceIncremental(int iterations);
136 
139  void refit();
140 
142  void extractLeaves(size_t root, Node*& leaves) const;
143 
145  size_t size() const;
146 
148  size_t getRoot() const;
149 
151  Node* getNodes() const;
152 
154  void print(size_t root, int depth);
155 
156  private:
158  void bottomup(size_t* lbeg, size_t* lend);
159 
161  size_t topdown(size_t* lbeg, size_t* lend);
162 
164  size_t getMaxHeight(size_t node) const;
165 
167  void getMaxDepth(size_t node, size_t depth, size_t& max_depth) const;
168 
174  size_t topdown_0(size_t* lbeg, size_t* lend);
175 
182  size_t topdown_1(size_t* lbeg, size_t* lend);
183 
186  void init_0(Node* leaves, int n_leaves_);
187 
192  void init_1(Node* leaves, int n_leaves_);
193 
198  void init_2(Node* leaves, int n_leaves_);
199 
203  void init_3(Node* leaves, int n_leaves_);
204 
205  size_t mortonRecurse_0(size_t* lbeg, size_t* lend, const uint32_t& split,
206  int bits);
207 
208  size_t mortonRecurse_1(size_t* lbeg, size_t* lend, const uint32_t& split,
209  int bits);
210 
211  size_t mortonRecurse_2(size_t* lbeg, size_t* lend);
212 
214  void update_(size_t leaf, const BV& bv);
215 
217  void insertLeaf(size_t root, size_t leaf);
218 
222  size_t removeLeaf(size_t leaf);
223 
226  void fetchLeaves(size_t root, Node*& leaves, int depth = -1);
227 
228  size_t indexOf(size_t node);
229 
230  size_t allocateNode();
231 
233  size_t createNode(size_t parent, const BV& bv1, const BV& bv2, void* data);
234 
235  size_t createNode(size_t parent, const BV& bv, void* data);
236 
237  size_t createNode(size_t parent, void* data);
238 
239  void deleteNode(size_t node);
240 
241  void recurseRefit(size_t node);
242 
243  protected:
244  size_t root_node;
246  size_t n_nodes;
248 
249  size_t n_leaves;
250  size_t freelist;
251  unsigned int opath;
252 
254 
255  public:
258 
261 
262  public:
263  static const size_t NULL_NODE = std::numeric_limits<size_t>::max();
264 };
265 
266 template <typename BV>
267 const size_t HierarchyTree<BV>::NULL_NODE;
268 
270 template <typename BV>
271 struct nodeBaseLess {
272  nodeBaseLess(const NodeBase<BV>* nodes_, size_t d_);
273 
274  bool operator()(size_t i, size_t j) const;
275 
276  private:
279 
281  size_t d;
282 };
283 
286 template <typename BV>
287 size_t select(size_t query, size_t node1, size_t node2, NodeBase<BV>* nodes);
288 
291 template <typename BV>
292 size_t select(const BV& query, size_t node1, size_t node2, NodeBase<BV>* nodes);
293 
294 } // namespace implementation_array
295 } // namespace detail
296 } // namespace coal
297 
299 
300 #endif
coal::detail::implementation_array::HierarchyTree::topdown_1
size_t topdown_1(size_t *lbeg, size_t *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_array-inl.h:555
coal::detail::implementation_array::HierarchyTree::extractLeaves
void extractLeaves(size_t root, Node *&leaves) const
extract all the leaves of the tree
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:409
node_base_array.h
coal::detail::implementation_array::HierarchyTree::balanceTopdown
void balanceTopdown()
balance the tree from top
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:363
coal::detail::implementation_array::HierarchyTree::SortByMorton::nodes
Node * nodes
Definition: coal/broadphase/detail/hierarchy_tree_array.h:78
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
coal::detail::implementation_array::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_array-inl.h:403
coal::detail::implementation_array::NodeBase::code
uint32_t code
Definition: coal/broadphase/detail/node_base_array.h:63
coal::detail::implementation_array::HierarchyTree::update
void update(size_t leaf, int lookahead_level=-1)
update one leaf node
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:275
coal::detail::implementation_array::HierarchyTree::empty
bool empty() const
Whether the tree is empty.
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:269
coal::detail::implementation_array::select
size_t select(size_t query, size_t node1, size_t node2, NodeBase< BV > *nodes)
select the node from node1 and node2 which is close to the query-th node in the nodes....
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:933
coal::detail::implementation_array::HierarchyTree::getRoot
size_t getRoot() const
get the root of the tree
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:427
coal::detail::implementation_array::HierarchyTree::SortByMorton::operator()
bool operator()(size_t a, size_t b) const
Definition: coal/broadphase/detail/hierarchy_tree_array.h:67
coal::detail::implementation_array::HierarchyTree::recurseRefit
void recurseRefit(size_t node)
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:869
coal::detail::implementation_array::nodeBaseLess::operator()
bool operator()(size_t i, size_t j) const
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:901
uint32_t
uint32_t
coal::detail::implementation_array::HierarchyTree::init_3
void init_3(Node *leaves, int n_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_array-inl.h:199
coal::detail::implementation_array::NodeBase
Definition: coal/broadphase/detail/node_base_array.h:50
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::detail::implementation_array::HierarchyTree::insert
size_t insert(const BV &bv, void *data)
Initialize the tree by a set of leaves using algorithm with a given level.
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:236
coal::detail::implementation_array::HierarchyTree::freelist
size_t freelist
Definition: coal/broadphase/detail/hierarchy_tree_array.h:250
coal::detail::implementation_array::nodeBaseLess::nodeBaseLess
nodeBaseLess(const NodeBase< BV > *nodes_, size_t d_)
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:894
coal::detail::implementation_array::HierarchyTree::getMaxHeight
size_t getMaxHeight() const
get the max height of the tree
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:321
coal::detail::implementation_array::HierarchyTree::nodes
Node * nodes
Definition: coal/broadphase/detail/hierarchy_tree_array.h:245
coal::detail::implementation_array::HierarchyTree::NULL_NODE
static const size_t NULL_NODE
Definition: coal/broadphase/detail/hierarchy_tree_array.h:263
a
list a
coal::detail::implementation_array::HierarchyTree::opath
unsigned int opath
Definition: coal/broadphase/detail/hierarchy_tree_array.h:251
coal::detail::implementation_array::HierarchyTree::topdown_0
size_t topdown_0(size_t *lbeg, size_t *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_array-inl.h:523
coal::detail::implementation_array::HierarchyTree::createNode
size_t createNode(size_t parent, const BV &bv1, const BV &bv2, void *data)
create one node (leaf or internal)
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:831
coal::detail::implementation_array::HierarchyTree::clear
void clear()
Clear the tree.
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:253
coal::detail::implementation_array::HierarchyTree::topdown
size_t topdown(size_t *lbeg, size_t *lend)
construct a tree for a set of leaves from top
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:508
coal::detail::implementation_array::HierarchyTree::init_1
void init_1(Node *leaves, int n_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_array-inl.h:123
coal::detail::implementation_array::HierarchyTree::SortByMorton::SortByMorton
SortByMorton(Node *nodes_in)
Definition: coal/broadphase/detail/hierarchy_tree_array.h:64
coal::detail::implementation_array::HierarchyTree::removeLeaf
size_t removeLeaf(size_t leaf)
Remove a leaf. The leaf node itself is not deleted yet, but all the unnecessary internal nodes are de...
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:750
coal::detail::implementation_array::HierarchyTree::size
size_t size() const
number of leaves in the tree
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:421
coal::detail::implementation_array::nodeBaseLess::nodes
const NodeBase< BV > * nodes
the nodes array
Definition: coal/broadphase/detail/hierarchy_tree_array.h:278
morton.h
coal::detail::implementation_array::HierarchyTree::getNodes
Node * getNodes() const
get the pointer to the nodes array
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:433
coal::detail::implementation_array::HierarchyTree::mortonRecurse_2
size_t mortonRecurse_2(size_t *lbeg, size_t *lend)
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:693
fwd.hh
coal::detail::implementation_array::HierarchyTree::SortByMorton
Definition: coal/broadphase/detail/hierarchy_tree_array.h:63
coal::detail::implementation_array::HierarchyTree::max_lookahead_level
int max_lookahead_level
Definition: coal/broadphase/detail/hierarchy_tree_array.h:253
coal::detail::implementation_array::nodeBaseLess
Functor comparing two nodes.
Definition: coal/broadphase/detail/hierarchy_tree_array.h:271
coal::detail::implementation_array::HierarchyTree::bu_threshold
int bu_threshold
decide the depth to use expensive bottom-up algorithm
Definition: coal/broadphase/detail/hierarchy_tree_array.h:260
coal::detail::implementation_array::HierarchyTree::bottomup
void bottomup(size_t *lbeg, size_t *lend)
construct a tree for a set of leaves from bottom – very heavy way
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:476
coal::detail::implementation_array::HierarchyTree::remove
void remove(size_t leaf)
Remove a leaf node.
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:245
coal::detail::implementation_array::HierarchyTree::n_leaves
size_t n_leaves
Definition: coal/broadphase/detail/hierarchy_tree_array.h:249
coal::detail::implementation_array::HierarchyTree::fetchLeaves
void fetchLeaves(size_t root, 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_array-inl.h:881
coal::detail::implementation_array::HierarchyTree::getMaxDepth
size_t getMaxDepth() const
get the max depth of the tree
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:329
coal::detail::implementation_array::HierarchyTree::n_nodes
size_t n_nodes
Definition: coal/broadphase/detail/hierarchy_tree_array.h:246
coal::detail::implementation_array::HierarchyTree::mortonRecurse_0
size_t mortonRecurse_0(size_t *lbeg, size_t *lend, const uint32_t &split, int bits)
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:613
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
coal::detail::implementation_array::HierarchyTree::topdown_level
int topdown_level
decide which topdown algorithm to use
Definition: coal/broadphase/detail/hierarchy_tree_array.h:257
coal::detail::implementation_array::HierarchyTree::deleteNode
void deleteNode(size_t node)
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:861
coal::detail::implementation_array::HierarchyTree::allocateNode
size_t allocateNode()
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:807
coal::detail::implementation_array::HierarchyTree::n_nodes_alloc
size_t n_nodes_alloc
Definition: coal/broadphase/detail/hierarchy_tree_array.h:247
coal::detail::implementation_array::HierarchyTree::insertLeaf
void insertLeaf(size_t root, size_t leaf)
Insert a leaf node and also update its ancestors.
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:710
coal::detail::implementation_array::HierarchyTree::~HierarchyTree
~HierarchyTree()
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:71
coal::detail::implementation_array::HierarchyTree::init
void init(Node *leaves, int n_leaves_, int level=0)
Initialize the tree by a set of leaves using algorithm with a given level.
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:77
coal::detail::implementation_array::HierarchyTree::Node
NodeBase< BV > Node
Definition: coal/broadphase/detail/hierarchy_tree_array.h:60
coal::detail::implementation_array::HierarchyTree::print
void print(size_t root, int depth)
print the tree in a recursive way
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:439
hierarchy_tree_array-inl.h
coal::detail::implementation_array::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_array-inl.h:54
coal::detail::implementation_array::HierarchyTree::init_0
void init_0(Node *leaves, int n_leaves_)
init tree from leaves in the topdown manner (topdown_0 or topdown_1)
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:98
coal::detail::implementation_array::HierarchyTree::init_2
void init_2(Node *leaves, int n_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_array-inl.h:161
coal::detail::implementation_array::HierarchyTree
Class for hierarchy tree structure.
Definition: coal/broadphase/detail/hierarchy_tree_array.h:58
coal::detail::implementation_array::HierarchyTree::root_node
size_t root_node
Definition: coal/broadphase/detail/hierarchy_tree_array.h:244
coal::detail::implementation_array::nodeBaseLess::d
size_t d
the dimension to compare
Definition: coal/broadphase/detail/hierarchy_tree_array.h:281
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::detail::implementation_array::HierarchyTree::balanceIncremental
void balanceIncremental(int iterations)
balance the tree in an incremental way
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:385
coal::detail::implementation_array::HierarchyTree::SortByMorton::split
uint32_t split
Definition: coal/broadphase/detail/hierarchy_tree_array.h:79
coal::detail::NodeBase
dynamic AABB tree node
Definition: coal/broadphase/detail/node_base.h:49
coal::detail::implementation_array::HierarchyTree::SortByMorton::SortByMorton
SortByMorton(Node *nodes_in, uint32_t split_in)
Definition: coal/broadphase/detail/hierarchy_tree_array.h:65
coal::detail::implementation_array::HierarchyTree::balanceBottomup
void balanceBottomup()
balance the tree from bottom
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:339
coal::detail::implementation_array::HierarchyTree::mortonRecurse_1
size_t mortonRecurse_1(size_t *lbeg, size_t *lend, const uint32_t &split, int bits)
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:650
coal::detail::implementation_array::HierarchyTree::indexOf
size_t indexOf(size_t node)
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:801
AABB.h
coal::detail::implementation_array::HierarchyTree::update_
void update_(size_t leaf, const BV &bv)
update one leaf node's bounding volume
Definition: coal/broadphase/detail/hierarchy_tree_array-inl.h:785


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