loader.cpp
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  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Open Source Robotics Foundation nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  */
36 
39 
40 #ifdef HPP_FCL_HAS_OCTOMAP
41 #include <hpp/fcl/octree.h>
42 #endif
43 
44 #include <hpp/fcl/BV/BV.h>
45 
46 namespace hpp {
47 namespace fcl {
49  const CachedMeshLoader::Key& a = *this;
50  for (int i = 0; i < 3; ++i) {
51  if (a.scale[i] < b.scale[i])
52  return true;
53  else if (a.scale[i] > b.scale[i])
54  return false;
55  }
56  return std::less<std::string>()(a.filename, b.filename);
57 }
58 
59 template <typename BV>
60 BVHModelPtr_t _load(const std::string& filename, const Vec3f& scale) {
61  shared_ptr<BVHModel<BV> > polyhedron(new BVHModel<BV>);
62  loadPolyhedronFromResource(filename, scale, polyhedron);
63  return polyhedron;
64 }
65 
67  const Vec3f& scale) {
68  switch (bvType_) {
69  case BV_AABB:
70  return _load<AABB>(filename, scale);
71  case BV_OBB:
72  return _load<OBB>(filename, scale);
73  case BV_RSS:
74  return _load<RSS>(filename, scale);
75  case BV_kIOS:
76  return _load<kIOS>(filename, scale);
77  case BV_OBBRSS:
78  return _load<OBBRSS>(filename, scale);
79  case BV_KDOP16:
80  return _load<KDOP<16> >(filename, scale);
81  case BV_KDOP18:
82  return _load<KDOP<18> >(filename, scale);
83  case BV_KDOP24:
84  return _load<KDOP<24> >(filename, scale);
85  default:
86  throw std::invalid_argument("Unhandled bouding volume type.");
87  }
88 }
89 
91 #ifdef HPP_FCL_HAS_OCTOMAP
92  shared_ptr<octomap::OcTree> octree(new octomap::OcTree(filename));
93  return CollisionGeometryPtr_t(new hpp::fcl::OcTree(octree));
94 #else
95  throw std::logic_error(
96  "hpp-fcl compiled without OctoMap. Cannot create OcTrees.");
97 #endif
98 }
99 
101  const Vec3f& scale) {
102  Key key(filename, scale);
103  Cache_t::const_iterator _cached = cache_.find(key);
104  if (_cached == cache_.end()) {
105  BVHModelPtr_t geom = MeshLoader::load(filename, scale);
106  cache_.insert(std::make_pair(key, geom));
107  return geom;
108  } else {
109  return _cached->second;
110  }
111 }
112 } // namespace fcl
113 
114 } // namespace hpp
Main namespace.
const NODE_TYPE bvType_
Definition: loader.h:66
bool operator<(const CachedMeshLoader::Key &b) const
Definition: loader.cpp:48
Octree is one type of collision geometry which can encode uncertainty information in the sensor data...
Definition: octree.h:53
Definition: octree.py:1
virtual BVHModelPtr_t load(const std::string &filename, const Vec3f &scale)
Definition: loader.cpp:100
virtual CollisionGeometryPtr_t loadOctree(const std::string &filename)
Definition: loader.cpp:90
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
list a
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
BVHModelPtr_t _load(const std::string &filename, const Vec3f &scale)
Definition: loader.cpp:60
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.
Definition: assimp.h:118
virtual BVHModelPtr_t load(const std::string &filename, const Vec3f &scale=Vec3f::Ones())
Definition: loader.cpp:66


hpp-fcl
Author(s):
autogenerated on Fri Jun 2 2023 02:39:01