40 #ifdef HPP_FCL_HAS_OCTOMAP 50 for (
int i = 0; i < 3; ++i) {
59 template <
typename BV>
86 throw std::invalid_argument(
"Unhandled bouding volume type.");
91 #ifdef HPP_FCL_HAS_OCTOMAP 95 throw std::logic_error(
96 "hpp-fcl compiled without OctoMap. Cannot create OcTrees.");
102 Key key(filename, scale);
103 Cache_t::const_iterator _cached =
cache_.find(key);
104 if (_cached ==
cache_.end()) {
106 cache_.insert(std::make_pair(key, geom));
109 return _cached->second;
bool operator<(const CachedMeshLoader::Key &b) const
Octree is one type of collision geometry which can encode uncertainty information in the sensor data...
virtual BVHModelPtr_t load(const std::string &filename, const Vec3f &scale)
virtual CollisionGeometryPtr_t loadOctree(const std::string &filename)
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
shared_ptr< BVHModelBase > BVHModelPtr_t
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
BVHModelPtr_t _load(const std::string &filename, const Vec3f &scale)
void loadPolyhedronFromResource(const std::string &resource_path, const fcl::Vec3f &scale, const shared_ptr< BVHModel< BoundingVolume > > &polyhedron)
Read a mesh file and convert it to a polyhedral mesh.
virtual BVHModelPtr_t load(const std::string &filename, const Vec3f &scale=Vec3f::Ones())