Directory: | ./ |
---|---|
File: | src/mesh_loader/loader.cpp |
Date: | 2025-04-01 09:23:31 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 43 | 51 | 84.3% |
Branches: | 27 | 87 | 31.0% |
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 "coal/mesh_loader/loader.h" | ||
38 | #include "coal/mesh_loader/assimp.h" | ||
39 | |||
40 | #include <boost/filesystem.hpp> | ||
41 | |||
42 | #ifdef COAL_HAS_OCTOMAP | ||
43 | #include "coal/octree.h" | ||
44 | #endif | ||
45 | |||
46 | #include "coal/BV/BV.h" | ||
47 | |||
48 | namespace coal { | ||
49 | 16 | bool CachedMeshLoader::Key::operator<(const CachedMeshLoader::Key& b) const { | |
50 | 16 | const CachedMeshLoader::Key& a = *this; | |
51 |
2/2✓ Branch 0 taken 48 times.
✓ Branch 1 taken 16 times.
|
64 | for (int i = 0; i < 3; ++i) { |
52 |
1/2✗ Branch 2 not taken.
✓ Branch 3 taken 48 times.
|
48 | if (a.scale[i] < b.scale[i]) |
53 | ✗ | return true; | |
54 |
1/2✗ Branch 2 not taken.
✓ Branch 3 taken 48 times.
|
48 | else if (a.scale[i] > b.scale[i]) |
55 | ✗ | return false; | |
56 | } | ||
57 | 16 | return std::less<std::string>()(a.filename, b.filename); | |
58 | } | ||
59 | |||
60 | template <typename BV> | ||
61 | 18 | BVHModelPtr_t _load(const std::string& filename, const Vec3s& scale) { | |
62 |
3/6✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 9 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 9 times.
✗ Branch 8 not taken.
|
18 | shared_ptr<BVHModel<BV> > polyhedron(new BVHModel<BV>); |
63 |
1/2✓ Branch 1 taken 9 times.
✗ Branch 2 not taken.
|
18 | loadPolyhedronFromResource(filename, scale, polyhedron); |
64 | 36 | return polyhedron; | |
65 | 18 | } | |
66 | |||
67 | 9 | BVHModelPtr_t MeshLoader::load(const std::string& filename, | |
68 | const Vec3s& scale) { | ||
69 |
8/9✓ Branch 0 taken 1 times.
✓ Branch 1 taken 1 times.
✓ Branch 2 taken 1 times.
✓ Branch 3 taken 1 times.
✓ Branch 4 taken 2 times.
✓ Branch 5 taken 1 times.
✓ Branch 6 taken 1 times.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
9 | switch (bvType_) { |
70 | 1 | case BV_AABB: | |
71 | 1 | return _load<AABB>(filename, scale); | |
72 | 1 | case BV_OBB: | |
73 | 1 | return _load<OBB>(filename, scale); | |
74 | 1 | case BV_RSS: | |
75 | 1 | return _load<RSS>(filename, scale); | |
76 | 1 | case BV_kIOS: | |
77 | 1 | return _load<kIOS>(filename, scale); | |
78 | 2 | case BV_OBBRSS: | |
79 | 2 | return _load<OBBRSS>(filename, scale); | |
80 | 1 | case BV_KDOP16: | |
81 | 1 | return _load<KDOP<16> >(filename, scale); | |
82 | 1 | case BV_KDOP18: | |
83 | 1 | return _load<KDOP<18> >(filename, scale); | |
84 | 1 | case BV_KDOP24: | |
85 | 1 | return _load<KDOP<24> >(filename, scale); | |
86 | ✗ | default: | |
87 | ✗ | COAL_THROW_PRETTY("Unhandled bouding volume type.", | |
88 | std::invalid_argument); | ||
89 | } | ||
90 | } | ||
91 | |||
92 | ✗ | CollisionGeometryPtr_t MeshLoader::loadOctree(const std::string& filename) { | |
93 | #ifdef COAL_HAS_OCTOMAP | ||
94 | ✗ | shared_ptr<octomap::OcTree> octree(new octomap::OcTree(filename)); | |
95 | ✗ | return CollisionGeometryPtr_t(new coal::OcTree(octree)); | |
96 | #else | ||
97 | COAL_THROW_PRETTY("Coal compiled without OctoMap. Cannot create OcTrees.", | ||
98 | std::logic_error); | ||
99 | #endif | ||
100 | } | ||
101 | |||
102 | 16 | BVHModelPtr_t CachedMeshLoader::load(const std::string& filename, | |
103 | const Vec3s& scale) { | ||
104 |
1/2✓ Branch 1 taken 16 times.
✗ Branch 2 not taken.
|
16 | Key key(filename, scale); |
105 | |||
106 | 16 | std::time_t mtime = 0; | |
107 | try { | ||
108 |
2/4✓ Branch 1 taken 16 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16 times.
✗ Branch 5 not taken.
|
16 | mtime = boost::filesystem::last_write_time(filename); |
109 | |||
110 |
1/2✓ Branch 1 taken 16 times.
✗ Branch 2 not taken.
|
16 | Cache_t::const_iterator _cached = cache_.find(key); |
111 |
5/6✓ Branch 3 taken 8 times.
✓ Branch 4 taken 8 times.
✓ Branch 6 taken 8 times.
✗ Branch 7 not taken.
✓ Branch 8 taken 8 times.
✓ Branch 9 taken 8 times.
|
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 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
8 | BVHModelPtr_t geom = MeshLoader::load(filename, scale); |
120 | 8 | Value val; | |
121 | 8 | val.model = geom; | |
122 | 8 | val.mtime = mtime; | |
123 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
8 | cache_[key] = val; |
124 | 8 | return geom; | |
125 | 16 | } | |
126 | } // namespace coal | ||
127 |