hpp-fcl  1.4.4
HPP fork of FCL -- The Flexible Collision Library
loader.h
Go to the documentation of this file.
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 <boost/shared_ptr.hpp>
42 #include <hpp/fcl/fwd.hh>
43 #include <hpp/fcl/config.hh>
44 #include <hpp/fcl/data_types.h>
46 
47 namespace hpp
48 {
49 namespace fcl {
52  class MeshLoader
53  {
54  public:
55  virtual ~MeshLoader() {}
56 
57  virtual BVHModelPtr_t load (const std::string& filename,
58  const Vec3f& scale = Vec3f::Ones());
59 
62  virtual CollisionGeometryPtr_t loadOctree (const std::string& filename);
63 
64  MeshLoader (const NODE_TYPE& bvType = BV_OBBRSS) : bvType_ (bvType) {}
65 
66  private:
67  const NODE_TYPE bvType_;
68  };
69 
75  {
76  public:
77  virtual ~CachedMeshLoader() {}
78 
79  CachedMeshLoader (const NODE_TYPE& bvType = BV_OBBRSS) : MeshLoader (bvType) {}
80 
81  virtual BVHModelPtr_t load (const std::string& filename,
82  const Vec3f& scale);
83 
84  struct Key {
85  std::string filename;
87 
88  Key (const std::string& f, const Vec3f& s)
89  : filename (f), scale (s) {}
90 
91  bool operator< (const CachedMeshLoader::Key& b) const;
92  };
93  typedef std::map <Key, BVHModelPtr_t> Cache_t;
94 
95  const Cache_t cache () const { return cache_; }
96  private:
97  Cache_t cache_;
98  };
99 }
100 
101 } // namespace hpp
102 
103 #endif // FCL_MESH_LOADER_LOADER_H
data_types.h
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:73
collision_object.h
hpp::fcl::MeshLoader::loadOctree
virtual CollisionGeometryPtr_t loadOctree(const std::string &filename)
hpp::fcl::CachedMeshLoader::Key::operator<
bool operator<(const CachedMeshLoader::Key &b) const
hpp::fcl::CachedMeshLoader::Key::Key
Key(const std::string &f, const Vec3f &s)
Definition: loader.h:88
hpp::fcl::MeshLoader::MeshLoader
MeshLoader(const NODE_TYPE &bvType=BV_OBBRSS)
Definition: loader.h:64
hpp::fcl::CachedMeshLoader::Cache_t
std::map< Key, BVHModelPtr_t > Cache_t
Definition: loader.h:93
hpp::fcl::CachedMeshLoader::Key::filename
std::string filename
Definition: loader.h:85
hpp::fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_object.h:56
hpp::fcl::CachedMeshLoader::Key
Definition: loader.h:84
fwd.hh
hpp::fcl::MeshLoader
Definition: loader.h:52
hpp::fcl::BV_OBBRSS
@ BV_OBBRSS
Definition: collision_object.h:56
hpp::fcl::CollisionGeometryPtr_t
boost::shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
Definition: fwd.hh:47
hpp::fcl::CachedMeshLoader::load
virtual BVHModelPtr_t load(const std::string &filename, const Vec3f &scale)
hpp
Main namespace.
Definition: AABB.h:43
hpp::fcl::MeshLoader::load
virtual BVHModelPtr_t load(const std::string &filename, const Vec3f &scale=Vec3f::Ones())
hpp::fcl::CachedMeshLoader::~CachedMeshLoader
virtual ~CachedMeshLoader()
Definition: loader.h:77
hpp::fcl::CachedMeshLoader::cache
const Cache_t cache() const
Definition: loader.h:95
hpp::fcl::CachedMeshLoader::Key::scale
Vec3f scale
Definition: loader.h:86
hpp::fcl::BVHModelPtr_t
boost::shared_ptr< BVHModelBase > BVHModelPtr_t
Definition: fwd.hh:55
hpp::fcl::MeshLoader::~MeshLoader
virtual ~MeshLoader()
Definition: loader.h:55
hpp::fcl::CachedMeshLoader
Definition: loader.h:74
hpp::fcl::CachedMeshLoader::CachedMeshLoader
CachedMeshLoader(const NODE_TYPE &bvType=BV_OBBRSS)
Definition: loader.h:79
config.hh