#include <boost/array.hpp>
#include <octomap/octomap.h>
#include <hpp/fcl/fwd.hh>
#include <hpp/fcl/BV/AABB.h>
#include <hpp/fcl/collision_object.h>
Go to the source code of this file.
|
class | hpp::fcl::OcTree |
| Octree is one type of collision geometry which can encode uncertainty information in the sensor data. More...
|
|
|
static void | hpp::fcl::computeChildBV (const AABB &root_bv, unsigned int i, AABB &child_bv) |
| compute the bounding volume of an octree node's i-th child More...
|
|
HPP_FCL_DLLAPI OcTreePtr_t | hpp::fcl::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. More...
|
|