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 |
|
|
|
36 |
|
|
/** \author Jia Pan */ |
37 |
|
|
|
38 |
|
|
#ifndef HPP_FCL_OCTREE_H |
39 |
|
|
#define HPP_FCL_OCTREE_H |
40 |
|
|
|
41 |
|
|
#include <boost/array.hpp> |
42 |
|
|
|
43 |
|
|
#include <octomap/octomap.h> |
44 |
|
|
#include <hpp/fcl/fwd.hh> |
45 |
|
|
#include <hpp/fcl/BV/AABB.h> |
46 |
|
|
#include <hpp/fcl/collision_object.h> |
47 |
|
|
|
48 |
|
|
namespace hpp { |
49 |
|
|
namespace fcl { |
50 |
|
|
|
51 |
|
|
/// @brief Octree is one type of collision geometry which can encode uncertainty |
52 |
|
|
/// information in the sensor data. |
53 |
|
|
class HPP_FCL_DLLAPI OcTree : public CollisionGeometry { |
54 |
|
|
private: |
55 |
|
|
shared_ptr<const octomap::OcTree> tree; |
56 |
|
|
|
57 |
|
|
FCL_REAL default_occupancy; |
58 |
|
|
|
59 |
|
|
FCL_REAL occupancy_threshold; |
60 |
|
|
FCL_REAL free_threshold; |
61 |
|
|
|
62 |
|
|
public: |
63 |
|
|
typedef octomap::OcTreeNode OcTreeNode; |
64 |
|
|
|
65 |
|
|
/// @brief construct octree with a given resolution |
66 |
|
|
explicit OcTree(FCL_REAL 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 |
|
|
|
77 |
|
|
/// @brief construct octree from octomap |
78 |
|
1 |
explicit OcTree(const shared_ptr<const octomap::OcTree>& tree_) |
79 |
|
1 |
: tree(tree_) { |
80 |
|
1 |
default_occupancy = tree->getOccupancyThres(); |
81 |
|
|
|
82 |
|
|
// default occupancy/free threshold is consistent with default setting from |
83 |
|
|
// octomap |
84 |
|
1 |
occupancy_threshold = tree->getOccupancyThres(); |
85 |
|
1 |
free_threshold = 0; |
86 |
|
1 |
} |
87 |
|
|
|
88 |
|
|
OcTree(const OcTree& other) |
89 |
|
|
: CollisionGeometry(other), |
90 |
|
|
tree(other.tree), |
91 |
|
|
default_occupancy(other.default_occupancy), |
92 |
|
|
occupancy_threshold(other.occupancy_threshold), |
93 |
|
|
free_threshold(other.free_threshold) {} |
94 |
|
|
|
95 |
|
|
OcTree* clone() const { return new OcTree(*this); } |
96 |
|
|
|
97 |
|
|
void exportAsObjFile(const std::string& filename) const; |
98 |
|
|
|
99 |
|
|
/// @brief compute the AABB for the octree in its local coordinate system |
100 |
|
|
void computeLocalAABB() { |
101 |
|
|
aabb_local = getRootBV(); |
102 |
|
|
aabb_center = aabb_local.center(); |
103 |
|
|
aabb_radius = (aabb_local.min_ - aabb_center).norm(); |
104 |
|
|
} |
105 |
|
|
|
106 |
|
|
/// @brief get the bounding volume for the root |
107 |
|
100 |
AABB getRootBV() const { |
108 |
✓✗ |
100 |
FCL_REAL delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2; |
109 |
|
|
|
110 |
|
|
// std::cout << "octree size " << delta << std::endl; |
111 |
✓✗✓✗ ✓✗ |
200 |
return AABB(Vec3f(-delta, -delta, -delta), Vec3f(delta, delta, delta)); |
112 |
|
|
} |
113 |
|
|
|
114 |
|
|
/// @brief Returns the depth of octree |
115 |
|
|
unsigned int getTreeDepth() const { return tree->getTreeDepth(); } |
116 |
|
|
|
117 |
|
|
/// @brief get the root node of the octree |
118 |
|
153 |
OcTreeNode* getRoot() const { return tree->getRoot(); } |
119 |
|
|
|
120 |
|
|
/// @brief whether one node is completely occupied |
121 |
|
29521 |
bool isNodeOccupied(const OcTreeNode* node) const { |
122 |
|
|
// return tree->isNodeOccupied(node); |
123 |
|
29521 |
return node->getOccupancy() >= occupancy_threshold; |
124 |
|
|
} |
125 |
|
|
|
126 |
|
|
/// @brief whether one node is completely free |
127 |
|
28982 |
bool isNodeFree(const OcTreeNode* node) const { |
128 |
|
|
// return false; // default no definitely free node |
129 |
|
28982 |
return node->getOccupancy() <= free_threshold; |
130 |
|
|
} |
131 |
|
|
|
132 |
|
|
/// @brief whether one node is uncertain |
133 |
|
28982 |
bool isNodeUncertain(const OcTreeNode* node) const { |
134 |
✗✓✗✗
|
28982 |
return (!isNodeOccupied(node)) && (!isNodeFree(node)); |
135 |
|
|
} |
136 |
|
|
|
137 |
|
|
/// @brief transform the octree into a bunch of boxes; uncertainty information |
138 |
|
|
/// is kept in the boxes. However, we only keep the occupied boxes (i.e., the |
139 |
|
|
/// boxes whose occupied probability is higher enough). |
140 |
|
|
std::vector<boost::array<FCL_REAL, 6> > toBoxes() const { |
141 |
|
|
std::vector<boost::array<FCL_REAL, 6> > boxes; |
142 |
|
|
boxes.reserve(tree->size() / 2); |
143 |
|
|
for (octomap::OcTree::iterator |
144 |
|
|
it = tree->begin((unsigned char)tree->getTreeDepth()), |
145 |
|
|
end = tree->end(); |
146 |
|
|
it != end; ++it) { |
147 |
|
|
// if(tree->isNodeOccupied(*it)) |
148 |
|
|
if (isNodeOccupied(&*it)) { |
149 |
|
|
FCL_REAL size = it.getSize(); |
150 |
|
|
FCL_REAL x = it.getX(); |
151 |
|
|
FCL_REAL y = it.getY(); |
152 |
|
|
FCL_REAL z = it.getZ(); |
153 |
|
|
FCL_REAL c = (*it).getOccupancy(); |
154 |
|
|
FCL_REAL t = tree->getOccupancyThres(); |
155 |
|
|
|
156 |
|
|
boost::array<FCL_REAL, 6> box = {{x, y, z, size, c, t}}; |
157 |
|
|
boxes.push_back(box); |
158 |
|
|
} |
159 |
|
|
} |
160 |
|
|
return boxes; |
161 |
|
|
} |
162 |
|
|
|
163 |
|
|
/// @brief the threshold used to decide whether one node is occupied, this is |
164 |
|
|
/// NOT the octree occupied_thresold |
165 |
|
|
FCL_REAL getOccupancyThres() const { return occupancy_threshold; } |
166 |
|
|
|
167 |
|
|
/// @brief the threshold used to decide whether one node is free, this is NOT |
168 |
|
|
/// the octree free_threshold |
169 |
|
|
FCL_REAL getFreeThres() const { return free_threshold; } |
170 |
|
|
|
171 |
|
|
FCL_REAL getDefaultOccupancy() const { return default_occupancy; } |
172 |
|
|
|
173 |
|
|
void setCellDefaultOccupancy(FCL_REAL d) { default_occupancy = d; } |
174 |
|
|
|
175 |
|
|
void setOccupancyThres(FCL_REAL d) { occupancy_threshold = d; } |
176 |
|
|
|
177 |
|
|
void setFreeThres(FCL_REAL d) { free_threshold = d; } |
178 |
|
|
|
179 |
|
|
/// @return ptr to child number childIdx of node |
180 |
|
|
OcTreeNode* getNodeChild(OcTreeNode* node, unsigned int childIdx) { |
181 |
|
|
#if OCTOMAP_VERSION_AT_LEAST(1, 8, 0) |
182 |
|
|
return tree->getNodeChild(node, childIdx); |
183 |
|
|
#else |
184 |
|
|
return node->getChild(childIdx); |
185 |
|
|
#endif |
186 |
|
|
} |
187 |
|
|
|
188 |
|
|
/// @return const ptr to child number childIdx of node |
189 |
|
18305 |
const OcTreeNode* getNodeChild(const OcTreeNode* node, |
190 |
|
|
unsigned int childIdx) const { |
191 |
|
|
#if OCTOMAP_VERSION_AT_LEAST(1, 8, 0) |
192 |
|
18305 |
return tree->getNodeChild(node, childIdx); |
193 |
|
|
#else |
194 |
|
|
return node->getChild(childIdx); |
195 |
|
|
#endif |
196 |
|
|
} |
197 |
|
|
|
198 |
|
|
/// @brief return true if the child at childIdx exists |
199 |
|
42996 |
bool nodeChildExists(const OcTreeNode* node, unsigned int childIdx) const { |
200 |
|
|
#if OCTOMAP_VERSION_AT_LEAST(1, 8, 0) |
201 |
|
42996 |
return tree->nodeChildExists(node, childIdx); |
202 |
|
|
#else |
203 |
|
|
return node->childExists(childIdx); |
204 |
|
|
#endif |
205 |
|
|
} |
206 |
|
|
|
207 |
|
|
/// @brief return true if node has at least one child |
208 |
|
20522 |
bool nodeHasChildren(const OcTreeNode* node) const { |
209 |
|
|
#if OCTOMAP_VERSION_AT_LEAST(1, 8, 0) |
210 |
|
20522 |
return tree->nodeHasChildren(node); |
211 |
|
|
#else |
212 |
|
|
return node->hasChildren(); |
213 |
|
|
#endif |
214 |
|
|
} |
215 |
|
|
|
216 |
|
|
/// @brief return object type, it is an octree |
217 |
|
100 |
OBJECT_TYPE getObjectType() const { return OT_OCTREE; } |
218 |
|
|
|
219 |
|
|
/// @brief return node type, it is an octree |
220 |
|
100 |
NODE_TYPE getNodeType() const { return GEOM_OCTREE; } |
221 |
|
|
|
222 |
|
|
private: |
223 |
|
|
virtual bool isEqual(const CollisionGeometry& _other) const { |
224 |
|
|
const OcTree* other_ptr = dynamic_cast<const OcTree*>(&_other); |
225 |
|
|
if (other_ptr == nullptr) return false; |
226 |
|
|
const OcTree& other = *other_ptr; |
227 |
|
|
|
228 |
|
|
return tree.get() == other.tree.get() && |
229 |
|
|
default_occupancy == other.default_occupancy && |
230 |
|
|
occupancy_threshold == other.occupancy_threshold && |
231 |
|
|
free_threshold == other.free_threshold; |
232 |
|
|
} |
233 |
|
|
|
234 |
|
|
public: |
235 |
|
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
236 |
|
|
}; |
237 |
|
|
|
238 |
|
|
/// @brief compute the bounding volume of an octree node's i-th child |
239 |
|
18305 |
static inline void computeChildBV(const AABB& root_bv, unsigned int i, |
240 |
|
|
AABB& child_bv) { |
241 |
✓✓ |
18305 |
if (i & 1) { |
242 |
|
8338 |
child_bv.min_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5; |
243 |
|
8338 |
child_bv.max_[0] = root_bv.max_[0]; |
244 |
|
|
} else { |
245 |
|
9967 |
child_bv.min_[0] = root_bv.min_[0]; |
246 |
|
9967 |
child_bv.max_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5; |
247 |
|
|
} |
248 |
|
|
|
249 |
✓✓ |
18305 |
if (i & 2) { |
250 |
|
9091 |
child_bv.min_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5; |
251 |
|
9091 |
child_bv.max_[1] = root_bv.max_[1]; |
252 |
|
|
} else { |
253 |
|
9214 |
child_bv.min_[1] = root_bv.min_[1]; |
254 |
|
9214 |
child_bv.max_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5; |
255 |
|
|
} |
256 |
|
|
|
257 |
✓✓ |
18305 |
if (i & 4) { |
258 |
|
13427 |
child_bv.min_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5; |
259 |
|
13427 |
child_bv.max_[2] = root_bv.max_[2]; |
260 |
|
|
} else { |
261 |
|
4878 |
child_bv.min_[2] = root_bv.min_[2]; |
262 |
|
4878 |
child_bv.max_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5; |
263 |
|
|
} |
264 |
|
18305 |
} |
265 |
|
|
|
266 |
|
|
/// |
267 |
|
|
/// \brief Build an OcTree from a point cloud and a given resolution |
268 |
|
|
/// |
269 |
|
|
/// \param[in] point_cloud The input points to insert in the OcTree |
270 |
|
|
/// \param[in] resolution of the octree. |
271 |
|
|
/// |
272 |
|
|
/// \returns An OcTree that can be used for collision checking and more. |
273 |
|
|
/// |
274 |
|
|
HPP_FCL_DLLAPI OcTreePtr_t |
275 |
|
|
makeOctree(const Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 3>& point_cloud, |
276 |
|
|
const FCL_REAL resolution); |
277 |
|
|
|
278 |
|
|
} // namespace fcl |
279 |
|
|
|
280 |
|
|
} // namespace hpp |
281 |
|
|
|
282 |
|
|
#endif |