coal 3.0.1
Coal, The Collision Detection Library. Previously known as HPP-FCL, fork of FCL -- The Flexible Collision Library
Loading...
Searching...
No Matches
details.h
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) 2018-2019, Centre National de la Recherche Scientifique
7 * Copyright (c) 2021-2024, INRIA
8 * All rights reserved.
9 *
10 * Redistribution and use in source and binary forms, with or without
11 * modification, are permitted provided that the following conditions
12 * are met:
13 *
14 * * Redistributions of source code must retain the above copyright
15 * notice, this list of conditions and the following disclaimer.
16 * * Redistributions in binary form must reproduce the above
17 * copyright notice, this list of conditions and the following
18 * disclaimer in the documentation and/or other materials provided
19 * with the distribution.
20 * * Neither the name of Open Source Robotics Foundation nor the names of its
21 * contributors may be used to endorse or promote products derived
22 * from this software without specific prior written permission.
23 *
24 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35 * POSSIBILITY OF SUCH DAMAGE.
36 */
39#ifndef COAL_SRC_NARROWPHASE_DETAILS_H
40#define COAL_SRC_NARROWPHASE_DETAILS_H
41
44
45namespace coal {
46namespace details {
47// Compute the point on a line segment that is the closest point on the
48// segment to to another point. The code is inspired by the explanation
49// given by Dan Sunday's page:
50// http://geomalgorithms.com/a02-_lines.html
51static inline void lineSegmentPointClosestToPoint(const Vec3s& p,
52 const Vec3s& s1,
53 const Vec3s& s2, Vec3s& sp) {
54 Vec3s v = s2 - s1;
55 Vec3s w = p - s1;
56
57 Scalar c1 = w.dot(v);
58 Scalar c2 = v.dot(v);
59
60 if (c1 <= 0) {
61 sp = s1;
62 } else if (c2 <= c1) {
63 sp = s2;
64 } else {
65 Scalar b = c1 / c2;
66 Vec3s Pb = s1 + v * b;
67 sp = Pb;
68 }
69}
70
75inline Scalar sphereCapsuleDistance(const Sphere& s1, const Transform3s& tf1,
76 const Capsule& s2, const Transform3s& tf2,
77 Vec3s& p1, Vec3s& p2, Vec3s& normal) {
78 Vec3s pos1(tf2.transform(Vec3s(0., 0., s2.halfLength)));
79 Vec3s pos2(tf2.transform(Vec3s(0., 0., -s2.halfLength)));
80 Vec3s s_c = tf1.getTranslation();
81
82 Vec3s segment_point;
83
84 lineSegmentPointClosestToPoint(s_c, pos1, pos2, segment_point);
85 normal = segment_point - s_c;
86 Scalar norm(normal.norm());
87 Scalar r1 = s1.radius + s1.getSweptSphereRadius();
88 Scalar r2 = s2.radius + s2.getSweptSphereRadius();
89 Scalar dist = norm - r1 - r2;
90
91 static const Scalar eps(std::numeric_limits<Scalar>::epsilon());
92 if (norm > eps) {
93 normal.normalize();
94 } else {
95 normal << 1, 0, 0;
96 }
97 p1 = s_c + normal * r1;
98 p2 = segment_point - normal * r2;
99 return dist;
100}
101
106inline Scalar sphereCylinderDistance(const Sphere& s1, const Transform3s& tf1,
107 const Cylinder& s2, const Transform3s& tf2,
108 Vec3s& p1, Vec3s& p2, Vec3s& normal) {
109 static const Scalar eps(sqrt(std::numeric_limits<Scalar>::epsilon()));
110 Scalar r1(s1.radius);
111 Scalar r2(s2.radius);
112 Scalar lz2(s2.halfLength);
113 // boundaries of the cylinder axis
114 Vec3s A(tf2.transform(Vec3s(0, 0, -lz2)));
115 Vec3s B(tf2.transform(Vec3s(0, 0, lz2)));
116 // Position of the center of the sphere
117 Vec3s S(tf1.getTranslation());
118 // axis of the cylinder
119 Vec3s u(tf2.getRotation().col(2));
122 assert((B - A - (s2.halfLength * 2) * u).norm() < eps);
123 Vec3s AS(S - A);
124 // abscissa of S on cylinder axis with A as the origin
125 Scalar s(u.dot(AS));
126 Vec3s P(A + s * u);
127 Vec3s PS(S - P);
128 Scalar dPS = PS.norm();
129 // Normal to cylinder axis such that plane (A, u, v) contains sphere
130 // center
131 Vec3s v(0, 0, 0);
132 Scalar dist;
133 if (dPS > eps) {
134 // S is not on cylinder axis
135 v = (1 / dPS) * PS;
136 }
137 if (s <= 0) {
138 if (dPS <= r2) {
139 // closest point on cylinder is on cylinder disc basis
140 dist = -s - r1;
141 p1 = S + r1 * u;
142 p2 = A + dPS * v;
143 normal = u;
144 } else {
145 // closest point on cylinder is on cylinder circle basis
146 p2 = A + r2 * v;
147 Vec3s Sp2(p2 - S);
148 Scalar dSp2 = Sp2.norm();
149 if (dSp2 > eps) {
150 normal = (1 / dSp2) * Sp2;
151 p1 = S + r1 * normal;
152 dist = dSp2 - r1;
153 assert(fabs(dist) - (p1 - p2).norm() < eps);
154 } else {
155 // Center of sphere is on cylinder boundary
156 normal = p2 - .5 * (A + B);
157 assert(u.dot(normal) >= 0);
158 normal.normalize();
159 dist = -r1;
160 p1 = S + r1 * normal;
161 }
162 }
163 } else if (s <= (s2.halfLength * 2)) {
164 // 0 < s <= s2.lz
165 normal = -v;
166 dist = dPS - r1 - r2;
167 p2 = P + r2 * v;
168 p1 = S - r1 * v;
169 } else {
170 // lz < s
171 if (dPS <= r2) {
172 // closest point on cylinder is on cylinder disc basis
173 dist = s - (s2.halfLength * 2) - r1;
174 p1 = S - r1 * u;
175 p2 = B + dPS * v;
176 normal = -u;
177 } else {
178 // closest point on cylinder is on cylinder circle basis
179 p2 = B + r2 * v;
180 Vec3s Sp2(p2 - S);
181 Scalar dSp2 = Sp2.norm();
182 if (dSp2 > eps) {
183 normal = (1 / dSp2) * Sp2;
184 p1 = S + r1 * normal;
185 dist = dSp2 - r1;
186 assert(fabs(dist) - (p1 - p2).norm() < eps);
187 } else {
188 // Center of sphere is on cylinder boundary
189 normal = p2 - .5 * (A + B);
190 normal.normalize();
191 p1 = S + r1 * normal;
192 dist = -r1;
193 }
194 }
195 }
196
197 // Take swept-sphere radius into account
198 const Scalar ssr1 = s1.getSweptSphereRadius();
199 const Scalar ssr2 = s2.getSweptSphereRadius();
200 if (ssr1 > 0 || ssr2 > 0) {
201 p1 += ssr1 * normal;
202 p2 -= ssr2 * normal;
203 dist -= (ssr1 + ssr2);
204 }
205
206 return dist;
207}
208
213inline Scalar sphereSphereDistance(const Sphere& s1, const Transform3s& tf1,
214 const Sphere& s2, const Transform3s& tf2,
215 Vec3s& p1, Vec3s& p2, Vec3s& normal) {
216 const coal::Vec3s& center1 = tf1.getTranslation();
217 const coal::Vec3s& center2 = tf2.getTranslation();
218 Scalar r1 = (s1.radius + s1.getSweptSphereRadius());
219 Scalar r2 = (s2.radius + s2.getSweptSphereRadius());
220
221 Vec3s c1c2 = center2 - center1;
222 Scalar cdist = c1c2.norm();
223 Vec3s unit(1, 0, 0);
224 if (cdist > Eigen::NumTraits<Scalar>::epsilon()) unit = c1c2 / cdist;
225 Scalar dist = cdist - r1 - r2;
226 normal = unit;
227 p1.noalias() = center1 + r1 * unit;
228 p2.noalias() = center2 - r2 * unit;
229 return dist;
230}
231
233inline Scalar segmentSqrDistance(const Vec3s& from, const Vec3s& to,
234 const Vec3s& p, Vec3s& nearest) {
235 Vec3s diff = p - from;
236 Vec3s v = to - from;
237 Scalar t = v.dot(diff);
238
239 if (t > 0) {
240 Scalar dotVV = v.squaredNorm();
241 if (t < dotVV) {
242 t /= dotVV;
243 diff -= v * t;
244 } else {
245 t = 1;
246 diff -= v;
247 }
248 } else
249 t = 0;
250
251 nearest.noalias() = from + v * t;
252 return diff.squaredNorm();
253}
254
256inline bool projectInTriangle(const Vec3s& p1, const Vec3s& p2, const Vec3s& p3,
257 const Vec3s& normal, const Vec3s& p) {
258 Vec3s edge1(p2 - p1);
259 Vec3s edge2(p3 - p2);
260 Vec3s edge3(p1 - p3);
261
262 Vec3s p1_to_p(p - p1);
263 Vec3s p2_to_p(p - p2);
264 Vec3s p3_to_p(p - p3);
265
266 Vec3s edge1_normal(edge1.cross(normal));
267 Vec3s edge2_normal(edge2.cross(normal));
268 Vec3s edge3_normal(edge3.cross(normal));
269
270 Scalar r1, r2, r3;
271 r1 = edge1_normal.dot(p1_to_p);
272 r2 = edge2_normal.dot(p2_to_p);
273 r3 = edge3_normal.dot(p3_to_p);
274 if ((r1 > 0 && r2 > 0 && r3 > 0) || (r1 <= 0 && r2 <= 0 && r3 <= 0)) {
275 return true;
276 }
277 return false;
278}
279
285 const TriangleP& tri,
286 const Transform3s& tf2, Vec3s& p1,
287 Vec3s& p2, Vec3s& normal) {
288 const Vec3s& P1 = tf2.transform(tri.a);
289 const Vec3s& P2 = tf2.transform(tri.b);
290 const Vec3s& P3 = tf2.transform(tri.c);
291
292 Vec3s tri_normal = (P2 - P1).cross(P3 - P1);
293 tri_normal.normalize();
294 const Vec3s& center = tf1.getTranslation();
295 // Note: comparing an object with a swept-sphere radius of r1 against another
296 // object with a swept-sphere radius of r2 is equivalent to comparing the
297 // first object with a swept-sphere radius of r1 + r2 against the second
298 // object with a swept-sphere radius of 0.
299 const Scalar& radius =
301 assert(radius >= 0);
302 assert(s.radius >= 0);
303 Vec3s p1_to_center = center - P1;
304 Scalar distance_from_plane = p1_to_center.dot(tri_normal);
305 Vec3s closest_point(
306 Vec3s::Constant(std::numeric_limits<Scalar>::quiet_NaN()));
307 Scalar min_distance_sqr, distance_sqr;
308
309 if (distance_from_plane < 0) {
310 distance_from_plane *= -1;
311 tri_normal *= -1;
312 }
313
314 if (projectInTriangle(P1, P2, P3, tri_normal, center)) {
315 closest_point = center - tri_normal * distance_from_plane;
316 min_distance_sqr = distance_from_plane * distance_from_plane;
317 } else {
318 // Compute distance to each edge and take minimal distance
319 Vec3s nearest_on_edge;
320 min_distance_sqr = segmentSqrDistance(P1, P2, center, closest_point);
321
322 distance_sqr = segmentSqrDistance(P2, P3, center, nearest_on_edge);
323 if (distance_sqr < min_distance_sqr) {
324 min_distance_sqr = distance_sqr;
325 closest_point = nearest_on_edge;
326 }
327 distance_sqr = segmentSqrDistance(P3, P1, center, nearest_on_edge);
328 if (distance_sqr < min_distance_sqr) {
329 min_distance_sqr = distance_sqr;
330 closest_point = nearest_on_edge;
331 }
332 }
333
334 normal = (closest_point - center).normalized();
335 p1 = center + normal * (s.radius + s.getSweptSphereRadius());
336 p2 = closest_point - normal * tri.getSweptSphereRadius();
337 const Scalar distance = std::sqrt(min_distance_sqr) - radius;
338 return distance;
339}
340
345inline Scalar halfspaceDistance(const Halfspace& h, const Transform3s& tf1,
346 const ShapeBase& s, const Transform3s& tf2,
347 Vec3s& p1, Vec3s& p2, Vec3s& normal) {
348 // TODO(louis): handle multiple contact points when the halfspace normal is
349 // parallel to the shape's surface (every primitive except sphere and
350 // ellipsoid).
351
352 // Express halfspace in world frame
353 Halfspace new_h = transform(h, tf1);
354
355 // Express halfspace normal in shape frame
356 Vec3s n_2(tf2.getRotation().transpose() * new_h.n);
357
358 // Compute support of shape in direction of halfspace normal
359 int hint = 0;
360 p2.noalias() =
361 getSupport<details::SupportOptions::WithSweptSphere>(&s, -n_2, hint);
362 p2 = tf2.transform(p2);
363
364 const Scalar dist = new_h.signedDistance(p2);
365 p1.noalias() = p2 - dist * new_h.n;
366 normal.noalias() = new_h.n;
367
368 const Scalar dummy_precision =
369 std::sqrt(Eigen::NumTraits<Scalar>::dummy_precision());
370 COAL_UNUSED_VARIABLE(dummy_precision);
371 assert(new_h.distance(p1) <= dummy_precision);
372 return dist;
373}
374
379inline Scalar planeDistance(const Plane& plane, const Transform3s& tf1,
380 const ShapeBase& s, const Transform3s& tf2,
381 Vec3s& p1, Vec3s& p2, Vec3s& normal) {
382 // TODO(louis): handle multiple contact points when the plane normal is
383 // parallel to the shape's surface (every primitive except sphere and
384 // ellipsoid).
385
386 // Express plane as two halfspaces in world frame
387 std::array<Halfspace, 2> new_h = transformToHalfspaces(plane, tf1);
388
389 // Express halfspace normals in shape frame
390 Vec3s n_h1(tf2.getRotation().transpose() * new_h[0].n);
391 Vec3s n_h2(tf2.getRotation().transpose() * new_h[1].n);
392
393 // Compute support of shape in direction of halfspace normal and its opposite
394 int hint = 0;
395 Vec3s p2h1 =
396 getSupport<details::SupportOptions::WithSweptSphere>(&s, -n_h1, hint);
397 p2h1 = tf2.transform(p2h1);
398
399 hint = 0;
400 Vec3s p2h2 =
401 getSupport<details::SupportOptions::WithSweptSphere>(&s, -n_h2, hint);
402 p2h2 = tf2.transform(p2h2);
403
404 Scalar dist1 = new_h[0].signedDistance(p2h1);
405 Scalar dist2 = new_h[1].signedDistance(p2h2);
406
407 const Scalar dummy_precision =
408 std::sqrt(Eigen::NumTraits<Scalar>::dummy_precision());
409 COAL_UNUSED_VARIABLE(dummy_precision);
410
411 Scalar dist;
412 if (dist1 >= dist2) {
413 dist = dist1;
414 p2.noalias() = p2h1;
415 p1.noalias() = p2 - dist * new_h[0].n;
416 normal.noalias() = new_h[0].n;
417 assert(new_h[0].distance(p1) <= dummy_precision);
418 } else {
419 dist = dist2;
420 p2.noalias() = p2h2;
421 p1.noalias() = p2 - dist * new_h[1].n;
422 normal.noalias() = new_h[1].n;
423 assert(new_h[1].distance(p1) <= dummy_precision);
424 }
425 return dist;
426}
427
433inline Scalar boxSphereDistance(const Box& b, const Transform3s& tfb,
434 const Sphere& s, const Transform3s& tfs,
435 Vec3s& pb, Vec3s& ps, Vec3s& normal) {
436 const Vec3s& os = tfs.getTranslation();
437 const Vec3s& ob = tfb.getTranslation();
438 const Matrix3s& Rb = tfb.getRotation();
439
440 pb = ob;
441
442 bool outside = false;
443 const Vec3s os_in_b_frame(Rb.transpose() * (os - ob));
444 int axis = -1;
445 Scalar min_d = (std::numeric_limits<Scalar>::max)();
446 for (int i = 0; i < 3; ++i) {
447 Scalar facedist;
448 if (os_in_b_frame(i) < -b.halfSide(i)) { // outside
449 pb.noalias() -= b.halfSide(i) * Rb.col(i);
450 outside = true;
451 } else if (os_in_b_frame(i) > b.halfSide(i)) { // outside
452 pb.noalias() += b.halfSide(i) * Rb.col(i);
453 outside = true;
454 } else {
455 pb.noalias() += os_in_b_frame(i) * Rb.col(i);
456 if (!outside &&
457 (facedist = b.halfSide(i) - std::fabs(os_in_b_frame(i))) < min_d) {
458 axis = i;
459 min_d = facedist;
460 }
461 }
462 }
463 normal = pb - os;
464 Scalar pdist = normal.norm();
465 Scalar dist; // distance between sphere and box
466 if (outside) { // pb is on the box
467 dist = pdist - s.radius;
468 normal /= -pdist;
469 } else { // pb is inside the box
470 if (os_in_b_frame(axis) >= 0) {
471 normal = Rb.col(axis);
472 } else {
473 normal = -Rb.col(axis);
474 }
475 dist = -min_d - s.radius;
476 }
477 ps = os - s.radius * normal;
478 if (!outside || dist <= 0) {
479 // project point pb onto the box's surface
480 pb = ps - dist * normal;
481 }
482
483 // Take swept-sphere radius into account
484 const Scalar ssrb = b.getSweptSphereRadius();
485 const Scalar ssrs = s.getSweptSphereRadius();
486 if (ssrb > 0 || ssrs > 0) {
487 pb += ssrb * normal;
488 ps -= ssrs * normal;
489 dist -= (ssrb + ssrs);
490 }
491
492 return dist;
493}
494
508 const Transform3s& tf1,
509 const Halfspace& s2,
510 const Transform3s& tf2, Vec3s& p1,
511 Vec3s& p2, Vec3s& normal) {
512 Halfspace new_s1 = transform(s1, tf1);
513 Halfspace new_s2 = transform(s2, tf2);
514
516 Vec3s dir = (new_s1.n).cross(new_s2.n);
517 Scalar dir_sq_norm = dir.squaredNorm();
518
519 if (dir_sq_norm < std::numeric_limits<Scalar>::epsilon()) // parallel
520 {
521 if (new_s1.n.dot(new_s2.n) > 0) {
522 // If the two halfspaces have the same normal, one is inside the other
523 // and they can't be separated. They have inifinte penetration depth.
524 distance = -(std::numeric_limits<Scalar>::max)();
525 if (new_s1.d <= new_s2.d) {
526 normal = new_s1.n;
527 p1 = normal * distance;
528 p2 = new_s2.n * new_s2.d;
529 assert(new_s2.distance(p2) <=
530 Eigen::NumTraits<Scalar>::dummy_precision());
531 } else {
532 normal = -new_s1.n;
533 p1 << new_s1.n * new_s1.d;
534 p2 = -(normal * distance);
535 assert(new_s1.distance(p1) <=
536 Eigen::NumTraits<Scalar>::dummy_precision());
537 }
538 } else {
539 distance = -(new_s1.d + new_s2.d);
540 normal = new_s1.n;
541 p1 = new_s1.n * new_s1.d;
542 p2 = new_s2.n * new_s2.d;
543 }
544 } else {
545 // If the halfspaces are not parallel, they are in collision.
546 // Their distance, in the sens of the norm of separation vector, is infinite
547 // (it's impossible to find a translation which separates them)
548 distance = -(std::numeric_limits<Scalar>::max)();
549 // p1 and p2 are the same point, corresponding to a point on the
550 // intersection line between the two objects. Normal is the direction of
551 // that line.
552 normal = dir;
553 p1 = p2 =
554 ((new_s2.n * new_s1.d - new_s1.n * new_s2.d).cross(dir)) / dir_sq_norm;
555 // Sources: https://en.wikipedia.org/wiki/Plane%E2%80%93plane_intersection
556 // and https://en.wikipedia.org/wiki/Cross_product
557 }
558
559 // Take swept-sphere radius into account
560 const Scalar ssr1 = s1.getSweptSphereRadius();
561 const Scalar ssr2 = s2.getSweptSphereRadius();
562 if (ssr1 > 0 || ssr2 > 0) {
563 p1 += ssr1 * normal;
564 p2 -= ssr2 * normal;
565 distance -= (ssr1 + ssr2);
566 }
567
568 return distance;
569}
570
584 const Transform3s& tf1, const Plane& s2,
585 const Transform3s& tf2, Vec3s& p1,
586 Vec3s& p2, Vec3s& normal) {
587 Halfspace new_s1 = transform(s1, tf1);
588 Plane new_s2 = transform(s2, tf2);
589
591 Vec3s dir = (new_s1.n).cross(new_s2.n);
592 Scalar dir_sq_norm = dir.squaredNorm();
593
594 if (dir_sq_norm < std::numeric_limits<Scalar>::epsilon()) // parallel
595 {
596 normal = new_s1.n;
597 distance = new_s1.n.dot(new_s2.n) > 0 ? (new_s2.d - new_s1.d)
598 : -(new_s1.d + new_s2.d);
599 p1 = new_s1.n * new_s1.d;
600 p2 = new_s2.n * new_s2.d;
601 assert(new_s1.distance(p1) <= Eigen::NumTraits<Scalar>::dummy_precision());
602 assert(new_s2.distance(p2) <= Eigen::NumTraits<Scalar>::dummy_precision());
603 } else {
604 // If the halfspace and plane are not parallel, they are in collision.
605 // Their distance, in the sens of the norm of separation vector, is infinite
606 // (it's impossible to find a translation which separates them)
607 distance = -(std::numeric_limits<Scalar>::max)();
608 // p1 and p2 are the same point, corresponding to a point on the
609 // intersection line between the two objects. Normal is the direction of
610 // that line.
611 normal = dir;
612 p1 = p2 =
613 ((new_s2.n * new_s1.d - new_s1.n * new_s2.d).cross(dir)) / dir_sq_norm;
614 // Sources: https://en.wikipedia.org/wiki/Plane%E2%80%93plane_intersection
615 // and https://en.wikipedia.org/wiki/Cross_product
616 }
617
618 // Take swept-sphere radius into account
619 const Scalar ssr1 = s1.getSweptSphereRadius();
620 const Scalar ssr2 = s2.getSweptSphereRadius();
621 if (ssr1 > 0 || ssr2 > 0) {
622 p1 += ssr1 * normal;
623 p2 -= ssr2 * normal;
624 distance -= (ssr1 + ssr2);
625 }
626
627 return distance;
628}
629
642inline Scalar planePlaneDistance(const Plane& s1, const Transform3s& tf1,
643 const Plane& s2, const Transform3s& tf2,
644 Vec3s& p1, Vec3s& p2, Vec3s& normal) {
645 Plane new_s1 = transform(s1, tf1);
646 Plane new_s2 = transform(s2, tf2);
647
649 Vec3s dir = (new_s1.n).cross(new_s2.n);
650 Scalar dir_sq_norm = dir.squaredNorm();
651
652 if (dir_sq_norm < std::numeric_limits<Scalar>::epsilon()) // parallel
653 {
654 p1 = new_s1.n * new_s1.d;
655 p2 = new_s2.n * new_s2.d;
656 assert(new_s1.distance(p1) <= Eigen::NumTraits<Scalar>::dummy_precision());
657 assert(new_s2.distance(p2) <= Eigen::NumTraits<Scalar>::dummy_precision());
658 distance = (p1 - p2).norm();
659
660 if (distance > Eigen::NumTraits<Scalar>::dummy_precision()) {
661 normal = (p2 - p1).normalized();
662 } else {
663 normal = new_s1.n;
664 }
665 } else {
666 // If the planes are not parallel, they are in collision.
667 // Their distance, in the sens of the norm of separation vector, is infinite
668 // (it's impossible to find a translation which separates them)
669 distance = -(std::numeric_limits<Scalar>::max)();
670 // p1 and p2 are the same point, corresponding to a point on the
671 // intersection line between the two objects. Normal is the direction of
672 // that line.
673 normal = dir;
674 p1 = p2 =
675 ((new_s2.n * new_s1.d - new_s1.n * new_s2.d).cross(dir)) / dir_sq_norm;
676 // Sources: https://en.wikipedia.org/wiki/Plane%E2%80%93plane_intersection
677 // and https://en.wikipedia.org/wiki/Cross_product
678 }
679
680 // Take swept-sphere radius into account
681 const Scalar ssr1 = s1.getSweptSphereRadius();
682 const Scalar ssr2 = s2.getSweptSphereRadius();
683 if (ssr1 > 0 || ssr2 > 0) {
684 p1 += ssr1 * normal;
685 p2 -= ssr2 * normal;
686 distance -= (ssr1 + ssr2);
687 }
688
689 return distance;
690}
691
693inline Scalar computePenetration(const Vec3s& P1, const Vec3s& P2,
694 const Vec3s& P3, const Vec3s& Q1,
695 const Vec3s& Q2, const Vec3s& Q3,
696 Vec3s& normal) {
697 Vec3s u((P2 - P1).cross(P3 - P1));
698 normal = u.normalized();
699 Scalar depth1((P1 - Q1).dot(normal));
700 Scalar depth2((P1 - Q2).dot(normal));
701 Scalar depth3((P1 - Q3).dot(normal));
702 return std::max(depth1, std::max(depth2, depth3));
703}
704
705// Compute penetration distance and normal of two triangles in collision
706// Normal is normal of triangle 1 (P1, P2, P3), penetration depth is the
707// minimal distance (Q1, Q2, Q3) should be translated along the normal so
708// that the triangles are collision free.
709//
710// Note that we compute here an upper bound of the penetration distance,
711// not the exact value.
712inline Scalar computePenetration(const Vec3s& P1, const Vec3s& P2,
713 const Vec3s& P3, const Vec3s& Q1,
714 const Vec3s& Q2, const Vec3s& Q3,
715 const Transform3s& tf1, const Transform3s& tf2,
716 Vec3s& normal) {
717 Vec3s globalP1(tf1.transform(P1));
718 Vec3s globalP2(tf1.transform(P2));
719 Vec3s globalP3(tf1.transform(P3));
720 Vec3s globalQ1(tf2.transform(Q1));
721 Vec3s globalQ2(tf2.transform(Q2));
722 Vec3s globalQ3(tf2.transform(Q3));
723 return computePenetration(globalP1, globalP2, globalP3, globalQ1, globalQ2,
724 globalQ3, normal);
725}
726
727} // namespace details
728} // namespace coal
729
730#endif // COAL_SRC_NARROWPHASE_DETAILS_H
Center at zero point, axis aligned box.
Definition geometric_shapes.h:164
Vec3s halfSide
box side half-length
Definition geometric_shapes.h:187
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition geometric_shapes.h:381
Scalar halfLength
Half Length along z axis.
Definition geometric_shapes.h:400
Scalar radius
Radius of capsule.
Definition geometric_shapes.h:397
Cylinder along Z axis. The cylinder is defined at its centroid.
Definition geometric_shapes.h:556
Scalar radius
Radius of the cylinder.
Definition geometric_shapes.h:580
Scalar halfLength
Half Length along z axis.
Definition geometric_shapes.h:583
Half Space: this is equivalent to the Plane in ODE. A Half space has a priviledged direction: the dir...
Definition geometric_shapes.h:963
Vec3s n
Plane normal.
Definition geometric_shapes.h:1027
Scalar d
Plane offset.
Definition geometric_shapes.h:1030
Scalar distance(const Vec3s &p) const
Definition geometric_shapes.h:995
Scalar signedDistance(const Vec3s &p) const
Definition geometric_shapes.h:991
Infinite plane. A plane can be viewed as two half spaces; it has no priviledged direction....
Definition geometric_shapes.h:1054
Scalar distance(const Vec3s &p) const
Definition geometric_shapes.h:1093
Vec3s n
Plane normal.
Definition geometric_shapes.h:1104
Scalar d
Plane offset.
Definition geometric_shapes.h:1107
Base class for all basic geometric shapes.
Definition geometric_shapes.h:58
Scalar getSweptSphereRadius() const
Get radius of sphere swept around the shape. This radius is always >= 0.
Definition geometric_shapes.h:86
Center at zero point sphere.
Definition geometric_shapes.h:238
Scalar radius
Radius of the sphere.
Definition geometric_shapes.h:251
Simple transform class used locally by InterpMotion.
Definition transform.h:55
Vec3s transform(const Eigen::MatrixBase< Derived > &v) const
transform a given vector by the transform
Definition transform.h:152
const Matrix3s & getRotation() const
get rotation
Definition transform.h:110
const Vec3s & getTranslation() const
get translation
Definition transform.h:101
Triangle stores the points instead of only indices of points.
Definition geometric_shapes.h:108
Vec3s a
Definition geometric_shapes.h:147
Vec3s b
Definition geometric_shapes.h:147
Vec3s c
Definition geometric_shapes.h:147
#define COAL_UNUSED_VARIABLE(var)
Definition fwd.hh:56
Scalar segmentSqrDistance(const Vec3s &from, const Vec3s &to, const Vec3s &p, Vec3s &nearest)
the minimum distance from a point to a line
Definition details.h:233
Scalar planePlaneDistance(const Plane &s1, const Transform3s &tf1, const Plane &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
return distance between two planes
Definition details.h:642
Scalar halfspacePlaneDistance(const Halfspace &s1, const Transform3s &tf1, const Plane &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
return distance between plane and halfspace.
Definition details.h:583
Scalar halfspaceHalfspaceDistance(const Halfspace &s1, const Transform3s &tf1, const Halfspace &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
return distance between two halfspaces
Definition details.h:507
Scalar planeDistance(const Plane &plane, const Transform3s &tf1, const ShapeBase &s, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
Definition details.h:379
Scalar halfspaceDistance(const Halfspace &h, const Transform3s &tf1, const ShapeBase &s, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
Definition details.h:345
Scalar sphereCylinderDistance(const Sphere &s1, const Transform3s &tf1, const Cylinder &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
Definition details.h:106
Scalar sphereCapsuleDistance(const Sphere &s1, const Transform3s &tf1, const Capsule &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
Definition details.h:75
Scalar sphereSphereDistance(const Sphere &s1, const Transform3s &tf1, const Sphere &s2, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
Definition details.h:213
Scalar computePenetration(const Vec3s &P1, const Vec3s &P2, const Vec3s &P3, const Vec3s &Q1, const Vec3s &Q2, const Vec3s &Q3, Vec3s &normal)
See the prototype below.
Definition details.h:693
Scalar sphereTriangleDistance(const Sphere &s, const Transform3s &tf1, const TriangleP &tri, const Transform3s &tf2, Vec3s &p1, Vec3s &p2, Vec3s &normal)
Definition details.h:284
Scalar boxSphereDistance(const Box &b, const Transform3s &tfb, const Sphere &s, const Transform3s &tfs, Vec3s &pb, Vec3s &ps, Vec3s &normal)
Definition details.h:433
bool projectInTriangle(const Vec3s &p1, const Vec3s &p2, const Vec3s &p3, const Vec3s &normal, const Vec3s &p)
Whether a point's projection is in a triangle.
Definition details.h:256
Main namespace.
Definition broadphase_bruteforce.h:44
std::array< Halfspace, 2 > transformToHalfspaces(const Plane &a, const Transform3s &tf)
Halfspace transform(const Halfspace &a, const Transform3s &tf)
Scalar distance(const Matrix3s &R0, const Vec3s &T0, const kIOS &b1, const kIOS &b2, Vec3s *P=NULL, Vec3s *Q=NULL)
Approximate distance between two kIOS bounding volumes.
Eigen::Matrix< Scalar, 3, 1 > Vec3s
Definition data_types.h:70
double Scalar
Definition data_types.h:68
Eigen::Matrix< Scalar, 3, 3 > Matrix3s
Definition data_types.h:74