GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: test/distance.cpp Lines: 235 255 92.2 %
Date: 2024-02-09 12:57:42 Branches: 720 1962 36.7 %

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
 *  All rights reserved.
7
 *
8
 *  Redistribution and use in source and binary forms, with or without
9
 *  modification, are permitted provided that the following conditions
10
 *  are met:
11
 *
12
 *   * Redistributions of source code must retain the above copyright
13
 *     notice, this list of conditions and the following disclaimer.
14
 *   * Redistributions in binary form must reproduce the above
15
 *     copyright notice, this list of conditions and the following
16
 *     disclaimer in the documentation and/or other materials provided
17
 *     with the distribution.
18
 *   * Neither the name of Open Source Robotics Foundation nor the names of its
19
 *     contributors may be used to endorse or promote products derived
20
 *     from this software without specific prior written permission.
21
 *
22
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25
 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26
 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27
 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28
 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29
 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30
 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31
 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32
 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33
 *  POSSIBILITY OF SUCH DAMAGE.
34
 */
35
36
/** \author Jia Pan */
37
38
#define BOOST_TEST_MODULE FCL_DISTANCE
39
#include <chrono>
40
41
#include <boost/test/included/unit_test.hpp>
42
#include <boost/filesystem.hpp>
43
44
#include <hpp/fcl/internal/traversal_node_bvhs.h>
45
#include <hpp/fcl/internal/traversal_node_setup.h>
46
#include "../src/collision_node.h"
47
#include <hpp/fcl/internal/BV_splitter.h>
48
49
#include "utility.h"
50
#include "fcl_resources/config.h"
51
52
using namespace hpp::fcl;
53
namespace utf = boost::unit_test::framework;
54
55
bool verbose = false;
56
FCL_REAL DELTA = 0.001;
57
58
template <typename BV>
59
void distance_Test(const Transform3f& tf, const std::vector<Vec3f>& vertices1,
60
                   const std::vector<Triangle>& triangles1,
61
                   const std::vector<Vec3f>& vertices2,
62
                   const std::vector<Triangle>& triangles2,
63
                   SplitMethodType split_method, unsigned int qsize,
64
                   DistanceRes& distance_result, bool verbose = true);
65
66
bool collide_Test_OBB(const Transform3f& tf,
67
                      const std::vector<Vec3f>& vertices1,
68
                      const std::vector<Triangle>& triangles1,
69
                      const std::vector<Vec3f>& vertices2,
70
                      const std::vector<Triangle>& triangles2,
71
                      SplitMethodType split_method, bool verbose);
72
73
template <typename BV, typename TraversalNode>
74
void distance_Test_Oriented(const Transform3f& tf,
75
                            const std::vector<Vec3f>& vertices1,
76
                            const std::vector<Triangle>& triangles1,
77
                            const std::vector<Vec3f>& vertices2,
78
                            const std::vector<Triangle>& triangles2,
79
                            SplitMethodType split_method, unsigned int qsize,
80
                            DistanceRes& distance_result, bool verbose = true);
81
82
inline bool nearlyEqual(const Vec3f& a, const Vec3f& b) {
83
  if (fabs(a[0] - b[0]) > DELTA) return false;
84
  if (fabs(a[1] - b[1]) > DELTA) return false;
85
  if (fabs(a[2] - b[2]) > DELTA) return false;
86
  return true;
87
}
88
89
















4
BOOST_AUTO_TEST_CASE(mesh_distance) {
90
4
  std::vector<Vec3f> p1, p2;
91
4
  std::vector<Triangle> t1, t2;
92
4
  boost::filesystem::path path(TEST_RESOURCES_DIR);
93

2
  loadOBJFile((path / "env.obj").string().c_str(), p1, t1);
94

2
  loadOBJFile((path / "rob.obj").string().c_str(), p2, t2);
95
96
2
  std::vector<Transform3f> transforms;  // t0
97
2
  FCL_REAL extents[] = {-3000, -3000, 0, 3000, 3000, 3000};
98
#ifndef NDEBUG  // if debug mode
99
2
  std::size_t n = 1;
100
#else
101
  std::size_t n = 10;
102
#endif
103

2
  n = getNbRun(utf::master_test_suite().argc, utf::master_test_suite().argv, n);
104
105
2
  generateRandomTransforms(extents, transforms, n);
106
107
2
  double dis_time = 0;
108
2
  double col_time = 0;
109
110

2
  DistanceRes res, res_now;
111
4
  for (std::size_t i = 0; i < transforms.size(); ++i) {
112
2
    auto timer_col = std::chrono::high_resolution_clock::now();
113
2
    collide_Test_OBB(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, verbose);
114
2
    col_time += std::chrono::duration_cast<std::chrono::duration<double>>(
115

2
                    std::chrono::high_resolution_clock::now() - timer_col)
116
2
                    .count();
117
118
2
    auto timer_dist = std::chrono::high_resolution_clock::now();
119
2
    distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(
120
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2, res, verbose);
121
2
    dis_time += std::chrono::duration_cast<std::chrono::duration<double>>(
122

2
                    std::chrono::high_resolution_clock::now() - timer_dist)
123
2
                    .count();
124
125
2
    distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(
126
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2, res_now,
127
        verbose);
128
129



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
130






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
131
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
132
                 nearlyEqual(res.p2, res_now.p2)));
