hpp-fcl  1.4.4
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  * 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 
39 #ifndef HPP_FCL_OCTREE_H
40 #define HPP_FCL_OCTREE_H
41 
42 
43 #include <boost/shared_ptr.hpp>
44 #include <boost/array.hpp>
45 
46 #include <octomap/octomap.h>
47 #include <hpp/fcl/BV/AABB.h>
49 
50 namespace hpp
51 {
52 namespace fcl
53 {
54 
56 class OcTree : public CollisionGeometry
57 {
58 private:
59  boost::shared_ptr<const octomap::OcTree> tree;
60 
61  FCL_REAL default_occupancy;
62 
63  FCL_REAL occupancy_threshold;
64  FCL_REAL free_threshold;
65 
66 public:
67 
68  typedef octomap::OcTreeNode OcTreeNode;
69 
71  OcTree(FCL_REAL resolution) : tree(boost::shared_ptr<const octomap::OcTree>(new octomap::OcTree(resolution)))
72  {
73  default_occupancy = tree->getOccupancyThres();
74 
75  // default occupancy/free threshold is consistent with default setting from octomap
76  occupancy_threshold = tree->getOccupancyThres();
77  free_threshold = 0;
78  }
79 
81  OcTree(const boost::shared_ptr<const octomap::OcTree>& tree_) : tree(tree_)
82  {
83  default_occupancy = tree->getOccupancyThres();
84 
85  // default occupancy/free threshold is consistent with default setting from octomap
86  occupancy_threshold = tree->getOccupancyThres();
87  free_threshold = 0;
88  }
89 
92  {
96  }
97 
99  AABB getRootBV() const
100  {
101  FCL_REAL delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2;
102 
103  // std::cout << "octree size " << delta << std::endl;
104  return AABB(Vec3f(-delta, -delta, -delta), Vec3f(delta, delta, delta));
105  }
106 
108  OcTreeNode* getRoot() const
109  {
110  return tree->getRoot();
111  }
112 
114  bool isNodeOccupied(const OcTreeNode* node) const
115  {
116  // return tree->isNodeOccupied(node);
117  return node->getOccupancy() >= occupancy_threshold;
118  }
119 
121  bool isNodeFree(const OcTreeNode* node) const
122  {
123  // return false; // default no definitely free node
124  return node->getOccupancy() <= free_threshold;
125  }
126 
128  bool isNodeUncertain(const OcTreeNode* node) const
129  {
130  return (!isNodeOccupied(node)) && (!isNodeFree(node));
131  }
132 
135  std::vector<boost::array<FCL_REAL, 6> > toBoxes() const
136  {
137  std::vector<boost::array<FCL_REAL, 6> > boxes;
138  boxes.reserve(tree->size() / 2);
139  for(octomap::OcTree::iterator it =
140  tree->begin((unsigned char) tree->getTreeDepth()), end = tree->end();
141  it != end;
142  ++it)
143  {
144  // if(tree->isNodeOccupied(*it))
145  if(isNodeOccupied(&*it))
146  {
147  FCL_REAL size = it.getSize();
148  FCL_REAL x = it.getX();
149  FCL_REAL y = it.getY();
150  FCL_REAL z = it.getZ();
151  FCL_REAL c = (*it).getOccupancy();
152  FCL_REAL t = tree->getOccupancyThres();
153 
154  boost::array<FCL_REAL, 6> box = {{x, y, z, size, c, t}};
155  boxes.push_back(box);
156  }
157  }
158  return boxes;
159  }
160 
163  {
164  return occupancy_threshold;
165  }
166 
169  {
170  return free_threshold;
171  }
172 
174  {
175  return default_occupancy;
176  }
177 
179  {
180  default_occupancy = d;
181  }
182 
184  {
185  occupancy_threshold = d;
186  }
187 
189  {
190  free_threshold = d;
191  }
192 
194  OcTreeNode* getNodeChild(OcTreeNode* node, unsigned int childIdx)
195  {
196 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
197  return tree->getNodeChild(node, childIdx);
198 #else
199  return node->getChild(childIdx);
200 #endif
201  }
202 
204  const OcTreeNode* getNodeChild(const OcTreeNode* node, unsigned int childIdx) const
205  {
206 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
207  return tree->getNodeChild(node, childIdx);
208 #else
209  return node->getChild(childIdx);
210 #endif
211  }
212 
214  bool nodeChildExists(const OcTreeNode* node, unsigned int childIdx) const
215  {
216 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
217  return tree->nodeChildExists(node, childIdx);
218 #else
219  return node->childExists(childIdx);
220 #endif
221  }
222 
224  bool nodeHasChildren(const OcTreeNode* node) const
225  {
226 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
227  return tree->nodeHasChildren(node);
228 #else
229  return node->hasChildren();
230 #endif
231  }
232 
234  OBJECT_TYPE getObjectType() const { return OT_OCTREE; }
235 
237  NODE_TYPE getNodeType() const { return GEOM_OCTREE; }
238 };
239 
241 static inline void computeChildBV(const AABB& root_bv, unsigned int i, AABB& child_bv)
242 {
243  if(i&1)
244  {
245  child_bv.min_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
246  child_bv.max_[0] = root_bv.max_[0];
247  }
248  else
249  {
250  child_bv.min_[0] = root_bv.min_[0];
251  child_bv.max_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
252  }
253 
254  if(i&2)
255  {
256  child_bv.min_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
257  child_bv.max_[1] = root_bv.max_[1];
258  }
259  else
260  {
261  child_bv.min_[1] = root_bv.min_[1];
262  child_bv.max_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
263  }
264 
265  if(i&4)
266  {
267  child_bv.min_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
268  child_bv.max_[2] = root_bv.max_[2];
269  }
270  else
271  {
272  child_bv.min_[2] = root_bv.min_[2];
273  child_bv.max_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
274  }
275 }
276 
277 
278 
279 }
280 
281 } // namespace hpp
282 
283 #endif
bool isNodeFree(const OcTreeNode *node) const
whether one node is completely free
Definition: octree.h:121
OcTreeNode * getRoot() const
get the root node of the octree
Definition: octree.h:108
FCL_REAL getOccupancyThres() const
the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold ...
Definition: octree.h:162
Vec3f min_
The min point in the AABB.
Definition: AABB.h:59
std::vector< boost::array< FCL_REAL, 6 > > toBoxes() const
transform the octree into a bunch of boxes; uncertainty information is kept in the boxes...
Definition: octree.h:135
Vec3f center() const
Center of the AABB.
Definition: AABB.h:157
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: collision_object.h:53
Main namespace.
Definition: AABB.h:43
OcTree(FCL_REAL resolution)
construct octree with a given resolution
Definition: octree.h:71
FCL_REAL getDefaultOccupancy() const
Definition: octree.h:173
AABB getRootBV() const
get the bounding volume for the root
Definition: octree.h:99
FCL_REAL getFreeThres() const
the threshold used to decide whether one node is occupied, this is NOT the octree free_threshold ...
Definition: octree.h:168
Definition: collision_object.h:57
void setOccupancyThres(FCL_REAL d)
Definition: octree.h:183
Octree is one type of collision geometry which can encode uncertainty information in the sensor data...
Definition: octree.h:56
octomap::OcTreeNode OcTreeNode
Definition: octree.h:68
OcTree(const boost::shared_ptr< const octomap::OcTree > &tree_)
construct octree from octomap
Definition: octree.h:81
bool isNodeUncertain(const OcTreeNode *node) const
whether one node is uncertain
Definition: octree.h:128
AABB aabb_local
AABB in local coordinate, used for tight AABB when only translation transform.
Definition: collision_object.h:113
double FCL_REAL
Definition: data_types.h:68
OcTreeNode * getNodeChild(OcTreeNode *node, unsigned int childIdx)
Definition: octree.h:194
const OcTreeNode * getNodeChild(const OcTreeNode *node, unsigned int childIdx) const
Definition: octree.h:204
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: AABB.h:55
FCL_REAL aabb_radius
AABB radius.
Definition: collision_object.h:110
Vec3f max_
The max point in the AABB.
Definition: AABB.h:61
Definition: collision_object.h:53
OBJECT_TYPE getObjectType() const
return object type, it is an octree
Definition: octree.h:234
void setCellDefaultOccupancy(FCL_REAL d)
Definition: octree.h:178
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, capsule, cone, cylinder, convex, plane, triangle), and octree
Definition: collision_object.h:56
Vec3f aabb_center
AABB center in local coordinate.
Definition: collision_object.h:107
NODE_TYPE getNodeType() const
return node type, it is an octree
Definition: octree.h:237
void computeLocalAABB()
compute the AABB for the octree in its local coordinate system
Definition: octree.h:91
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:73
The geometry for the object for collision or distance computation.
Definition: collision_object.h:63
bool isNodeOccupied(const OcTreeNode *node) const
whether one node is completely occupied
Definition: octree.h:114
bool nodeChildExists(const OcTreeNode *node, unsigned int childIdx) const
return true if the child at childIdx exists
Definition: octree.h:214
void setFreeThres(FCL_REAL d)
Definition: octree.h:188
bool nodeHasChildren(const OcTreeNode *node) const
return true if node has at least one child
Definition: octree.h:224