.. _program_listing_file__tmp_ws_src_hpp-fcl_include_hpp_fcl_broadphase_detail_hierarchy_tree_array.h: Program Listing for File hierarchy_tree_array.h =============================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/hpp-fcl/include/hpp/fcl/broadphase/detail/hierarchy_tree_array.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* * Software License Agreement (BSD License) * * Copyright (c) 2011-2014, Willow Garage, Inc. * Copyright (c) 2014-2016, Open Source Robotics Foundation * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Open Source Robotics Foundation nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef HPP_FCL_HIERARCHY_TREE_ARRAY_H #define HPP_FCL_HIERARCHY_TREE_ARRAY_H #include #include #include #include "hpp/fcl/fwd.hh" #include "hpp/fcl/BV/AABB.h" #include "hpp/fcl/broadphase/detail/morton.h" #include "hpp/fcl/broadphase/detail/node_base_array.h" namespace hpp { namespace fcl { namespace detail { namespace implementation_array { template class HierarchyTree { public: typedef NodeBase Node; private: struct SortByMorton { SortByMorton(Node* nodes_in) : nodes(nodes_in) {} SortByMorton(Node* nodes_in, uint32_t split_in) : nodes(nodes_in), split(split_in) {} bool operator()(size_t a, size_t b) const { if ((a != NULL_NODE) && (b != NULL_NODE)) return nodes[a].code < nodes[b].code; else if (a == NULL_NODE) return split < nodes[b].code; else if (b == NULL_NODE) return nodes[a].code < split; return false; } Node* nodes{}; uint32_t split{}; }; public: HierarchyTree(int bu_threshold_ = 16, int topdown_level_ = 0); ~HierarchyTree(); void init(Node* leaves, int n_leaves_, int level = 0); size_t insert(const BV& bv, void* data); void remove(size_t leaf); void clear(); bool empty() const; void update(size_t leaf, int lookahead_level = -1); bool update(size_t leaf, const BV& bv); bool update(size_t leaf, const BV& bv, const Vec3f& vel, FCL_REAL margin); bool update(size_t leaf, const BV& bv, const Vec3f& vel); size_t getMaxHeight() const; size_t getMaxDepth() const; void balanceBottomup(); void balanceTopdown(); void balanceIncremental(int iterations); void refit(); void extractLeaves(size_t root, Node*& leaves) const; size_t size() const; size_t getRoot() const; Node* getNodes() const; void print(size_t root, int depth); private: void bottomup(size_t* lbeg, size_t* lend); size_t topdown(size_t* lbeg, size_t* lend); size_t getMaxHeight(size_t node) const; void getMaxDepth(size_t node, size_t depth, size_t& max_depth) const; size_t topdown_0(size_t* lbeg, size_t* lend); size_t topdown_1(size_t* lbeg, size_t* lend); void init_0(Node* leaves, int n_leaves_); void init_1(Node* leaves, int n_leaves_); void init_2(Node* leaves, int n_leaves_); void init_3(Node* leaves, int n_leaves_); size_t mortonRecurse_0(size_t* lbeg, size_t* lend, const uint32_t& split, int bits); size_t mortonRecurse_1(size_t* lbeg, size_t* lend, const uint32_t& split, int bits); size_t mortonRecurse_2(size_t* lbeg, size_t* lend); void update_(size_t leaf, const BV& bv); void insertLeaf(size_t root, size_t leaf); size_t removeLeaf(size_t leaf); void fetchLeaves(size_t root, Node*& leaves, int depth = -1); size_t indexOf(size_t node); size_t allocateNode(); size_t createNode(size_t parent, const BV& bv1, const BV& bv2, void* data); size_t createNode(size_t parent, const BV& bv, void* data); size_t createNode(size_t parent, void* data); void deleteNode(size_t node); void recurseRefit(size_t node); protected: size_t root_node; Node* nodes; size_t n_nodes; size_t n_nodes_alloc; size_t n_leaves; size_t freelist; unsigned int opath; int max_lookahead_level; public: int topdown_level; int bu_threshold; public: static const size_t NULL_NODE = std::numeric_limits::max(); }; template const size_t HierarchyTree::NULL_NODE; template struct nodeBaseLess { nodeBaseLess(const NodeBase* nodes_, size_t d_); bool operator()(size_t i, size_t j) const; private: const NodeBase* nodes; size_t d; }; template size_t select(size_t query, size_t node1, size_t node2, NodeBase* nodes); template size_t select(const BV& query, size_t node1, size_t node2, NodeBase* nodes); } // namespace implementation_array } // namespace detail } // namespace fcl } // namespace hpp #include "hpp/fcl/broadphase/detail/hierarchy_tree_array-inl.h" #endif