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 |
|
|
* Copyright (c) 2016, CNRS - LAAS |
7 |
|
|
* Copyright (c) 2020, INRIA |
8 |
|
|
* All rights reserved. |
9 |
|
|
* |
10 |
|
|
* Redistribution and use in source and binary forms, with or without |
11 |
|
|
* modification, are permitted provided that the following conditions |
12 |
|
|
* are met: |
13 |
|
|
* |
14 |
|
|
* * Redistributions of source code must retain the above copyright |
15 |
|
|
* notice, this list of conditions and the following disclaimer. |
16 |
|
|
* * Redistributions in binary form must reproduce the above |
17 |
|
|
* copyright notice, this list of conditions and the following |
18 |
|
|
* disclaimer in the documentation and/or other materials provided |
19 |
|
|
* with the distribution. |
20 |
|
|
* * Neither the name of Open Source Robotics Foundation nor the names of its |
21 |
|
|
* contributors may be used to endorse or promote products derived |
22 |
|
|
* from this software without specific prior written permission. |
23 |
|
|
* |
24 |
|
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
25 |
|
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
26 |
|
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
27 |
|
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
28 |
|
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
29 |
|
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
30 |
|
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; |
31 |
|
|
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
32 |
|
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
33 |
|
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
34 |
|
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
35 |
|
|
* POSSIBILITY OF SUCH DAMAGE. |
36 |
|
|
*/ |
37 |
|
|
|
38 |
|
|
#ifndef HPP_FCL_MESH_LOADER_LOADER_H |
39 |
|
|
#define HPP_FCL_MESH_LOADER_LOADER_H |
40 |
|
|
|
41 |
|
|
#include <hpp/fcl/fwd.hh> |
42 |
|
|
#include <hpp/fcl/config.hh> |
43 |
|
|
#include <hpp/fcl/data_types.h> |
44 |
|
|
#include <hpp/fcl/collision_object.h> |
45 |
|
|
|
46 |
|
|
#include <map> |
47 |
|
|
#include <ctime> |
48 |
|
|
|
49 |
|
|
namespace hpp { |
50 |
|
|
namespace fcl { |
51 |
|
|
/// Base class for building polyhedron from files. |
52 |
|
|
/// This class builds a new object for each file. |
53 |
|
|
class HPP_FCL_DLLAPI MeshLoader { |
54 |
|
|
public: |
55 |
|
18 |
virtual ~MeshLoader() {} |
56 |
|
|
|
57 |
|
|
virtual BVHModelPtr_t load(const std::string& filename, |
58 |
|
|
const Vec3f& scale = Vec3f::Ones()); |
59 |
|
|
|
60 |
|
|
/// Create an OcTree from a file in binary octomap format. |
61 |
|
|
/// \todo add OctreePtr_t |
62 |
|
|
virtual CollisionGeometryPtr_t loadOctree(const std::string& filename); |
63 |
|
|
|
64 |
✗✗ |
1 |
MeshLoader(const NODE_TYPE& bvType = BV_OBBRSS) : bvType_(bvType) {} |
65 |
|
|
|
66 |
|
|
private: |
67 |
|
|
const NODE_TYPE bvType_; |
68 |
|
|
}; |
69 |
|
|
|
70 |
|
|
/// Class for building polyhedron from files with cache mechanism. |
71 |
|
|
/// This class builds a new object for each different file. |
72 |
|
|
/// If method CachedMeshLoader::load is called twice with the same arguments, |
73 |
|
|
/// the second call returns the result of the first call. |
74 |
|
|
class HPP_FCL_DLLAPI CachedMeshLoader : public MeshLoader { |
75 |
|
|
public: |
76 |
|
16 |
virtual ~CachedMeshLoader() {} |
77 |
|
|
|
78 |
✗✗ |
8 |
CachedMeshLoader(const NODE_TYPE& bvType = BV_OBBRSS) : MeshLoader(bvType) {} |
79 |
|
|
|
80 |
|
|
virtual BVHModelPtr_t load(const std::string& filename, const Vec3f& scale); |
81 |
|
|
|
82 |
|
|
struct HPP_FCL_DLLAPI Key { |
83 |
|
|
std::string filename; |
84 |
|
|
Vec3f scale; |
85 |
|
|
|
86 |
✓✗ |
16 |
Key(const std::string& f, const Vec3f& s) : filename(f), scale(s) {} |
87 |
|
|
|
88 |
|
|
bool operator<(const CachedMeshLoader::Key& b) const; |
89 |
|
|
}; |
90 |
|
|
struct HPP_FCL_DLLAPI Value { |
91 |
|
|
BVHModelPtr_t model; |
92 |
|
|
std::time_t mtime; |
93 |
|
|
}; |
94 |
|
|
typedef std::map<Key, Value> Cache_t; |
95 |
|
|
|
96 |
|
|
const Cache_t& cache() const { return cache_; } |
97 |
|
|
|
98 |
|
|
private: |
99 |
|
|
Cache_t cache_; |
100 |
|
|
}; |
101 |
|
|
} // namespace fcl |
102 |
|
|
|
103 |
|
|
} // namespace hpp |
104 |
|
|
|
105 |
|
|
#endif // FCL_MESH_LOADER_LOADER_H |