coal/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 COAL_OCTREE_H
40 #define COAL_OCTREE_H
41 
42 #include <algorithm>
43 
44 #include <octomap/octomap.h>
45 #include "coal/fwd.hh"
46 #include "coal/BV/AABB.h"
47 #include "coal/collision_object.h"
48 
49 namespace coal {
50 
53 class COAL_DLLAPI OcTree : public CollisionGeometry {
54  protected:
55  shared_ptr<const octomap::OcTree> tree;
56 
58 
61 
62  public:
63  typedef octomap::OcTreeNode OcTreeNode;
64 
66  explicit OcTree(CoalScalar resolution)
67  : tree(shared_ptr<const octomap::OcTree>(
68  new octomap::OcTree(resolution))) {
69  default_occupancy = tree->getOccupancyThres();
70 
71  // default occupancy/free threshold is consistent with default setting from
72  // octomap
73  occupancy_threshold = tree->getOccupancyThres();
74  free_threshold = 0;
75  }
76 
78  explicit OcTree(const shared_ptr<const octomap::OcTree>& tree_)
79  : tree(tree_) {
80  default_occupancy = tree->getOccupancyThres();
81 
82  // default occupancy/free threshold is consistent with default setting from
83  // octomap
84  occupancy_threshold = tree->getOccupancyThres();
85  free_threshold = 0;
86  }
87 
89  OcTree(const OcTree& other)
90  : CollisionGeometry(other),
91  tree(other.tree),
92  default_occupancy(other.default_occupancy),
93  occupancy_threshold(other.occupancy_threshold),
94  free_threshold(other.free_threshold) {}
95 
97  OcTree* clone() const { return new OcTree(*this); }
98 
100  shared_ptr<const octomap::OcTree> getTree() const { return tree; }
101 
102  void exportAsObjFile(const std::string& filename) const;
103 
106  typedef Eigen::Matrix<float, 3, 1> Vec3sloat;
107  Vec3sloat max_extent, min_extent;
108 
109  octomap::OcTree::iterator it =
110  tree->begin((unsigned char)tree->getTreeDepth());
111  octomap::OcTree::iterator end = tree->end();
112 
113  if (it == end) return;
114 
115  {
116  const octomap::point3d& coord =
117  it.getCoordinate(); // getCoordinate returns a copy
118  max_extent = min_extent = Eigen::Map<const Vec3sloat>(&coord.x());
119  for (++it; it != end; ++it) {
120  const octomap::point3d& coord = it.getCoordinate();
121  const Vec3sloat pos = Eigen::Map<const Vec3sloat>(&coord.x());
122  max_extent = max_extent.array().max(pos.array());
123  min_extent = min_extent.array().min(pos.array());
124  }
125  }
126 
127  // Account for the size of the boxes.
128  const CoalScalar resolution = tree->getResolution();
129  max_extent.array() += float(resolution / 2.);
130  min_extent.array() -= float(resolution / 2.);
131 
132  aabb_local =
133  AABB(min_extent.cast<CoalScalar>(), max_extent.cast<CoalScalar>());
134  aabb_center = aabb_local.center();
135  aabb_radius = (aabb_local.min_ - aabb_center).norm();
136  }
137 
139  AABB getRootBV() const {
140  CoalScalar delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2;
141 
142  // std::cout << "octree size " << delta << std::endl;
143  return AABB(Vec3s(-delta, -delta, -delta), Vec3s(delta, delta, delta));
144  }
145 
147  unsigned int getTreeDepth() const { return tree->getTreeDepth(); }
148 
150  unsigned long size() const { return tree->size(); }
151 
153  CoalScalar 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<Vec6s> toBoxes() const {
179  std::vector<Vec6s> 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  CoalScalar x = it.getX();
188  CoalScalar y = it.getY();
189  CoalScalar z = it.getZ();
190  CoalScalar size = it.getSize();
191  CoalScalar c = (*it).getOccupancy();
192  CoalScalar t = tree->getOccupancyThres();
193 
194  Vec6s 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> Vec3sloat;
205  const size_t total_size = (tree->size() * sizeof(CoalScalar) * 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 Vec3s box_pos =
214  Eigen::Map<Vec3sloat>(&it.getCoordinate().x()).cast<CoalScalar>();
215  if (isNodeOccupied(&*it))
216  std::copy(box_pos.data(), box_pos.data() + sizeof(CoalScalar) * 3,
217  std::back_inserter(bytes));
218  }
219 
220  return bytes;
221  }
222 
225  CoalScalar getOccupancyThres() const { return occupancy_threshold; }
226 
229  CoalScalar getFreeThres() const { return free_threshold; }
230 
231  CoalScalar getDefaultOccupancy() const { return default_occupancy; }
232 
233  void setCellDefaultOccupancy(CoalScalar d) { default_occupancy = d; }
234 
235  void setOccupancyThres(CoalScalar d) { occupancy_threshold = d; }
236 
237  void setFreeThres(CoalScalar 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 
334 COAL_DLLAPI OcTreePtr_t
335 makeOctree(const Eigen::Matrix<CoalScalar, Eigen::Dynamic, 3>& point_cloud,
336  const CoalScalar resolution);
337 
338 } // namespace coal
339 
340 #endif
coal::OcTree::getNodeChild
const OcTreeNode * getNodeChild(const OcTreeNode *node, unsigned int childIdx) const
Definition: coal/octree.h:249
coal::OcTree::toBoxes
std::vector< Vec6s > toBoxes() const
transform the octree into a bunch of boxes; uncertainty information is kept in the boxes....
Definition: coal/octree.h:178
coal::OcTree::getNodeType
NODE_TYPE getNodeType() const
return node type, it is an octree
Definition: coal/octree.h:280
coal::Vec3s
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
Definition: coal/data_types.h:77
collision_manager.box
box
Definition: collision_manager.py:11
coal::OcTree::tree
shared_ptr< const octomap::OcTree > tree
Definition: coal/octree.h:55
coal::OT_OCTREE
@ OT_OCTREE
Definition: coal/collision_object.h:56
y
y
coal::OcTree::getRoot
OcTreeNode * getRoot() const
get the root node of the octree
Definition: coal/octree.h:156
coal::OcTree::getRootBV
AABB getRootBV() const
get the bounding volume for the root
Definition: coal/octree.h:139
coal::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: coal/collision_object.h:64
coal
Main namespace.
Definition: coal/broadphase/broadphase_bruteforce.h:44
coal::OcTree::occupancy_threshold
CoalScalar occupancy_threshold
Definition: coal/octree.h:59
coal::OcTree::free_threshold
CoalScalar free_threshold
Definition: coal/octree.h:60
coal::OcTree::size
unsigned long size() const
Returns the size of the octree.
Definition: coal/octree.h:150
coal::OcTree::tobytes
std::vector< uint8_t > tobytes() const
Returns a byte description of *this.
Definition: coal/octree.h:203
coal::makeOctree
COAL_DLLAPI OcTreePtr_t makeOctree(const Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3 > &point_cloud, const CoalScalar resolution)
Build an OcTree from a point cloud and a given resolution.
Definition: src/octree.cpp:188
coal::OcTree::isNodeOccupied
bool isNodeOccupied(const OcTreeNode *node) const
whether one node is completely occupied
Definition: coal/octree.h:159
collision_object.h
coal::OcTree::getResolution
CoalScalar getResolution() const
Returns the resolution of the octree.
Definition: coal/octree.h:153
coal::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: coal/collision_object.h:94
coal::OcTree::getObjectType
OBJECT_TYPE getObjectType() const
return object type, it is an octree
Definition: coal/octree.h:277
coal::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: coal/BV/AABB.h:55
coal::OcTree::nodeHasChildren
bool nodeHasChildren(const OcTreeNode *node) const
return true if node has at least one child
Definition: coal/octree.h:268
coal::OcTree::isNodeFree
bool isNodeFree(const OcTreeNode *node) const
whether one node is completely free
Definition: coal/octree.h:165
coal::AABB::max_
Vec3s max_
The max point in the AABB.
Definition: coal/BV/AABB.h:60
coal::OcTree::getNodeChild
OcTreeNode * getNodeChild(OcTreeNode *node, unsigned int childIdx)
Definition: coal/octree.h:240
d
d
c
c
coal::OcTree::OcTree
OcTree(CoalScalar resolution)
construct octree with a given resolution
Definition: coal/octree.h:66
coal::OcTree::getOccupancyThres
CoalScalar getOccupancyThres() const
the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
Definition: coal/octree.h:225
collision-bench.filename
filename
Definition: collision-bench.py:6
fwd.hh
coal::computeChildBV
static void computeChildBV(const AABB &root_bv, unsigned int i, AABB &child_bv)
compute the bounding volume of an octree node's i-th child
Definition: coal/octree.h:299
coal::Vec6s
Eigen::Matrix< CoalScalar, 6, 1 > Vec6s
Definition: coal/data_types.h:79
x
x
coal::OcTree::setFreeThres
void setFreeThres(CoalScalar d)
Definition: coal/octree.h:237
coal::OcTree::setOccupancyThres
void setOccupancyThres(CoalScalar d)
Definition: coal/octree.h:235
coal::OcTree::nodeChildExists
bool nodeChildExists(const OcTreeNode *node, unsigned int childIdx) const
return true if the child at childIdx exists
Definition: coal/octree.h:259
coal::OcTree::computeLocalAABB
void computeLocalAABB()
compute the AABB for the octree in its local coordinate system
Definition: coal/octree.h:105
octree.pos
pos
Definition: octree.py:7
coal::OcTree::setCellDefaultOccupancy
void setCellDefaultOccupancy(CoalScalar d)
Definition: coal/octree.h:233
coal::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: coal/collision_object.h:52
coal::OcTree::isNodeUncertain
bool isNodeUncertain(const OcTreeNode *node) const
whether one node is uncertain
Definition: coal/octree.h:171
coal::AABB::min_
Vec3s min_
The min point in the AABB.
Definition: coal/BV/AABB.h:58
coal::OcTreePtr_t
shared_ptr< OcTree > OcTreePtr_t
Definition: include/coal/fwd.hh:144
coal::GEOM_OCTREE
@ GEOM_OCTREE
Definition: coal/collision_object.h:83
coal::OcTree::OcTreeNode
octomap::OcTreeNode OcTreeNode
Definition: coal/octree.h:63
coal::OcTree
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: coal/octree.h:53
coal::OcTree::isEqual
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
Definition: coal/octree.h:283
coal::OcTree::getDefaultOccupancy
CoalScalar getDefaultOccupancy() const
Definition: coal/octree.h:231
coal::OcTree::getTree
shared_ptr< const octomap::OcTree > getTree() const
Returns the tree associated to the underlying octomap OcTree.
Definition: coal/octree.h:100
coal::OcTree::clone
OcTree * clone() const
Clone *this into a new Octree.
Definition: coal/octree.h:97
octomap
Definition: utility.h:80
coal::OcTree::getFreeThres
CoalScalar getFreeThres() const
the threshold used to decide whether one node is free, this is NOT the octree free_threshold
Definition: coal/octree.h:229
coal::OcTree::default_occupancy
CoalScalar default_occupancy
Definition: coal/octree.h:57
coal::OcTree::OcTree
OcTree(const shared_ptr< const octomap::OcTree > &tree_)
construct octree from octomap
Definition: coal/octree.h:78
t
dictionary t
coal::CoalScalar
double CoalScalar
Definition: coal/data_types.h:76
coal::OcTree::getTreeDepth
unsigned int getTreeDepth() const
Returns the depth of the octree.
Definition: coal/octree.h:147
coal::OcTree::OcTree
OcTree(const OcTree &other)
&#160;
Definition: coal/octree.h:89
AABB.h


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