133
134
2
    distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(
135
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2, res_now,
136
        verbose);
137
138



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
139






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
140
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
141
                 nearlyEqual(res.p2, res_now.p2)));
142
143
2
    distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(
144
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20, res_now, verbose);
145
146



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
147






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
148
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
149
                 nearlyEqual(res.p2, res_now.p2)));
150
151
2
    distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(
152
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 20, res_now,
153
        verbose);
154
155



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
156






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
157
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
158
                 nearlyEqual(res.p2, res_now.p2)));
159
160
2
    distance_Test_Oriented<RSS, MeshDistanceTraversalNodeRSS>(
161
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20, res_now,
162
        verbose);
163
164



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
165






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
166
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
167
                 nearlyEqual(res.p2, res_now.p2)));
168
169
2
    distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(
170
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2, res_now, verbose);
171
172



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
173






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
174
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
175
                 nearlyEqual(res.p2, res_now.p2)));
176
177
2
    distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(
178
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2, res_now,
179
        verbose);
180
181



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
182






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
183
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
184
                 nearlyEqual(res.p2, res_now.p2)));
185
186
2
    distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(
187
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2, res_now,
188
        verbose);
189
190



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
191






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
192
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
193
                 nearlyEqual(res.p2, res_now.p2)));
194
195
2
    distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(
196
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20, res_now, verbose);
197
198



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
199






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
200
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
201
                 nearlyEqual(res.p2, res_now.p2)));
202
203
2
    distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(
204
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20, res_now,
205
        verbose);
206
207



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
208






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
209
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
210
                 nearlyEqual(res.p2, res_now.p2)));
211
212
2
    distance_Test_Oriented<kIOS, MeshDistanceTraversalNodekIOS>(
213
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 20, res_now,
214
        verbose);
215
216



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
217






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
218
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
219
                 nearlyEqual(res.p2, res_now.p2)));
220
221
2
    distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(
222
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2, res_now, verbose);
223
224



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
225






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
226
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
227
                 nearlyEqual(res.p2, res_now.p2)));
228
229
2
    distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(
230
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2, res_now,
231
        verbose);
232
233



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
234






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
235
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
236
                 nearlyEqual(res.p2, res_now.p2)));
237
238
2
    distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(
239
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2, res_now,
240
        verbose);
241
242



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
243






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
244
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
245
                 nearlyEqual(res.p2, res_now.p2)));
246
247
2
    distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(
248
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20, res_now, verbose);
249
250



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
251






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
252
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
253
                 nearlyEqual(res.p2, res_now.p2)));
254
255
2
    distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(
256
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20, res_now,
257
        verbose);
258
259



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
260






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
261
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
262
                 nearlyEqual(res.p2, res_now.p2)));
263
264
2
    distance_Test_Oriented<OBBRSS, MeshDistanceTraversalNodeOBBRSS>(
265
2
        transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 20, res_now,
266
        verbose);
267
268



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
269






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
270
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
271
                 nearlyEqual(res.p2, res_now.p2)));
272
273
2
    distance_Test<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2,
274
                       res_now, verbose);
275
276



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
277






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
278
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
279
                 nearlyEqual(res.p2, res_now.p2)));
280
281
2
    distance_Test<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2,
282
                       res_now, verbose);
283
284



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
285






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
286
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
287
                 nearlyEqual(res.p2, res_now.p2)));
288
289
2
    distance_Test<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2,
290
                       res_now, verbose);
291
292



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
293






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
294
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
295
                 nearlyEqual(res.p2, res_now.p2)));
296
297
2
    distance_Test<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20,
298
                       res_now, verbose);
299
300



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
301






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
302
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
303
                 nearlyEqual(res.p2, res_now.p2)));
304
305
2
    distance_Test<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER,
306
                       20, res_now, verbose);
307
308



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
309






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
310
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
311
                 nearlyEqual(res.p2, res_now.p2)));
312
313
2
    distance_Test<OBB>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20,
314
                       res_now, verbose);
315
316



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
317






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
318
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
319
                 nearlyEqual(res.p2, res_now.p2)));
320
321
2
    distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2,
322
                       res_now, verbose);
