-
Notifications
You must be signed in to change notification settings - Fork 417
/
narrowphase.cpp
executable file
·3574 lines (3122 loc) · 116 KB
/
narrowphase.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2011-2014, Willow Garage, Inc.
* Copyright (c) 2014-2016, Open Source Robotics Foundation
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Open Source Robotics Foundation nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
/** \author Jia Pan */
#include "fcl/narrowphase/narrowphase.h"
#include "fcl/shape/geometric_shapes_utility.h"
#include "fcl/intersect.h"
#include <vector>
namespace fcl
{
namespace details
{
// Clamp n to lie within the range [min, max]
float clamp(float n, float min, float max) {
if (n < min) return min;
if (n > max) return max;
return n;
}
// Computes closest points C1 and C2 of S1(s)=P1+s*(Q1-P1) and
// S2(t)=P2+t*(Q2-P2), returning s and t. Function result is squared
// distance between between S1(s) and S2(t)
float closestPtSegmentSegment(Vec3f p1, Vec3f q1, Vec3f p2, Vec3f q2,
float &s, float &t, Vec3f &c1, Vec3f &c2)
{
const float EPSILON = 0.001;
Vec3f d1 = q1 - p1; // Direction vector of segment S1
Vec3f d2 = q2 - p2; // Direction vector of segment S2
Vec3f r = p1 - p2;
float a = d1.dot(d1); // Squared length of segment S1, always nonnegative
float e = d2.dot(d2); // Squared length of segment S2, always nonnegative
float f = d2.dot(r);
// Check if either or both segments degenerate into points
if (a <= EPSILON && e <= EPSILON) {
// Both segments degenerate into points
s = t = 0.0f;
c1 = p1;
c2 = p2;
Vec3f diff = c1-c2;
float res = diff.dot(diff);
return res;
}
if (a <= EPSILON) {
// First segment degenerates into a point
s = 0.0f;
t = f / e; // s = 0 => t = (b*s + f) / e = f / e
t = clamp(t, 0.0f, 1.0f);
} else {
float c = d1.dot(r);
if (e <= EPSILON) {
// Second segment degenerates into a point
t = 0.0f;
s = clamp(-c / a, 0.0f, 1.0f); // t = 0 => s = (b*t - c) / a = -c / a
} else {
// The general nondegenerate case starts here
float b = d1.dot(d2);
float denom = a*e-b*b; // Always nonnegative
// If segments not parallel, compute closest point on L1 to L2 and
// clamp to segment S1. Else pick arbitrary s (here 0)
if (denom != 0.0f) {
std::cerr << "denominator equals zero, using 0 as reference" << std::endl;
s = clamp((b*f - c*e) / denom, 0.0f, 1.0f);
} else s = 0.0f;
// Compute point on L2 closest to S1(s) using
// t = Dot((P1 + D1*s) - P2,D2) / Dot(D2,D2) = (b*s + f) / e
t = (b*s + f) / e;
//
//If t in [0,1] done. Else clamp t, recompute s for the new value
//of t using s = Dot((P2 + D2*t) - P1,D1) / Dot(D1,D1)= (t*b - c) / a
//and clamp s to [0, 1]
if(t < 0.0f) {
t = 0.0f;
s = clamp(-c / a, 0.0f, 1.0f);
} else if (t > 1.0f) {
t = 1.0f;
s = clamp((b - c) / a, 0.0f, 1.0f);
}
}
}
c1 = p1 + d1 * s;
c2 = p2 + d2 * t;
Vec3f diff = c1-c2;
float res = diff.dot(diff);
return res;
}
// Computes closest points C1 and C2 of S1(s)=P1+s*(Q1-P1) and
// S2(t)=P2+t*(Q2-P2), returning s and t. Function result is squared
// distance between between S1(s) and S2(t)
bool capsuleCapsuleDistance(const Capsule& s1, const Transform3f& tf1,
const Capsule& s2, const Transform3f& tf2,
FCL_REAL* dist, Vec3f* p1_res, Vec3f* p2_res)
{
Vec3f p1(tf1.getTranslation());
Vec3f p2(tf2.getTranslation());
// line segment composes two points. First point is given by the origin, second point is computed by the origin transformed along z.
// extension along z-axis means transformation with identity matrix and translation vector z pos
Transform3f transformQ1(Vec3f(0,0,s1.lz));
transformQ1 = tf1 * transformQ1;
Vec3f q1 = transformQ1.getTranslation();
Transform3f transformQ2(Vec3f(0,0,s2.lz));
transformQ2 = tf2 * transformQ2;
Vec3f q2 = transformQ2.getTranslation();
// s and t correspont to the length of the line segment
float s, t;
Vec3f c1, c2;
float result = closestPtSegmentSegment(p1, q1, p2, q2, s, t, c1, c2);
*dist = sqrt(result)-s1.radius-s2.radius;
// getting directional unit vector
Vec3f distVec = c2 -c1;
distVec.normalize();
// extend the point to be border of the capsule.
// Done by following the directional unit vector for the length of the capsule radius
*p1_res = c1 + distVec*s1.radius;
distVec = c1-c2;
distVec.normalize();
*p2_res = c2 + distVec*s2.radius;
return true;
}
// Compute the point on a line segment that is the closest point on the
// segment to to another point. The code is inspired by the explanation
// given by Dan Sunday's page:
// http://geomalgorithms.com/a02-_lines.html
static inline void lineSegmentPointClosestToPoint (const Vec3f &p, const Vec3f &s1, const Vec3f &s2, Vec3f &sp) {
Vec3f v = s2 - s1;
Vec3f w = p - s1;
FCL_REAL c1 = w.dot(v);
FCL_REAL c2 = v.dot(v);
if (c1 <= 0) {
sp = s1;
} else if (c2 <= c1) {
sp = s2;
} else {
FCL_REAL b = c1/c2;
Vec3f Pb = s1 + v * b;
sp = Pb;
}
}
bool sphereCapsuleIntersect(const Sphere& s1, const Transform3f& tf1,
const Capsule& s2, const Transform3f& tf2,
std::vector<ContactPoint>* contacts)
{
Transform3f tf2_inv(tf2);
tf2_inv.inverse();
const Vec3f pos1(0., 0., 0.5 * s2.lz);
const Vec3f pos2(0., 0., -0.5 * s2.lz);
const Vec3f s_c = tf2_inv.transform(tf1.transform(Vec3f()));
Vec3f segment_point;
lineSegmentPointClosestToPoint (s_c, pos1, pos2, segment_point);
Vec3f diff = s_c - segment_point;
const FCL_REAL distance = diff.length() - s1.radius - s2.radius;
if (distance > 0)
return false;
const Vec3f local_normal = diff.normalize() * - FCL_REAL(1);
if (contacts)
{
const Vec3f normal = tf2.getQuatRotation().transform(local_normal);
const Vec3f point = tf2.transform(segment_point + local_normal * distance);
const FCL_REAL penetration_depth = -distance;
contacts->push_back(ContactPoint(normal, point, penetration_depth));
}
return true;
}
bool sphereCapsuleDistance(const Sphere& s1, const Transform3f& tf1,
const Capsule& s2, const Transform3f& tf2,
FCL_REAL* dist, Vec3f* p1, Vec3f* p2)
{
Transform3f tf2_inv(tf2);
tf2_inv.inverse();
Vec3f pos1(0., 0., 0.5 * s2.lz);
Vec3f pos2(0., 0., -0.5 * s2.lz);
Vec3f s_c = tf2_inv.transform(tf1.transform(Vec3f()));
Vec3f segment_point;
lineSegmentPointClosestToPoint (s_c, pos1, pos2, segment_point);
Vec3f diff = s_c - segment_point;
FCL_REAL distance = diff.length() - s1.radius - s2.radius;
if(distance <= 0)
return false;
if(dist) *dist = distance;
if(p1 || p2) diff.normalize();
if(p1)
{
*p1 = s_c - diff * s1.radius;
*p1 = inverse(tf1).transform(tf2.transform(*p1));
}
if(p2) *p2 = segment_point + diff * s1.radius;
return true;
}
bool sphereSphereIntersect(const Sphere& s1, const Transform3f& tf1,
const Sphere& s2, const Transform3f& tf2,
std::vector<ContactPoint>* contacts)
{
Vec3f diff = tf2.transform(Vec3f()) - tf1.transform(Vec3f());
FCL_REAL len = diff.length();
if(len > s1.radius + s2.radius)
return false;
if(contacts)
{
// If the centers of two sphere are at the same position, the normal is (0, 0, 0).
// Otherwise, normal is pointing from center of object 1 to center of object 2
const Vec3f normal = len > 0 ? diff / len : diff;
const Vec3f point = tf1.transform(Vec3f()) + diff * s1.radius / (s1.radius + s2.radius);
const FCL_REAL penetration_depth = s1.radius + s2.radius - len;
contacts->push_back(ContactPoint(normal, point, penetration_depth));
}
return true;
}
bool sphereSphereDistance(const Sphere& s1, const Transform3f& tf1,
const Sphere& s2, const Transform3f& tf2,
FCL_REAL* dist, Vec3f* p1, Vec3f* p2)
{
Vec3f o1 = tf1.getTranslation();
Vec3f o2 = tf2.getTranslation();
Vec3f diff = o1 - o2;
FCL_REAL len = diff.length();
if(len > s1.radius + s2.radius)
{
if(dist) *dist = len - (s1.radius + s2.radius);
if(p1) *p1 = inverse(tf1).transform(o1 - diff * (s1.radius / len));
if(p2) *p2 = inverse(tf2).transform(o2 + diff * (s2.radius / len));
return true;
}
if(dist) *dist = -1;
return false;
}
/** \brief the minimum distance from a point to a line */
FCL_REAL segmentSqrDistance(const Vec3f& from, const Vec3f& to,const Vec3f& p, Vec3f& nearest)
{
Vec3f diff = p - from;
Vec3f v = to - from;
FCL_REAL t = v.dot(diff);
if(t > 0)
{
FCL_REAL dotVV = v.dot(v);
if(t < dotVV)
{
t /= dotVV;
diff -= v * t;
}
else
{
t = 1;
diff -= v;
}
}
else
t = 0;
nearest = from + v * t;
return diff.dot(diff);
}
/// @brief Whether a point's projection is in a triangle
bool projectInTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3, const Vec3f& normal, const Vec3f& p)
{
Vec3f edge1(p2 - p1);
Vec3f edge2(p3 - p2);
Vec3f edge3(p1 - p3);
Vec3f p1_to_p(p - p1);
Vec3f p2_to_p(p - p2);
Vec3f p3_to_p(p - p3);
Vec3f edge1_normal(edge1.cross(normal));
Vec3f edge2_normal(edge2.cross(normal));
Vec3f edge3_normal(edge3.cross(normal));
FCL_REAL r1, r2, r3;
r1 = edge1_normal.dot(p1_to_p);
r2 = edge2_normal.dot(p2_to_p);
r3 = edge3_normal.dot(p3_to_p);
if ( ( r1 > 0 && r2 > 0 && r3 > 0 ) ||
( r1 <= 0 && r2 <= 0 && r3 <= 0 ) )
return true;
return false;
}
bool sphereTriangleIntersect(const Sphere& s, const Transform3f& tf,
const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, Vec3f* contact_points, FCL_REAL* penetration_depth, Vec3f* normal_)
{
Vec3f normal = (P2 - P1).cross(P3 - P1);
normal.normalize();
const Vec3f& center = tf.getTranslation();
const FCL_REAL& radius = s.radius;
FCL_REAL radius_with_threshold = radius + std::numeric_limits<FCL_REAL>::epsilon();
Vec3f p1_to_center = center - P1;
FCL_REAL distance_from_plane = p1_to_center.dot(normal);
if(distance_from_plane < 0)
{
distance_from_plane *= -1;
normal *= -1;
}
bool is_inside_contact_plane = (distance_from_plane < radius_with_threshold);
bool has_contact = false;
Vec3f contact_point;
if(is_inside_contact_plane)
{
if(projectInTriangle(P1, P2, P3, normal, center))
{
has_contact = true;
contact_point = center - normal * distance_from_plane;
}
else
{
FCL_REAL contact_capsule_radius_sqr = radius_with_threshold * radius_with_threshold;
Vec3f nearest_on_edge;
FCL_REAL distance_sqr;
distance_sqr = segmentSqrDistance(P1, P2, center, nearest_on_edge);
if(distance_sqr < contact_capsule_radius_sqr)
{
has_contact = true;
contact_point = nearest_on_edge;
}
distance_sqr = segmentSqrDistance(P2, P3, center, nearest_on_edge);
if(distance_sqr < contact_capsule_radius_sqr)
{
has_contact = true;
contact_point = nearest_on_edge;
}
distance_sqr = segmentSqrDistance(P3, P1, center, nearest_on_edge);
if(distance_sqr < contact_capsule_radius_sqr)
{
has_contact = true;
contact_point = nearest_on_edge;
}
}
}
if(has_contact)
{
Vec3f contact_to_center = contact_point - center;
FCL_REAL distance_sqr = contact_to_center.sqrLength();
if(distance_sqr < radius_with_threshold * radius_with_threshold)
{
if(distance_sqr > 0)
{
FCL_REAL distance = std::sqrt(distance_sqr);
if(normal_) *normal_ = normalize(contact_to_center);
if(contact_points) *contact_points = contact_point;
if(penetration_depth) *penetration_depth = -(radius - distance);
}
else
{
if(normal_) *normal_ = -normal;
if(contact_points) *contact_points = contact_point;
if(penetration_depth) *penetration_depth = -radius;
}
return true;
}
}
return false;
}
bool sphereTriangleDistance(const Sphere& sp, const Transform3f& tf,
const Vec3f& P1, const Vec3f& P2, const Vec3f& P3,
FCL_REAL* dist)
{
// from geometric tools, very different from the collision code.
const Vec3f& center = tf.getTranslation();
FCL_REAL radius = sp.radius;
Vec3f diff = P1 - center;
Vec3f edge0 = P2 - P1;
Vec3f edge1 = P3 - P1;
FCL_REAL a00 = edge0.sqrLength();
FCL_REAL a01 = edge0.dot(edge1);
FCL_REAL a11 = edge1.sqrLength();
FCL_REAL b0 = diff.dot(edge0);
FCL_REAL b1 = diff.dot(edge1);
FCL_REAL c = diff.sqrLength();
FCL_REAL det = fabs(a00*a11 - a01*a01);
FCL_REAL s = a01*b1 - a11*b0;
FCL_REAL t = a01*b0 - a00*b1;
FCL_REAL sqr_dist;
if(s + t <= det)
{
if(s < 0)
{
if(t < 0) // region 4
{
if(b0 < 0)
{
t = 0;
if(-b0 >= a00)
{
s = 1;
sqr_dist = a00 + 2*b0 + c;
}
else
{
s = -b0/a00;
sqr_dist = b0*s + c;
}
}
else
{
s = 0;
if(b1 >= 0)
{
t = 0;
sqr_dist = c;
}
else if(-b1 >= a11)
{
t = 1;
sqr_dist = a11 + 2*b1 + c;
}
else
{
t = -b1/a11;
sqr_dist = b1*t + c;
}
}
}
else // region 3
{
s = 0;
if(b1 >= 0)
{
t = 0;
sqr_dist = c;
}
else if(-b1 >= a11)
{
t = 1;
sqr_dist = a11 + 2*b1 + c;
}
else
{
t = -b1/a11;
sqr_dist = b1*t + c;
}
}
}
else if(t < 0) // region 5
{
t = 0;
if(b0 >= 0)
{
s = 0;
sqr_dist = c;
}
else if(-b0 >= a00)
{
s = 1;
sqr_dist = a00 + 2*b0 + c;
}
else
{
s = -b0/a00;
sqr_dist = b0*s + c;
}
}
else // region 0
{
// minimum at interior point
FCL_REAL inv_det = (1)/det;
s *= inv_det;
t *= inv_det;
sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
}
}
else
{
FCL_REAL tmp0, tmp1, numer, denom;
if(s < 0) // region 2
{
tmp0 = a01 + b0;
tmp1 = a11 + b1;
if(tmp1 > tmp0)
{
numer = tmp1 - tmp0;
denom = a00 - 2*a01 + a11;
if(numer >= denom)
{
s = 1;
t = 0;
sqr_dist = a00 + 2*b0 + c;
}
else
{
s = numer/denom;
t = 1 - s;
sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
}
}
else
{
s = 0;
if(tmp1 <= 0)
{
t = 1;
sqr_dist = a11 + 2*b1 + c;
}
else if(b1 >= 0)
{
t = 0;
sqr_dist = c;
}
else
{
t = -b1/a11;
sqr_dist = b1*t + c;
}
}
}
else if(t < 0) // region 6
{
tmp0 = a01 + b1;
tmp1 = a00 + b0;
if(tmp1 > tmp0)
{
numer = tmp1 - tmp0;
denom = a00 - 2*a01 + a11;
if(numer >= denom)
{
t = 1;
s = 0;
sqr_dist = a11 + 2*b1 + c;
}
else
{
t = numer/denom;
s = 1 - t;
sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
}
}
else
{
t = 0;
if(tmp1 <= 0)
{
s = 1;
sqr_dist = a00 + 2*b0 + c;
}
else if(b0 >= 0)
{
s = 0;
sqr_dist = c;
}
else
{
s = -b0/a00;
sqr_dist = b0*s + c;
}
}
}
else // region 1
{
numer = a11 + b1 - a01 - b0;
if(numer <= 0)
{
s = 0;
t = 1;
sqr_dist = a11 + 2*b1 + c;
}
else
{
denom = a00 - 2*a01 + a11;
if(numer >= denom)
{
s = 1;
t = 0;
sqr_dist = a00 + 2*b0 + c;
}
else
{
s = numer/denom;
t = 1 - s;
sqr_dist = s*(a00*s + a01*t + 2*b0) + t*(a01*s + a11*t + 2*b1) + c;
}
}
}
}
// Account for numerical round-off error.
if(sqr_dist < 0)
sqr_dist = 0;
if(sqr_dist > radius * radius)
{
if(dist) *dist = std::sqrt(sqr_dist) - radius;
return true;
}
else
{
if(dist) *dist = -1;
return false;
}
}
bool sphereTriangleDistance(const Sphere& sp, const Transform3f& tf,
const Vec3f& P1, const Vec3f& P2, const Vec3f& P3,
FCL_REAL* dist, Vec3f* p1, Vec3f* p2)
{
if(p1 || p2)
{
Vec3f o = tf.getTranslation();
Project::ProjectResult result;
result = Project::projectTriangle(P1, P2, P3, o);
if(result.sqr_distance > sp.radius * sp.radius)
{
if(dist) *dist = std::sqrt(result.sqr_distance) - sp.radius;
Vec3f project_p = P1 * result.parameterization[0] + P2 * result.parameterization[1] + P3 * result.parameterization[2];
Vec3f dir = o - project_p;
dir.normalize();
if(p1) { *p1 = o - dir * sp.radius; *p1 = inverse(tf).transform(*p1); }
if(p2) *p2 = project_p;
return true;
}
else
return false;
}
else
{
return sphereTriangleDistance(sp, tf, P1, P2, P3, dist);
}
}
bool sphereTriangleDistance(const Sphere& sp, const Transform3f& tf1,
const Vec3f& P1, const Vec3f& P2, const Vec3f& P3, const Transform3f& tf2,
FCL_REAL* dist, Vec3f* p1, Vec3f* p2)
{
bool res = details::sphereTriangleDistance(sp, tf1, tf2.transform(P1), tf2.transform(P2), tf2.transform(P3), dist, p1, p2);
if(p2) *p2 = inverse(tf2).transform(*p2);
return res;
}
static inline void lineClosestApproach(const Vec3f& pa, const Vec3f& ua,
const Vec3f& pb, const Vec3f& ub,
FCL_REAL* alpha, FCL_REAL* beta)
{
Vec3f p = pb - pa;
FCL_REAL uaub = ua.dot(ub);
FCL_REAL q1 = ua.dot(p);
FCL_REAL q2 = -ub.dot(p);
FCL_REAL d = 1 - uaub * uaub;
if(d <= (FCL_REAL)(0.0001f))
{
*alpha = 0;
*beta = 0;
}
else
{
d = 1 / d;
*alpha = (q1 + uaub * q2) * d;
*beta = (uaub * q1 + q2) * d;
}
}
// find all the intersection points between the 2D rectangle with vertices
// at (+/-h[0],+/-h[1]) and the 2D quadrilateral with vertices (p[0],p[1]),
// (p[2],p[3]),(p[4],p[5]),(p[6],p[7]).
//
// the intersection points are returned as x,y pairs in the 'ret' array.
// the number of intersection points is returned by the function (this will
// be in the range 0 to 8).
static int intersectRectQuad2(FCL_REAL h[2], FCL_REAL p[8], FCL_REAL ret[16])
{
// q (and r) contain nq (and nr) coordinate points for the current (and
// chopped) polygons
int nq = 4, nr = 0;
FCL_REAL buffer[16];
FCL_REAL* q = p;
FCL_REAL* r = ret;
for(int dir = 0; dir <= 1; ++dir)
{
// direction notation: xy[0] = x axis, xy[1] = y axis
for(int sign = -1; sign <= 1; sign += 2)
{
// chop q along the line xy[dir] = sign*h[dir]
FCL_REAL* pq = q;
FCL_REAL* pr = r;
nr = 0;
for(int i = nq; i > 0; --i)
{
// go through all points in q and all lines between adjacent points
if(sign * pq[dir] < h[dir])
{
// this point is inside the chopping line
pr[0] = pq[0];
pr[1] = pq[1];
pr += 2;
nr++;
if(nr & 8)
{
q = r;
goto done;
}
}
FCL_REAL* nextq = (i > 1) ? pq+2 : q;
if((sign*pq[dir] < h[dir]) ^ (sign*nextq[dir] < h[dir]))
{
// this line crosses the chopping line
pr[1-dir] = pq[1-dir] + (nextq[1-dir]-pq[1-dir]) /
(nextq[dir]-pq[dir]) * (sign*h[dir]-pq[dir]);
pr[dir] = sign*h[dir];
pr += 2;
nr++;
if(nr & 8)
{
q = r;
goto done;
}
}
pq += 2;
}
q = r;
r = (q == ret) ? buffer : ret;
nq = nr;
}
}
done:
if(q != ret) memcpy(ret, q, nr*2*sizeof(FCL_REAL));
return nr;
}
// given n points in the plane (array p, of size 2*n), generate m points that
// best represent the whole set. the definition of 'best' here is not
// predetermined - the idea is to select points that give good box-box
// collision detection behavior. the chosen point indexes are returned in the
// array iret (of size m). 'i0' is always the first entry in the array.
// n must be in the range [1..8]. m must be in the range [1..n]. i0 must be
// in the range [0..n-1].
static inline void cullPoints2(int n, FCL_REAL p[], int m, int i0, int iret[])
{
// compute the centroid of the polygon in cx,cy
FCL_REAL a, cx, cy, q;
switch(n)
{
case 1:
cx = p[0];
cy = p[1];
break;
case 2:
cx = 0.5 * (p[0] + p[2]);
cy = 0.5 * (p[1] + p[3]);
break;
default:
a = 0;
cx = 0;
cy = 0;
for(int i = 0; i < n-1; ++i)
{
q = p[i*2]*p[i*2+3] - p[i*2+2]*p[i*2+1];
a += q;
cx += q*(p[i*2]+p[i*2+2]);
cy += q*(p[i*2+1]+p[i*2+3]);
}
q = p[n*2-2]*p[1] - p[0]*p[n*2-1];
if(std::abs(a+q) > std::numeric_limits<FCL_REAL>::epsilon())
a = 1/(3*(a+q));
else
a= 1e18f;
cx = a*(cx + q*(p[n*2-2]+p[0]));
cy = a*(cy + q*(p[n*2-1]+p[1]));
}
// compute the angle of each point w.r.t. the centroid
FCL_REAL A[8];
for(int i = 0; i < n; ++i)
A[i] = atan2(p[i*2+1]-cy,p[i*2]-cx);
// search for points that have angles closest to A[i0] + i*(2*pi/m).
int avail[8];
for(int i = 0; i < n; ++i) avail[i] = 1;
avail[i0] = 0;
iret[0] = i0;
iret++;
const double pi = constants::pi;
for(int j = 1; j < m; ++j)
{
a = j*(2*pi/m) + A[i0];
if (a > pi) a -= 2*pi;
FCL_REAL maxdiff= 1e9, diff;
*iret = i0; // iret is not allowed to keep this value, but it sometimes does, when diff=#QNAN0
for(int i = 0; i < n; ++i)
{
if(avail[i])
{
diff = std::abs(A[i]-a);
if(diff > pi) diff = 2*pi - diff;
if(diff < maxdiff)
{
maxdiff = diff;
*iret = i;
}
}
}
avail[*iret] = 0;
iret++;
}
}
int boxBox2(const Vec3f& side1, const Matrix3f& R1, const Vec3f& T1,
const Vec3f& side2, const Matrix3f& R2, const Vec3f& T2,
Vec3f& normal, FCL_REAL* depth, int* return_code,
int maxc, std::vector<ContactPoint>& contacts)
{
const FCL_REAL fudge_factor = FCL_REAL(1.05);
Vec3f normalC;
FCL_REAL s, s2, l;
int invert_normal, code;
Vec3f p = T2 - T1; // get vector from centers of box 1 to box 2, relative to box 1
Vec3f pp = R1.transposeTimes(p); // get pp = p relative to body 1
// get side lengths / 2
Vec3f A = side1 * 0.5;
Vec3f B = side2 * 0.5;
// Rij is R1'*R2, i.e. the relative rotation between R1 and R2
Matrix3f R = R1.transposeTimes(R2);
Matrix3f Q = abs(R);
// for all 15 possible separating axes:
// * see if the axis separates the boxes. if so, return 0.
// * find the depth of the penetration along the separating axis (s2)
// * if this is the largest depth so far, record it.
// the normal vector will be set to the separating axis with the smallest
// depth. note: normalR is set to point to a column of R1 or R2 if that is
// the smallest depth normal so far. otherwise normalR is 0 and normalC is
// set to a vector relative to body 1. invert_normal is 1 if the sign of
// the normal should be flipped.
int best_col_id = -1;
const Matrix3f* normalR = 0;
FCL_REAL tmp = 0;
s = - std::numeric_limits<FCL_REAL>::max();
invert_normal = 0;
code = 0;
// separating axis = u1, u2, u3
tmp = pp[0];
s2 = std::abs(tmp) - (Q.dotX(B) + A[0]);
if(s2 > 0) { *return_code = 0; return 0; }
if(s2 > s)
{
s = s2;
best_col_id = 0;
normalR = &R1;
invert_normal = (tmp < 0);
code = 1;
}
tmp = pp[1];
s2 = std::abs(tmp) - (Q.dotY(B) + A[1]);
if(s2 > 0) { *return_code = 0; return 0; }
if(s2 > s)
{
s = s2;
best_col_id = 1;
normalR = &R1;
invert_normal = (tmp < 0);
code = 2;
}
tmp = pp[2];
s2 = std::abs(tmp) - (Q.dotZ(B) + A[2]);
if(s2 > 0) { *return_code = 0; return 0; }
if(s2 > s)
{
s = s2;
best_col_id = 2;
normalR = &R1;
invert_normal = (tmp < 0);
code = 3;
}
// separating axis = v1, v2, v3
tmp = R2.transposeDotX(p);
s2 = std::abs(tmp) - (Q.transposeDotX(A) + B[0]);
if(s2 > 0) { *return_code = 0; return 0; }
if(s2 > s)
{
s = s2;
best_col_id = 0;
normalR = &R2;
invert_normal = (tmp < 0);
code = 4;
}
tmp = R2.transposeDotY(p);
s2 = std::abs(tmp) - (Q.transposeDotY(A) + B[1]);
if(s2 > 0) { *return_code = 0; return 0; }
if(s2 > s)
{
s = s2;
best_col_id = 1;
normalR = &R2;
invert_normal = (tmp < 0);
code = 5;