hpp-fcl  3.0.0
HPP fork of FCL -- The Flexible Collision Library
octree.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-2015, Open Source Robotics Foundation
6  * Copyright (c) 2022-2024, Inria
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Open Source Robotics Foundation nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  */
36 
39 #ifndef HPP_FCL_OCTREE_H
40 #define HPP_FCL_OCTREE_H
41 
42 #include <algorithm>
43 
44 #include <octomap/octomap.h>
45 #include <hpp/fcl/fwd.hh>
46 #include <hpp/fcl/BV/AABB.h>
48 
49 namespace hpp {
50 namespace fcl {
51 
55  protected:
56  shared_ptr<const octomap::OcTree> tree;
57 
59 
62 
63  public:
64  typedef octomap::OcTreeNode OcTreeNode;
65 
67  explicit OcTree(FCL_REAL resolution)
68  : tree(shared_ptr<const octomap::OcTree>(
69  new octomap::OcTree(resolution))) {
70  default_occupancy = tree->getOccupancyThres();
71 
72  // default occupancy/free threshold is consistent with default setting from
73  // octomap
74  occupancy_threshold = tree->getOccupancyThres();
75  free_threshold = 0;
76  }
77 
79  explicit OcTree(const shared_ptr<const octomap::OcTree>& tree_)
80  : tree(tree_) {
81  default_occupancy = tree->getOccupancyThres();
82 
83  // default occupancy/free threshold is consistent with default setting from
84  // octomap
85  occupancy_threshold = tree->getOccupancyThres();
86  free_threshold = 0;
87  }
88 
90  OcTree(const OcTree& other)
91  : CollisionGeometry(other),
92  tree(other.tree),
93  default_occupancy(other.default_occupancy),
94  occupancy_threshold(other.occupancy_threshold),
95  free_threshold(other.free_threshold) {}
96 
98  OcTree* clone() const { return new OcTree(*this); }
99 
101  shared_ptr<const octomap::OcTree> getTree() const { return tree; }
102 
103  void exportAsObjFile(const std::string& filename) const;
104 
107  typedef Eigen::Matrix<float, 3, 1> Vec3float;
108  Vec3float max_extent, min_extent;
109 
110  octomap::OcTree::iterator it =
111  tree->begin((unsigned char)tree->getTreeDepth());
112  octomap::OcTree::iterator end = tree->end();
113 
114  if (it == end) return;
115 
116  {
117  const octomap::point3d& coord =
118  it.getCoordinate(); // getCoordinate returns a copy
119  max_extent = min_extent = Eigen::Map<const Vec3float>(&coord.x());
120  for (++it; it != end; ++it) {
121  const octomap::point3d& coord = it.getCoordinate();
122  const Vec3float pos = Eigen::Map<const Vec3float>(&coord.x());
123  max_extent = max_extent.array().max(pos.array());
124  min_extent = min_extent.array().min(pos.array());
125  }
126  }
127 
128  // Account for the size of the boxes.
129  const FCL_REAL resolution = tree->getResolution();
130  max_extent.array() += float(resolution / 2.);
131  min_extent.array() -= float(resolution / 2.);
132 
133  aabb_local = AABB(min_extent.cast<FCL_REAL>(), max_extent.cast<FCL_REAL>());
134  aabb_center = aabb_local.center();
135  aabb_radius = (aabb_local.min_ - aabb_center).norm();
136  }
137 
139  AABB getRootBV() const {
140  FCL_REAL delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2;
141 
142  // std::cout << "octree size " << delta << std::endl;
143  return AABB(Vec3f(-delta, -delta, -delta), Vec3f(delta, delta, delta));
144  }
145 
147  unsigned int getTreeDepth() const { return tree->getTreeDepth(); }
148 
150  unsigned long size() const { return tree->size(); }
151 
153  FCL_REAL getResolution() const { return tree->getResolution(); }
154 
156  OcTreeNode* getRoot() const { return tree->getRoot(); }
157 
159  bool isNodeOccupied(const OcTreeNode* node) const {
160  // return tree->isNodeOccupied(node);
161  return node->getOccupancy() >= occupancy_threshold;
162  }
163 
165  bool isNodeFree(const OcTreeNode* node) const {
166  // return false; // default no definitely free node
167  return node->getOccupancy() <= free_threshold;
168  }
169 
171  bool isNodeUncertain(const OcTreeNode* node) const {
172  return (!isNodeOccupied(node)) && (!isNodeFree(node));
173  }
174 
178  std::vector<Vec6f> toBoxes() const {
179  std::vector<Vec6f> boxes;
180  boxes.reserve(tree->size() / 2);
181  for (octomap::OcTree::iterator
182  it = tree->begin((unsigned char)tree->getTreeDepth()),
183  end = tree->end();
184  it != end; ++it) {
185  // if(tree->isNodeOccupied(*it))
186  if (isNodeOccupied(&*it)) {
187  FCL_REAL x = it.getX();
188  FCL_REAL y = it.getY();
189  FCL_REAL z = it.getZ();
190  FCL_REAL size = it.getSize();
191  FCL_REAL c = (*it).getOccupancy();
192  FCL_REAL t = tree->getOccupancyThres();
193 
194  Vec6f box;
195  box << x, y, z, size, c, t;
196  boxes.push_back(box);
197  }
198  }
199  return boxes;
200  }
201 
203  std::vector<uint8_t> tobytes() const {
204  typedef Eigen::Matrix<float, 3, 1> Vec3float;
205  const size_t total_size = (tree->size() * sizeof(FCL_REAL) * 3) / 2;
206  std::vector<uint8_t> bytes;
207  bytes.reserve(total_size);
208 
209  for (octomap::OcTree::iterator
210  it = tree->begin((unsigned char)tree->getTreeDepth()),
211  end = tree->end();
212  it != end; ++it) {
213  const Vec3f box_pos =
214  Eigen::Map<Vec3float>(&it.getCoordinate().x()).cast<FCL_REAL>();
215  if (isNodeOccupied(&*it))
216  std::copy(box_pos.data(), box_pos.data() + sizeof(FCL_REAL) * 3,
217  std::back_inserter(bytes));
218  }
219 
220  return bytes;
221  }
222 
225  FCL_REAL getOccupancyThres() const { return occupancy_threshold; }
226 
229  FCL_REAL getFreeThres() const { return free_threshold; }
230 
231  FCL_REAL getDefaultOccupancy() const { return default_occupancy; }
232 
233  void setCellDefaultOccupancy(FCL_REAL d) { default_occupancy = d; }
234 
235  void setOccupancyThres(FCL_REAL d) { occupancy_threshold = d; }
236 
237  void setFreeThres(FCL_REAL d) { free_threshold = d; }
238 
240  OcTreeNode* getNodeChild(OcTreeNode* node, unsigned int childIdx) {
241 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
242  return tree->getNodeChild(node, childIdx);
243 #else
244  return node->getChild(childIdx);
245 #endif
246  }
247 
249  const OcTreeNode* getNodeChild(const OcTreeNode* node,
250  unsigned int childIdx) const {
251 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
252  return tree->getNodeChild(node, childIdx);
253 #else
254  return node->getChild(childIdx);
255 #endif
256  }
257 
259  bool nodeChildExists(const OcTreeNode* node, unsigned int childIdx) const {
260 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
261  return tree->nodeChildExists(node, childIdx);
262 #else
263  return node->childExists(childIdx);
264 #endif
265  }
266 
268  bool nodeHasChildren(const OcTreeNode* node) const {
269 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
270  return tree->nodeHasChildren(node);
271 #else
272  return node->hasChildren();
273 #endif
274  }
275 
277  OBJECT_TYPE getObjectType() const { return OT_OCTREE; }
278 
280  NODE_TYPE getNodeType() const { return GEOM_OCTREE; }
281 
282  private:
283  virtual bool isEqual(const CollisionGeometry& _other) const {
284  const OcTree* other_ptr = dynamic_cast<const OcTree*>(&_other);
285  if (other_ptr == nullptr) return false;
286  const OcTree& other = *other_ptr;
287 
288  return (tree.get() == other.tree.get() || toBoxes() == other.toBoxes()) &&
289  default_occupancy == other.default_occupancy &&
290  occupancy_threshold == other.occupancy_threshold &&
291  free_threshold == other.free_threshold;
292  }
293 
294  public:
295  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
296 };
297 
299 static inline void computeChildBV(const AABB& root_bv, unsigned int i,
300  AABB& child_bv) {
301  if (i & 1) {
302  child_bv.min_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
303  child_bv.max_[0] = root_bv.max_[0];
304  } else {
305  child_bv.min_[0] = root_bv.min_[0];
306  child_bv.max_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
307  }
308 
309  if (i & 2) {
310  child_bv.min_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
311  child_bv.max_[1] = root_bv.max_[1];
312  } else {
313  child_bv.min_[1] = root_bv.min_[1];
314  child_bv.max_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
315  }
316 
317  if (i & 4) {
318  child_bv.min_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
319  child_bv.max_[2] = root_bv.max_[2];
320  } else {
321  child_bv.min_[2] = root_bv.min_[2];
322  child_bv.max_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
323  }
324 }
325 
335 makeOctree(const Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 3>& point_cloud,
336  const FCL_REAL resolution);
337 
338 } // namespace fcl
339 
340 } // namespace hpp
341 
342 #endif
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: AABB.h:56
The geometry for the object for collision or distance computation.
Definition: collision_object.h:95
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: octree.h:54
AABB getRootBV() const
get the bounding volume for the root
Definition: octree.h:139
unsigned long size() const
Returns the size of the octree.
Definition: octree.h:150
OcTree(FCL_REAL resolution)
construct octree with a given resolution
Definition: octree.h:67
shared_ptr< const octomap::OcTree > tree
Definition: octree.h:56
OBJECT_TYPE getObjectType() const
return object type, it is an octree
Definition: octree.h:277
FCL_REAL default_occupancy
Definition: octree.h:58
bool isNodeOccupied(const OcTreeNode *node) const
whether one node is completely occupied
Definition: octree.h:159
FCL_REAL getFreeThres() const
the threshold used to decide whether one node is free, this is NOT the octree free_threshold
Definition: octree.h:229
FCL_REAL getDefaultOccupancy() const
Definition: octree.h:231
OcTree(const OcTree &other)
&#160;
Definition: octree.h:90
octomap::OcTreeNode OcTreeNode
Definition: octree.h:64
void setCellDefaultOccupancy(FCL_REAL d)
Definition: octree.h:233
OcTreeNode * getNodeChild(OcTreeNode *node, unsigned int childIdx)
Definition: octree.h:240
OcTreeNode * getRoot() const
get the root node of the octree
Definition: octree.h:156
void exportAsObjFile(const std::string &filename) const
unsigned int getTreeDepth() const
Returns the depth of the octree.
Definition: octree.h:147
void setFreeThres(FCL_REAL d)
Definition: octree.h:237
std::vector< Vec6f > toBoxes() const
transform the octree into a bunch of boxes; uncertainty information is kept in the boxes....
Definition: octree.h:178
bool isNodeUncertain(const OcTreeNode *node) const
whether one node is uncertain
Definition: octree.h:171
OcTree * clone() const
Clone *this into a new Octree.
Definition: octree.h:98
void setOccupancyThres(FCL_REAL d)
Definition: octree.h:235
bool nodeChildExists(const OcTreeNode *node, unsigned int childIdx) const
return true if the child at childIdx exists
Definition: octree.h:259
FCL_REAL getOccupancyThres() const
the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
Definition: octree.h:225
FCL_REAL getResolution() const
Returns the resolution of the octree.
Definition: octree.h:153
const OcTreeNode * getNodeChild(const OcTreeNode *node, unsigned int childIdx) const
Definition: octree.h:249
void computeLocalAABB()
compute the AABB for the octree in its local coordinate system
Definition: octree.h:106
FCL_REAL occupancy_threshold
Definition: octree.h:60
bool nodeHasChildren(const OcTreeNode *node) const
return true if node has at least one child
Definition: octree.h:268
OcTree(const shared_ptr< const octomap::OcTree > &tree_)
construct octree from octomap
Definition: octree.h:79
shared_ptr< const octomap::OcTree > getTree() const
Returns the tree associated to the underlying octomap OcTree.
Definition: octree.h:101
NODE_TYPE getNodeType() const
return node type, it is an octree
Definition: octree.h:280
bool isNodeFree(const OcTreeNode *node) const
whether one node is completely free
Definition: octree.h:165
std::vector< uint8_t > tobytes() const
Returns a byte description of *this.
Definition: octree.h:203
FCL_REAL free_threshold
Definition: octree.h:61
#define HPP_FCL_DLLAPI
Definition: config.hh:88
@ OT_OCTREE
Definition: collision_object.h:57
@ GEOM_OCTREE
Definition: collision_object.h:84
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:67
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: collision_object.h:53
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_object.h:65
shared_ptr< OcTree > OcTreePtr_t
Definition: fwd.hh:145
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const FCL_REAL tol=std::numeric_limits< FCL_REAL >::epsilon() *100)
Definition: tools.h:205
OcTreePtr_t makeOctree(const Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 3 > &point_cloud, const FCL_REAL resolution)
Build an OcTree from a point cloud and a given resolution.
double FCL_REAL
Definition: data_types.h:66
Eigen::Matrix< FCL_REAL, 6, 1 > Vec6f
Definition: data_types.h:69
Main namespace.
Definition: broadphase_bruteforce.h:44