323
324



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
325






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
326
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
327
                 nearlyEqual(res.p2, res_now.p2)));
328
329
2
    distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER, 2,
330
                       res_now, verbose);
331
332



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
333






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
334
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
335
                 nearlyEqual(res.p2, res_now.p2)));
336
337
2
    distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2,
338
                       res_now, verbose);
339
340



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
341






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
342
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
343
                 nearlyEqual(res.p2, res_now.p2)));
344
345
2
    distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20,
346
                       res_now, verbose);
347
348



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
349






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
350
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
351
                 nearlyEqual(res.p2, res_now.p2)));
352
353
2
    distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER,
354
                       20, res_now, verbose);
355
356



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
357






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
358
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
359
                 nearlyEqual(res.p2, res_now.p2)));
360
361
2
    distance_Test<RSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20,
362
                       res_now, verbose);
363
364



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
365






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
366
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
367
                 nearlyEqual(res.p2, res_now.p2)));
368
369
2
    distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2,
370
                        res_now, verbose);
371
372



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
373






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
374
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
375
                 nearlyEqual(res.p2, res_now.p2)));
376
377
2
    distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2,
378
                        res_now, verbose);
379
380



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
381






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
382
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
383
                 nearlyEqual(res.p2, res_now.p2)));
384
385
2
    distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER,
386
                        2, res_now, verbose);
387
388



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
389






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
390
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
391
                 nearlyEqual(res.p2, res_now.p2)));
392
393
2
    distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20,
394
                        res_now, verbose);
395
396



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
397






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
398
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
399
                 nearlyEqual(res.p2, res_now.p2)));
400
401
2
    distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 20,
402
                        res_now, verbose);
403
404



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
405






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
406
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
407
                 nearlyEqual(res.p2, res_now.p2)));
408
409
2
    distance_Test<kIOS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER,
410
                        20, res_now, verbose);
411
412



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
413






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
414
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
415
                 nearlyEqual(res.p2, res_now.p2)));
416
417
2
    distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 2,
418
                          res_now, verbose);
419
420



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
421






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
422
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
423
                 nearlyEqual(res.p2, res_now.p2)));
424
425
2
    distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN, 2,
426
                          res_now, verbose);
427
428



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
429






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
430
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
431
                 nearlyEqual(res.p2, res_now.p2)));
432
433
2
    distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER,
434
                          2, res_now, verbose);
435
436



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
437






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
438
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
439
                 nearlyEqual(res.p2, res_now.p2)));
440
441
2
    distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEAN, 20,
442
                          res_now, verbose);
443
444



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
445






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
446
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
447
                 nearlyEqual(res.p2, res_now.p2)));
448
449
2
    distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_MEDIAN,
450
                          20, res_now, verbose);
451
452



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
453






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
454
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
455
                 nearlyEqual(res.p2, res_now.p2)));
456
457
2
    distance_Test<OBBRSS>(transforms[i], p1, t1, p2, t2, SPLIT_METHOD_BV_CENTER,
458
                          20, res_now, verbose);
459
460



2
    BOOST_CHECK(fabs(res.distance - res_now.distance) < DELTA);
461






2
    BOOST_CHECK(fabs(res.distance) < DELTA ||
462
                (res.distance > 0 && nearlyEqual(res.p1, res_now.p1) &&
463
                 nearlyEqual(res.p2, res_now.p2)));
464
  }
465
466



2
  BOOST_TEST_MESSAGE("distance timing: " << dis_time << " sec");
467



2
  BOOST_TEST_MESSAGE("collision timing: " << col_time << " sec");
