GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: src/mesh_loader/loader.cpp Lines: 41 49 83.7 %
Date: 2024-02-09 12:57:42 Branches: 27 57 47.4 %

Line Branch Exec Source
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
37
#include <hpp/fcl/mesh_loader/loader.h>
38
#include <hpp/fcl/mesh_loader/assimp.h>
39
40
#include <boost/filesystem.hpp>
41
42
#ifdef HPP_FCL_HAS_OCTOMAP
43
#include <hpp/fcl/octree.h>
44
#endif
45
46
#include <hpp/fcl/BV/BV.h>
47
48
namespace hpp {
49
namespace fcl {
50
16
bool CachedMeshLoader::Key::operator<(const CachedMeshLoader::Key& b) const {
51
16
  const CachedMeshLoader::Key& a = *this;
52
64
  for (int i = 0; i < 3; ++i) {
53
48
    if (a.scale[i] < b.scale[i])
54
      return true;
55
48
    else if (a.scale[i] > b.scale[i])
56
      return false;
57
  }
58
16
  return std::less<std::string>()(a.filename, b.filename);
59
}
60
61
template <typename BV>
62
18
BVHModelPtr_t _load(const std::string& filename, const Vec3f& scale) {
63

36
  shared_ptr<BVHModel<BV> > polyhedron(new BVHModel<BV>);
64
18
  loadPolyhedronFromResource(filename, scale, polyhedron);
65
36
  return polyhedron;
66
}
67
68
9
BVHModelPtr_t MeshLoader::load(const std::string& filename,
69
                               const Vec3f& scale) {
70


9
  switch (bvType_) {
71
1
    case BV_AABB:
72
1
      return _load<AABB>(filename, scale);
73
1
    case BV_OBB:
74
1
      return _load<OBB>(filename, scale);
75
1
    case BV_RSS:
76
1
      return _load<RSS>(filename, scale);
77
1
    case BV_kIOS:
78
1
      return _load<kIOS>(filename, scale);
79
2
    case BV_OBBRSS:
80
2
      return _load<OBBRSS>(filename, scale);
81
1
    case BV_KDOP16:
82
1
      return _load<KDOP<16> >(filename, scale);
83
1
    case BV_KDOP18:
84
1
      return _load<KDOP<18> >(filename, scale);
85
1
    case BV_KDOP24:
86
1
      return _load<KDOP<24> >(filename, scale);
87
    default:
88
      throw std::invalid_argument("Unhandled bouding volume type.");
89
  }
90
}
91
92
CollisionGeometryPtr_t MeshLoader::loadOctree(const std::string& filename) {
93
#ifdef HPP_FCL_HAS_OCTOMAP
94
  shared_ptr<octomap::OcTree> octree(new octomap::OcTree(filename));
95
  return CollisionGeometryPtr_t(new hpp::fcl::OcTree(octree));
96
#else
97
  throw std::logic_error(
98
      "hpp-fcl compiled without OctoMap. Cannot create OcTrees.");
99
#endif
100
}
101
102
16
BVHModelPtr_t CachedMeshLoader::load(const std::string& filename,
103
                                     const Vec3f& scale) {
104
32
  Key key(filename, scale);
105
106
16
  std::time_t mtime = 0;
107
  try {
108

16
    mtime = boost::filesystem::last_write_time(filename);
109
110
16
    Cache_t::const_iterator _cached = cache_.find(key);
111

16
    if (_cached != cache_.end() && _cached->second.mtime == mtime)
112
      // File found in cache and mtime is the same
113
8
      return _cached->second.model;
114
  } catch (boost::filesystem::filesystem_error&) {
115
    // Could not stat. Make sure we will try to load the file so that
116
    // there will be a file not found error.
117
  }
118
119
16
  BVHModelPtr_t geom = MeshLoader::load(filename, scale);
120
16
  Value val;
121
8
  val.model = geom;
122
8
  val.mtime = mtime;
123
8
  cache_[key] = val;
124
8
  return geom;
125
}
126
}  // namespace fcl
127
128
}  // namespace hpp