Go to the documentation of this file.
40 #include <boost/filesystem.hpp>
42 #ifdef COAL_HAS_OCTOMAP
51 for (
int i = 0; i < 3; ++i) {
52 if (
a.scale[i] <
b.scale[i])
54 else if (
a.scale[i] >
b.scale[i])
57 return std::less<std::string>()(
a.filename,
b.filename);
60 template <
typename BV>
79 return _load<OBBRSS>(
filename, scale);
81 return _load<KDOP<16> >(
filename, scale);
83 return _load<KDOP<18> >(
filename, scale);
85 return _load<KDOP<24> >(
filename, scale);
88 std::invalid_argument);
93 #ifdef COAL_HAS_OCTOMAP
103 const Vec3s& scale) {
106 std::time_t mtime = 0;
108 mtime = boost::filesystem::last_write_time(
filename);
110 Cache_t::const_iterator _cached =
cache_.find(key);
111 if (_cached !=
cache_.end() && _cached->second.mtime == mtime)
113 return _cached->second.model;
114 }
catch (boost::filesystem::filesystem_error&) {
virtual CollisionGeometryPtr_t loadOctree(const std::string &filename)
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
void loadPolyhedronFromResource(const std::string &resource_path, const coal::Vec3s &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 Vec3s &scale=Vec3s::Ones())
virtual BVHModelPtr_t load(const std::string &filename, const Vec3s &scale)
BVHModelPtr_t _load(const std::string &filename, const Vec3s &scale)
#define COAL_THROW_PRETTY(message, exception)
shared_ptr< BVHModelBase > BVHModelPtr_t
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
bool operator<(const CachedMeshLoader::Key &b) const
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:58