468
2
}
469
470
template <typename BV, typename TraversalNode>
471
36
void distance_Test_Oriented(const Transform3f& tf,
472
                            const std::vector<Vec3f>& vertices1,
473
                            const std::vector<Triangle>& triangles1,
474
                            const std::vector<Vec3f>& vertices2,
475
                            const std::vector<Triangle>& triangles2,
476
                            SplitMethodType split_method, unsigned int qsize,
477
                            DistanceRes& distance_result, bool verbose) {
478
72
  BVHModel<BV> m1;
479
72
  BVHModel<BV> m2;
480

36
  m1.bv_splitter.reset(new BVSplitter<BV>(split_method));
481

36
  m2.bv_splitter.reset(new BVSplitter<BV>(split_method));
482
483
36
  m1.beginModel();
484
36
  m1.addSubModel(vertices1, triangles1);
485
36
  m1.endModel();
486
487
36
  m2.beginModel();
488
36
  m2.addSubModel(vertices2, triangles2);
489
36
  m2.endModel();
490
491
36
  DistanceResult local_result;
492
72
  TraversalNode node;
493


36
  if (!initialize(node, (const BVHModel<BV>&)m1, tf, (const BVHModel<BV>&)m2,
494
                  Transform3f(), DistanceRequest(true), local_result))
495
    std::cout << "initialize error" << std::endl;
496
497
36
  node.enable_statistics = verbose;
498
499
36
  distance(&node, NULL, qsize);
500
501
  // points are in local coordinate, to global coordinate
502
36
  Vec3f p1 = local_result.nearest_points[0];
503
36
  Vec3f p2 = local_result.nearest_points[1];
504
505
36
  distance_result.distance = local_result.min_distance;
506
36
  distance_result.p1 = p1;
507
36
  distance_result.p2 = p2;
508
509
36
  if (verbose) {
510
    std::cout << "distance " << local_result.min_distance << std::endl;
511
512
    std::cout << p1[0] << " " << p1[1] << " " << p1[2] << std::endl;
513
    std::cout << p2[0] << " " << p2[1] << " " << p2[2] << std::endl;
514
    std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl;
515
  }
516
36
}
517
518
template <typename BV>
519
48
void distance_Test(const Transform3f& tf, const std::vector<Vec3f>& vertices1,
520
                   const std::vector<Triangle>& triangles1,
521
                   const std::vector<Vec3f>& vertices2,
522
                   const std::vector<Triangle>& triangles2,
523
                   SplitMethodType split_method, unsigned int qsize,
524
                   DistanceRes& distance_result, bool verbose) {
525
96
  BVHModel<BV> m1;
526
96
  BVHModel<BV> m2;
527

48
  m1.bv_splitter.reset(new BVSplitter<BV>(split_method));
528

48
  m2.bv_splitter.reset(new BVSplitter<BV>(split_method));
529
530
48
  m1.beginModel();
531
48
  m1.addSubModel(vertices1, triangles1);
532
48
  m1.endModel();
533
534
48
  m2.beginModel();
535
48
  m2.addSubModel(vertices2, triangles2);
536
48
  m2.endModel();
537
538

48
  Transform3f pose1(tf), pose2;
539
540
48
  DistanceResult local_result;
541
96
  MeshDistanceTraversalNode<BV> node;
542
543

48
  if (!initialize<BV>(node, m1, pose1, m2, pose2, DistanceRequest(true),
544
                      local_result))
545
    std::cout << "initialize error" << std::endl;
546
547
48
  node.enable_statistics = verbose;
548
549
48
  distance(&node, NULL, qsize);
550
551
48
  distance_result.distance = local_result.min_distance;
552
48
  distance_result.p1 = local_result.nearest_points[0];
553
48
  distance_result.p2 = local_result.nearest_points[1];
554
555
48
  if (verbose) {
556
    std::cout << "distance " << local_result.min_distance << std::endl;
557
558
    std::cout << local_result.nearest_points[0][0] << " "
559
              << local_result.nearest_points[0][1] << " "
560
              << local_result.nearest_points[0][2] << std::endl;
561
    std::cout << local_result.nearest_points[1][0] << " "
562
              << local_result.nearest_points[1][1] << " "
563
              << local_result.nearest_points[1][2] << std::endl;
564
    std::cout << node.num_bv_tests << " " << node.num_leaf_tests << std::endl;
565
  }
566
48
}
567
568
1
bool collide_Test_OBB(const Transform3f& tf,
569
                      const std::vector<Vec3f>& vertices1,
570
                      const std::vector<Triangle>& triangles1,
571
                      const std::vector<Vec3f>& vertices2,
572
                      const std::vector<Triangle>& triangles2,
573
                      SplitMethodType split_method, bool verbose) {
574
2
  BVHModel<OBB> m1;
575
2
  BVHModel<OBB> m2;
576

1
  m1.bv_splitter.reset(new BVSplitter<OBB>(split_method));
577

1
  m2.bv_splitter.reset(new BVSplitter<OBB>(split_method));
578
579
1
  m1.beginModel();
580
1
  m1.addSubModel(vertices1, triangles1);
581
1
  m1.endModel();
582
583
1
  m2.beginModel();
584
1
  m2.addSubModel(vertices2, triangles2);
585
1
  m2.endModel();
586
587
2
  CollisionResult local_result;
588
1
  CollisionRequest request(CONTACT | DISTANCE_LOWER_BOUND, 1);
589
2
  MeshCollisionTraversalNodeOBB node(request);
590
1
  bool success(initialize(node, (const BVHModel<OBB>&)m1, tf,
591
2
                          (const BVHModel<OBB>&)m2, Transform3f(),
592
                          local_result));
593



1
  BOOST_REQUIRE(success);
594
595
1
  node.enable_statistics = verbose;
596
597
1
  collide(&node, request, local_result);
598
599
1
  if (local_result.numContacts() > 0)
600
1
    return true;
601
  else
602
    return false;
603
}