Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00038 #ifndef FCL_OCTREE_H
00039 #define FCL_OCTREE_H
00040
00041
00042 #include <boost/shared_ptr.hpp>
00043 #include <boost/array.hpp>
00044
00045 #include <octomap/octomap.h>
00046 #include "fcl/BV/AABB.h"
00047 #include "fcl/collision_object.h"
00048
00049 namespace fcl
00050 {
00051
00053 class OcTree : public CollisionGeometry
00054 {
00055 private:
00056 boost::shared_ptr<const octomap::OcTree> tree;
00057
00058 FCL_REAL default_occupancy;
00059
00060 FCL_REAL occupancy_threshold;
00061 FCL_REAL free_threshold;
00062
00063 public:
00064
00069 typedef octomap::OcTreeNode OcTreeNode;
00070
00072 OcTree(FCL_REAL resolution) : tree(boost::shared_ptr<const octomap::OcTree>(new octomap::OcTree(resolution)))
00073 {
00074 default_occupancy = tree->getOccupancyThres();
00075
00076
00077 occupancy_threshold = tree->getOccupancyThres();
00078 free_threshold = 0;
00079 }
00080
00082 OcTree(const boost::shared_ptr<const octomap::OcTree>& tree_) : tree(tree_)
00083 {
00084 default_occupancy = tree->getOccupancyThres();
00085
00086
00087 occupancy_threshold = tree->getOccupancyThres();
00088 free_threshold = 0;
00089 }
00090
00092 void computeLocalAABB()
00093 {
00094 aabb_local = getRootBV();
00095 aabb_center = aabb_local.center();
00096 aabb_radius = (aabb_local.min_ - aabb_center).length();
00097 }
00098
00100 inline AABB getRootBV() const
00101 {
00102 FCL_REAL delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2;
00103
00104
00105 return AABB(Vec3f(-delta, -delta, -delta), Vec3f(delta, delta, delta));
00106 }
00107
00109 inline OcTreeNode* getRoot() const
00110 {
00111 return tree->getRoot();
00112 }
00113
00115 inline bool isNodeOccupied(const OcTreeNode* node) const
00116 {
00117
00118 return node->getOccupancy() >= occupancy_threshold;
00119 }
00120
00122 inline bool isNodeFree(const OcTreeNode* node) const
00123 {
00124
00125 return node->getOccupancy() <= free_threshold;
00126 }
00127
00129 inline bool isNodeUncertain(const OcTreeNode* node) const
00130 {
00131 return (!isNodeOccupied(node)) && (!isNodeFree(node));
00132 }
00133
00136 inline std::vector<boost::array<FCL_REAL, 6> > toBoxes() const
00137 {
00138 std::vector<boost::array<FCL_REAL, 6> > boxes;
00139 boxes.reserve(tree->size() / 2);
00140 for(octomap::OcTree::iterator it = tree->begin(tree->getTreeDepth()), end = tree->end();
00141 it != end;
00142 ++it)
00143 {
00144
00145 if(isNodeOccupied(&*it))
00146 {
00147 FCL_REAL size = it.getSize();
00148 FCL_REAL x = it.getX();
00149 FCL_REAL y = it.getY();
00150 FCL_REAL z = it.getZ();
00151 FCL_REAL c = (*it).getOccupancy();
00152 FCL_REAL t = tree->getOccupancyThres();
00153
00154 boost::array<FCL_REAL, 6> box = {{x, y, z, size, c, t}};
00155 boxes.push_back(box);
00156 }
00157 }
00158 return boxes;
00159 }
00160
00162 FCL_REAL getOccupancyThres() const
00163 {
00164 return occupancy_threshold;
00165 }
00166
00168 FCL_REAL getFreeThres() const
00169 {
00170 return free_threshold;
00171 }
00172
00173 FCL_REAL getDefaultOccupancy() const
00174 {
00175 return default_occupancy;
00176 }
00177
00178 void setCellDefaultOccupancy(FCL_REAL d)
00179 {
00180 default_occupancy = d;
00181 }
00182
00183 void setOccupancyThres(FCL_REAL d)
00184 {
00185 occupancy_threshold = d;
00186 }
00187
00188 void setFreeThres(FCL_REAL d)
00189 {
00190 free_threshold = d;
00191 }
00192
00194 OBJECT_TYPE getObjectType() const { return OT_OCTREE; }
00195
00197 NODE_TYPE getNodeType() const { return GEOM_OCTREE; }
00198 };
00199
00201 static inline void computeChildBV(const AABB& root_bv, unsigned int i, AABB& child_bv)
00202 {
00203 if(i&1)
00204 {
00205 child_bv.min_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
00206 child_bv.max_[0] = root_bv.max_[0];
00207 }
00208 else
00209 {
00210 child_bv.min_[0] = root_bv.min_[0];
00211 child_bv.max_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
00212 }
00213
00214 if(i&2)
00215 {
00216 child_bv.min_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
00217 child_bv.max_[1] = root_bv.max_[1];
00218 }
00219 else
00220 {
00221 child_bv.min_[1] = root_bv.min_[1];
00222 child_bv.max_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
00223 }
00224
00225 if(i&4)
00226 {
00227 child_bv.min_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
00228 child_bv.max_[2] = root_bv.max_[2];
00229 }
00230 else
00231 {
00232 child_bv.min_[2] = root_bv.min_[2];
00233 child_bv.max_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
00234 }
00235 }
00236
00237
00238
00239 }
00240
00241 #endif