gjk_solver_indep-inl.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-2016, 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 
38 #ifndef FCL_NARROWPHASE_GJKSOLVERINDEP_INL_H
39 #define FCL_NARROWPHASE_GJKSOLVERINDEP_INL_H
40 
42 
43 #include <algorithm>
44 
45 #include "fcl/common/unused.h"
46 
48 
61 
62 namespace fcl
63 {
64 
65 namespace detail
66 {
67 
68 //==============================================================================
69 extern template
70 struct GJKSolver_indep<double>;
71 
72 //==============================================================================
73 template <typename S>
74 template<typename Shape1, typename Shape2>
75 bool GJKSolver_indep<S>::shapeIntersect(const Shape1& s1, const Transform3<S>& tf1,
76  const Shape2& s2, const Transform3<S>& tf2,
77  Vector3<S>* contact_points, S* penetration_depth, Vector3<S>* normal) const
78 {
79  bool res;
80 
81  if (contact_points || penetration_depth || normal)
82  {
83  std::vector<ContactPoint<S>> contacts;
84 
85  res = shapeIntersect(s1, tf1, s2, tf2, &contacts);
86 
87  if (!contacts.empty())
88  {
89  // Get the deepest contact point
90  const ContactPoint<S>& maxDepthContact = *std::max_element(contacts.begin(), contacts.end(), comparePenDepth<S>);
91 
92  if (contact_points)
93  *contact_points = maxDepthContact.pos;
94 
95  if (penetration_depth)
96  *penetration_depth = maxDepthContact.penetration_depth;
97 
98  if (normal)
99  *normal = maxDepthContact.normal;
100  }
101  }
102  else
103  {
104  res = shapeIntersect(s1, tf1, s2, tf2, nullptr);
105  }
106 
107  return res;
108 }
109 
110 //==============================================================================
111 template<typename S, typename Shape1, typename Shape2>
113 {
114  static bool run(
115  const GJKSolver_indep<S>& gjkSolver,
116  const Shape1& s1,
117  const Transform3<S>& tf1,
118  const Shape2& s2,
119  const Transform3<S>& tf2,
120  std::vector<ContactPoint<S>>* contacts)
121  {
122  Vector3<S> guess(1, 0, 0);
123  if(gjkSolver.enable_cached_guess) guess = gjkSolver.cached_guess;
124 
126  shape.shapes[0] = &s1;
127  shape.shapes[1] = &s2;
128  shape.toshape1.noalias() = tf2.linear().transpose() * tf1.linear();
129  shape.toshape0 = tf1.inverse(Eigen::Isometry) * tf2;
130 
131  detail::GJK<S> gjk(gjkSolver.gjk_max_iterations, gjkSolver.gjk_tolerance);
132  typename detail::GJK<S>::Status gjk_status = gjk.evaluate(shape, -guess);
133  if(gjkSolver.enable_cached_guess) gjkSolver.cached_guess = gjk.getGuessFromSimplex();
134 
135  switch(gjk_status)
136  {
138  {
139  detail::EPA<S> epa(gjkSolver.epa_max_face_num, gjkSolver.epa_max_vertex_num, gjkSolver.epa_max_iterations, gjkSolver.epa_tolerance);
140  typename detail::EPA<S>::Status epa_status = epa.evaluate(gjk, -guess);
141  if(epa_status != detail::EPA<S>::Failed)
142  {
144  for(size_t i = 0; i < epa.result.rank; ++i)
145  {
146  w0.noalias() += shape.support(epa.result.c[i]->d, 0) * epa.result.p[i];
147  }
148  if(contacts)
149  {
150  Vector3<S> normal = epa.normal;
151  Vector3<S> point = tf1 * (w0 - epa.normal*(epa.depth *0.5));
152  S depth = -epa.depth;
153  contacts->emplace_back(normal, point, depth);
154  }
155  return true;
156  }
157  else return false;
158  }
159  break;
160  default:
161  ;
162  }
163 
164  return false;
165  }
166 };
167 
168 //==============================================================================
169 template<typename S>
170 template<typename Shape1, typename Shape2>
172  const Shape1& s1,
173  const Transform3<S>& tf1,
174  const Shape2& s2,
175  const Transform3<S>& tf2,
176  std::vector<ContactPoint<S>>* contacts) const
177 {
179  *this, s1, tf1, s2, tf2, contacts);
180 }
181 
182 // Shape intersect algorithms not using built-in GJK algorithm
183 //
184 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
185 // | | box | sphere | ellipsoid | capsule | cone | cylinder | plane | half-space | triangle | convex |
186 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
187 // | box | O | O | | | | | O | O | | |
188 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
189 // | sphere |/////| O | | O | | O | O | O | O | |
190 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
191 // | ellipsoid |/////|////////| | | | | O | O | | |
192 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
193 // | capsule |/////|////////|///////////| | | | O | O | | |
194 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
195 // | cone |/////|////////|///////////|/////////| | | O | O | | |
196 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
197 // | cylinder |/////|////////|///////////|/////////|//////| | O | O | | |
198 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
199 // | plane |/////|////////|///////////|/////////|//////|//////////| O | O | O | |
200 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
201 // | half-space |/////|////////|///////////|/////////|//////|//////////|///////| O | O | O |
202 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
203 // | triangle |/////|////////|///////////|/////////|//////|//////////|///////|////////////| | |
204 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
205 // | convex |/////|////////|///////////|/////////|//////|//////////|///////|////////////|//////////| |
206 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+----------+
207 
208 #define FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_REG(SHAPE1, SHAPE2, ALG)\
209  template <typename S>\
210  struct ShapeIntersectIndepImpl<S, SHAPE1<S>, SHAPE2<S>>\
211  {\
212  static bool run(\
213  const GJKSolver_indep<S>& /*gjkSolver*/,\
214  const SHAPE1<S>& s1,\
215  const Transform3<S>& tf1,\
216  const SHAPE2<S>& s2,\
217  const Transform3<S>& tf2,\
218  std::vector<ContactPoint<S>>* contacts)\
219  {\
220  return ALG(s1, tf1, s2, tf2, contacts);\
221  }\
222  };
223 
224 #define FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_INV(SHAPE1, SHAPE2, ALG)\
225  template <typename S>\
226  struct ShapeIntersectIndepImpl<S, SHAPE2<S>, SHAPE1<S>>\
227  {\
228  static bool run(\
229  const GJKSolver_indep<S>& /*gjkSolver*/,\
230  const SHAPE2<S>& s1,\
231  const Transform3<S>& tf1,\
232  const SHAPE1<S>& s2,\
233  const Transform3<S>& tf2,\
234  std::vector<ContactPoint<S>>* contacts)\
235  {\
236  const bool res = ALG(s2, tf2, s1, tf1, contacts);\
237  if (contacts) flipNormal(*contacts);\
238  return res;\
239  }\
240  };
241 
242 #define FCL_GJK_INDEP_SHAPE_INTERSECT(SHAPE, ALG)\
243  FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_REG(SHAPE, SHAPE, ALG)
244 
245 #define FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT(SHAPE1, SHAPE2, ALG)\
246  FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_REG(SHAPE1, SHAPE2, ALG)\
247  FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT_INV(SHAPE1, SHAPE2, ALG)
248 
251 
253 
255 
257 
265 
272 
273 template <typename S>
275 {
276  static bool run(
277  const GJKSolver_indep<S>& /*gjkSolver*/,
278  const Halfspace<S>& s1,
279  const Transform3<S>& tf1,
280  const Halfspace<S>& s2,
281  const Transform3<S>& tf2,
282  std::vector<ContactPoint<S>>* contacts)
283  {
284  FCL_UNUSED(contacts);
285 
286  Halfspace<S> s;
287  Vector3<S> p, d;
288  S depth;
289  int ret;
290  return detail::halfspaceIntersect(s1, tf1, s2, tf2, p, d, s, depth, ret);
291  }
292 };
293 
294 template <typename S>
296 {
297  static bool run(
298  const GJKSolver_indep<S>& /*gjkSolver*/,
299  const Plane<S>& s1,
300  const Transform3<S>& tf1,
301  const Plane<S>& s2,
302  const Transform3<S>& tf2,
303  std::vector<ContactPoint<S>>* contacts)
304  {
305  return detail::planeIntersect(s1, tf1, s2, tf2, contacts);
306  }
307 };
308 
309 template <typename S>
311 {
312  static bool run(
313  const GJKSolver_indep<S>& /*gjkSolver*/,
314  const Plane<S>& s1,
315  const Transform3<S>& tf1,
316  const Halfspace<S>& s2,
317  const Transform3<S>& tf2,
318  std::vector<ContactPoint<S>>* contacts)
319  {
320  FCL_UNUSED(contacts);
321 
322  Plane<S> pl;
323  Vector3<S> p, d;
324  S depth;
325  int ret;
326  return detail::planeHalfspaceIntersect(s1, tf1, s2, tf2, pl, p, d, depth, ret);
327  }
328 };
329 
330 template <typename S>
332 {
333  static bool run(
334  const GJKSolver_indep<S>& /*gjkSolver*/,
335  const Halfspace<S>& s1,
336  const Transform3<S>& tf1,
337  const Plane<S>& s2,
338  const Transform3<S>& tf2,
339  std::vector<ContactPoint<S>>* contacts)
340  {
341  FCL_UNUSED(contacts);
342 
343  Plane<S> pl;
344  Vector3<S> p, d;
345  S depth;
346  int ret;
347  return detail::halfspacePlaneIntersect(s1, tf1, s2, tf2, pl, p, d, depth, ret);
348  }
349 };
350 
351 //==============================================================================
352 template<typename S, typename Shape>
354 {
355  static bool run(
356  const GJKSolver_indep<S>& gjkSolver,
357  const Shape& s,
358  const Transform3<S>& tf,
359  const Vector3<S>& P1,
360  const Vector3<S>& P2,
361  const Vector3<S>& P3,
362  Vector3<S>* contact_points,
363  S* penetration_depth,
364  Vector3<S>* normal)
365  {
366  TriangleP<S> tri(P1, P2, P3);
367 
368  Vector3<S> guess(1, 0, 0);
369  if(gjkSolver.enable_cached_guess) guess = gjkSolver.cached_guess;
370 
372  shape.shapes[0] = &s;
373  shape.shapes[1] = &tri;
374  shape.toshape1 = tf.linear();
375  shape.toshape0 = tf.inverse(Eigen::Isometry);
376 
377  detail::GJK<S> gjk(gjkSolver.gjk_max_iterations, gjkSolver.gjk_tolerance);
378  typename detail::GJK<S>::Status gjk_status = gjk.evaluate(shape, -guess);
379  if(gjkSolver.enable_cached_guess) gjkSolver.cached_guess = gjk.getGuessFromSimplex();
380 
381  switch(gjk_status)
382  {
384  {
385  detail::EPA<S> epa(gjkSolver.epa_max_face_num, gjkSolver.epa_max_vertex_num, gjkSolver.epa_max_iterations, gjkSolver.epa_tolerance);
386  typename detail::EPA<S>::Status epa_status = epa.evaluate(gjk, -guess);
387  if(epa_status != detail::EPA<S>::Failed)
388  {
390  for(size_t i = 0; i < epa.result.rank; ++i)
391  {
392  w0.noalias() += shape.support(epa.result.c[i]->d, 0) * epa.result.p[i];
393  }
394  if(penetration_depth) *penetration_depth = -epa.depth;
395  if(normal) *normal = -epa.normal;
396  if(contact_points) (*contact_points).noalias() = tf * (w0 - epa.normal*(epa.depth *0.5));
397  return true;
398  }
399  else return false;
400  }
401  break;
402  default:
403  ;
404  }
405 
406  return false;
407  }
408 };
409 
410 template<typename S>
411 template<typename Shape>
413  const Shape& s,
414  const Transform3<S>& tf,
415  const Vector3<S>& P1,
416  const Vector3<S>& P2,
417  const Vector3<S>& P3,
418  Vector3<S>* contact_points,
419  S* penetration_depth,
420  Vector3<S>* normal) const
421 {
423  *this, s, tf, P1, P2, P3, contact_points, penetration_depth, normal);
424 }
425 
426 //==============================================================================
427 template<typename S>
429 {
430  static bool run(
431  const GJKSolver_indep<S>& /*gjkSolver*/,
432  const Sphere<S>& s,
433  const Transform3<S>& tf,
434  const Vector3<S>& P1,
435  const Vector3<S>& P2,
436  const Vector3<S>& P3,
437  Vector3<S>* contact_points,
438  S* penetration_depth,
439  Vector3<S>* normal)
440  {
442  s, tf, P1, P2, P3, contact_points, penetration_depth, normal);
443  }
444 };
445 
446 
447 //==============================================================================
448 template<typename S, typename Shape>
450 {
451  static bool run(
452  const GJKSolver_indep<S>& gjkSolver,
453  const Shape& s,
454  const Transform3<S>& tf1,
455  const Vector3<S>& P1,
456  const Vector3<S>& P2,
457  const Vector3<S>& P3,
458  const Transform3<S>& tf2,
459  Vector3<S>* contact_points,
460  S* penetration_depth,
461  Vector3<S>* normal)
462  {
463  TriangleP<S> tri(P1, P2, P3);
464 
465  Vector3<S> guess(1, 0, 0);
466  if(gjkSolver.enable_cached_guess) guess = gjkSolver.cached_guess;
467 
469  shape.shapes[0] = &s;
470  shape.shapes[1] = &tri;
471  shape.toshape1.noalias() = tf2.linear().transpose() * tf1.linear();
472  shape.toshape0 = tf1.inverse(Eigen::Isometry) * tf2;
473 
474  detail::GJK<S> gjk(gjkSolver.gjk_max_iterations, gjkSolver.gjk_tolerance);
475  typename detail::GJK<S>::Status gjk_status = gjk.evaluate(shape, -guess);
476  if(gjkSolver.enable_cached_guess) gjkSolver.cached_guess = gjk.getGuessFromSimplex();
477 
478  switch(gjk_status)
479  {
481  {
482  detail::EPA<S> epa(gjkSolver.epa_max_face_num, gjkSolver.epa_max_vertex_num, gjkSolver.epa_max_iterations, gjkSolver.epa_tolerance);
483  typename detail::EPA<S>::Status epa_status = epa.evaluate(gjk, -guess);
484  if(epa_status != detail::EPA<S>::Failed)
485  {
487  for(size_t i = 0; i < epa.result.rank; ++i)
488  {
489  w0.noalias() += shape.support(epa.result.c[i]->d, 0) * epa.result.p[i];
490  }
491  if(penetration_depth) *penetration_depth = -epa.depth;
492  if(normal) *normal = -epa.normal;
493  if(contact_points) (*contact_points).noalias() = tf1 * (w0 - epa.normal*(epa.depth *0.5));
494  return true;
495  }
496  else return false;
497  }
498  break;
499  default:
500  ;
501  }
502 
503  return false;
504  }
505 };
506 
507 template<typename S>
508 template<typename Shape>
510  const Shape& s,
511  const Transform3<S>& tf1,
512  const Vector3<S>& P1,
513  const Vector3<S>& P2,
514  const Vector3<S>& P3,
515  const Transform3<S>& tf2,
516  Vector3<S>* contact_points,
517  S* penetration_depth,
518  Vector3<S>* normal) const
519 {
521  *this, s, tf1, P1, P2, P3, tf2,
522  contact_points, penetration_depth, normal);
523 }
524 
525 //==============================================================================
526 template<typename S>
528 {
529  static bool run(
530  const GJKSolver_indep<S>& /*gjkSolver*/,
531  const Sphere<S>& s,
532  const Transform3<S>& tf1,
533  const Vector3<S>& P1,
534  const Vector3<S>& P2,
535  const Vector3<S>& P3,
536  const Transform3<S>& tf2,
537  Vector3<S>* contact_points,
538  S* penetration_depth,
539  Vector3<S>* normal)
540  {
542  s, tf1, tf2 * P1, tf2 * P2, tf2 * P3,
543  contact_points, penetration_depth, normal);
544  }
545 };
546 
547 //==============================================================================
548 template<typename S>
550 {
551  static bool run(
552  const GJKSolver_indep<S>& /*gjkSolver*/,
553  const Halfspace<S>& s,
554  const Transform3<S>& tf1,
555  const Vector3<S>& P1,
556  const Vector3<S>& P2,
557  const Vector3<S>& P3,
558  const Transform3<S>& tf2,
559  Vector3<S>* contact_points,
560  S* penetration_depth,
561  Vector3<S>* normal)
562  {
564  s, tf1, P1, P2, P3, tf2,
565  contact_points, penetration_depth, normal);
566  }
567 };
568 
569 //==============================================================================
570 template<typename S>
572 {
573  static bool run(
574  const GJKSolver_indep<S>& /*gjkSolver*/,
575  const Plane<S>& s,
576  const Transform3<S>& tf1,
577  const Vector3<S>& P1,
578  const Vector3<S>& P2,
579  const Vector3<S>& P3,
580  const Transform3<S>& tf2,
581  Vector3<S>* contact_points,
582  S* penetration_depth,
583  Vector3<S>* normal)
584  {
586  s, tf1, P1, P2, P3, tf2,
587  contact_points, penetration_depth, normal);
588  }
589 };
590 
591 
592 //==============================================================================
593 template<typename S, typename Shape1, typename Shape2>
595 {
596  static bool run(
597  const GJKSolver_indep<S>& gjkSolver,
598  const Shape1& s1,
599  const Transform3<S>& tf1,
600  const Shape2& s2,
601  const Transform3<S>& tf2,
602  S* distance,
603  Vector3<S>* p1,
604  Vector3<S>* p2)
605  {
606  Vector3<S> guess(1, 0, 0);
607  if(gjkSolver.enable_cached_guess) guess = gjkSolver.cached_guess;
608 
610  shape.shapes[0] = &s1;
611  shape.shapes[1] = &s2;
612  shape.toshape1.noalias() = tf2.linear().transpose() * tf1.linear();
613  shape.toshape0 = tf1.inverse(Eigen::Isometry) * tf2;
614 
615  detail::GJK<S> gjk(gjkSolver.gjk_max_iterations, gjkSolver.gjk_tolerance);
616  typename detail::GJK<S>::Status gjk_status = gjk.evaluate(shape, -guess);
617  if(gjkSolver.enable_cached_guess) gjkSolver.cached_guess = gjk.getGuessFromSimplex();
618 
619  if(gjk_status == detail::GJK<S>::Valid)
620  {
623  for(size_t i = 0; i < gjk.getSimplex()->rank; ++i)
624  {
625  S p = gjk.getSimplex()->p[i];
626  w0.noalias() += shape.support(gjk.getSimplex()->c[i]->d, 0) * p;
627  w1.noalias() += shape.support(-gjk.getSimplex()->c[i]->d, 1) * p;
628  }
629 
630  if(distance) *distance = (w0 - w1).norm();
631 
632  // Answer is solved in Shape1's local frame; answers are given in the
633  // world frame.
634  if(p1) p1->noalias() = tf1 * w0;
635  if(p2) p2->noalias() = tf1 * w1;
636 
637  return true;
638  }
639  else
640  {
641  if(distance) *distance = -1;
642  return false;
643  }
644  }
645 };
646 
647 template<typename S>
648 template<typename Shape1, typename Shape2>
650  const Shape1& s1,
651  const Transform3<S>& tf1,
652  const Shape2& s2,
653  const Transform3<S>& tf2,
654  S* dist,
655  Vector3<S>* p1,
656  Vector3<S>* p2) const
657 {
659  *this, s1, tf1, s2, tf2, dist, p1, p2);
660 }
661 
662 
663 //==============================================================================
664 template<typename S>
665 template<typename Shape1, typename Shape2>
667  const Shape1& s1,
668  const Transform3<S>& tf1,
669  const Shape2& s2,
670  const Transform3<S>& tf2,
671  S* dist,
672  Vector3<S>* p1,
673  Vector3<S>* p2) const
674 {
675  // TODO: should implement the signed distance version
676  bool result = false;
677  try {
679  *this, s1, tf1, s2, tf2, dist, p1, p2);
680  } catch (const FailedAtThisConfiguration& e) {
681  ThrowDetailedConfiguration(s1, tf1, s2, tf2, *this, e);
682  }
683  return result;
684 }
685 
686 // Shape distance algorithms not using built-in GJK algorithm
687 //
688 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
689 // | | box | sphere | ellipsoid | capsule | cone | cylinder | plane | half-space | triangle |
690 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
691 // | box | | O | | | | | | | |
692 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
693 // | sphere |/////| O | | O | | O | | | O |
694 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
695 // | ellipsoid |/////|////////| | | | | | | |
696 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
697 // | capsule |/////|////////|///////////| O | | | | | |
698 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
699 // | cone |/////|////////|///////////|/////////| | | | | |
700 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
701 // | cylinder |/////|////////|///////////|/////////|//////| | | | |
702 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
703 // | plane |/////|////////|///////////|/////////|//////|//////////| | | |
704 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
705 // | half-space |/////|////////|///////////|/////////|//////|//////////|///////| | |
706 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
707 // | triangle |/////|////////|///////////|/////////|//////|//////////|///////|////////////| |
708 // +------------+-----+--------+-----------+---------+------+----------+-------+------------+----------+
709 
710 //==============================================================================
711 template<typename S>
713 {
714  static bool run(
715  const GJKSolver_indep<S>& /*gjkSolver*/,
716  const Sphere<S>& s1,
717  const Transform3<S>& tf1,
718  const Box<S>& s2,
719  const Transform3<S>& tf2,
720  S* dist,
721  Vector3<S>* p1,
722  Vector3<S>* p2)
723  {
724  return detail::sphereBoxDistance(s1, tf1, s2, tf2, dist, p1, p2);
725  }
726 };
727 
728 //==============================================================================
729 template<typename S>
731 {
732  static bool run(
733  const GJKSolver_indep<S>& /*gjkSolver*/,
734  const Box<S>& s1,
735  const Transform3<S>& tf1,
736  const Sphere<S>& s2,
737  const Transform3<S>& tf2,
738  S* dist,
739  Vector3<S>* p1,
740  Vector3<S>* p2)
741  {
742  return detail::sphereBoxDistance(s2, tf2, s1, tf1, dist, p2, p1);
743  }
744 };
745 
746 //==============================================================================
747 template<typename S>
749 {
750  static bool run(
751  const GJKSolver_indep<S>& /*gjkSolver*/,
752  const Sphere<S>& s1,
753  const Transform3<S>& tf1,
754  const Capsule<S>& s2,
755  const Transform3<S>& tf2,
756  S* dist,
757  Vector3<S>* p1,
758  Vector3<S>* p2)
759  {
760  return detail::sphereCapsuleDistance(s1, tf1, s2, tf2, dist, p1, p2);
761  }
762 };
763 
764 //==============================================================================
765 template<typename S>
767 {
768  static bool run(
769  const GJKSolver_indep<S>& /*gjkSolver*/,
770  const Capsule<S>& s1,
771  const Transform3<S>& tf1,
772  const Sphere<S>& s2,
773  const Transform3<S>& tf2,
774  S* dist,
775  Vector3<S>* p1,
776  Vector3<S>* p2)
777  {
778  return detail::sphereCapsuleDistance(s2, tf2, s1, tf1, dist, p2, p1);
779  }
780 };
781 
782 //==============================================================================
783 template<typename S>
785 {
786  static bool run(
787  const GJKSolver_indep<S>& /*gjkSolver*/,
788  const Sphere<S>& s1,
789  const Transform3<S>& tf1,
790  const Cylinder<S>& s2,
791  const Transform3<S>& tf2,
792  S* dist,
793  Vector3<S>* p1,
794  Vector3<S>* p2)
795  {
796  return detail::sphereCylinderDistance(s1, tf1, s2, tf2, dist, p1, p2);
797  }
798 };
799 
800 //==============================================================================
801 template<typename S>
803 {
804  static bool run(
805  const GJKSolver_indep<S>& /*gjkSolver*/,
806  const Cylinder<S>& s1,
807  const Transform3<S>& tf1,
808  const Sphere<S>& s2,
809  const Transform3<S>& tf2,
810  S* dist,
811  Vector3<S>* p1,
812  Vector3<S>* p2)
813  {
814  return detail::sphereCylinderDistance(s2, tf2, s1, tf1, dist, p2, p1);
815  }
816 };
817 
818 //==============================================================================
819 template<typename S>
821 {
822  static bool run(
823  const GJKSolver_indep<S>& /*gjkSolver*/,
824  const Sphere<S>& s1,
825  const Transform3<S>& tf1,
826  const Sphere<S>& s2,
827  const Transform3<S>& tf2,
828  S* dist,
829  Vector3<S>* p1,
830  Vector3<S>* p2)
831  {
832  return detail::sphereSphereDistance(s1, tf1, s2, tf2, dist, p1, p2);
833  }
834 };
835 
836 //==============================================================================
837 template<typename S>
839 {
840  static bool run(
841  const GJKSolver_indep<S>& /*gjkSolver*/,
842  const Capsule<S>& s1,
843  const Transform3<S>& tf1,
844  const Capsule<S>& s2,
845  const Transform3<S>& tf2,
846  S* dist,
847  Vector3<S>* p1,
848  Vector3<S>* p2)
849  {
850  return detail::capsuleCapsuleDistance(s1, tf1, s2, tf2, dist, p1, p2);
851  }
852 };
853 
854 //==============================================================================
855 template<typename S, typename Shape>
857 {
858  static bool run(
859  const GJKSolver_indep<S>& gjkSolver,
860  const Shape& s,
861  const Transform3<S>& tf,
862  const Vector3<S>& P1,
863  const Vector3<S>& P2,
864  const Vector3<S>& P3,
865  S* distance,
866  Vector3<S>* p1,
867  Vector3<S>* p2)
868  {
869  TriangleP<S> tri(P1, P2, P3);
870  Vector3<S> guess(1, 0, 0);
871  if(gjkSolver.enable_cached_guess) guess = gjkSolver.cached_guess;
872 
874  shape.shapes[0] = &s;
875  shape.shapes[1] = &tri;
876  shape.toshape1 = tf.linear();
877  shape.toshape0 = tf.inverse(Eigen::Isometry);
878 
879  detail::GJK<S> gjk(gjkSolver.gjk_max_iterations, gjkSolver.gjk_tolerance);
880  typename detail::GJK<S>::Status gjk_status = gjk.evaluate(shape, -guess);
881  if(gjkSolver.enable_cached_guess) gjkSolver.cached_guess = gjk.getGuessFromSimplex();
882 
883  if(gjk_status == detail::GJK<S>::Valid)
884  {
887  for(size_t i = 0; i < gjk.getSimplex()->rank; ++i)
888  {
889  S p = gjk.getSimplex()->p[i];
890  w0.noalias() += shape.support(gjk.getSimplex()->c[i]->d, 0) * p;
891  w1.noalias() += shape.support(-gjk.getSimplex()->c[i]->d, 1) * p;
892  }
893 
894  if(distance) *distance = (w0 - w1).norm();
895  // The answers are produced in world coordinates. Keep them there.
896  if(p1) *p1 = w0;
897  if(p2) *p2 = w1;
898  return true;
899  }
900  else
901  {
902  if(distance) *distance = -1;
903  return false;
904  }
905  }
906 };
907 
908 //==============================================================================
909 template<typename S>
910 template<typename Shape>
912  const Shape& s,
913  const Transform3<S>& tf,
914  const Vector3<S>& P1,
915  const Vector3<S>& P2,
916  const Vector3<S>& P3,
917  S* dist,
918  Vector3<S>* p1,
919  Vector3<S>* p2) const
920 {
922  *this, s, tf, P1, P2, P3, dist, p1, p2);
923 }
924 
925 //==============================================================================
926 template<typename S>
928 {
929  static bool run(
930  const GJKSolver_indep<S>& /*gjkSolver*/,
931  const Sphere<S>& s,
932  const Transform3<S>& tf,
933  const Vector3<S>& P1,
934  const Vector3<S>& P2,
935  const Vector3<S>& P3,
936  S* dist,
937  Vector3<S>* p1,
938  Vector3<S>* p2)
939  {
940  return detail::sphereTriangleDistance(s, tf, P1, P2, P3, dist, p1, p2);
941  }
942 };
943 
944 //==============================================================================
945 template<typename S, typename Shape>
947 {
948  static bool run(
949  const GJKSolver_indep<S>& gjkSolver,
950  const Shape& s,
951  const Transform3<S>& tf1,
952  const Vector3<S>& P1,
953  const Vector3<S>& P2,
954  const Vector3<S>& P3,
955  const Transform3<S>& tf2,
956  S* distance,
957  Vector3<S>* p1,
958  Vector3<S>* p2)
959  {
960  TriangleP<S> tri(P1, P2, P3);
961  Vector3<S> guess(1, 0, 0);
962  if(gjkSolver.enable_cached_guess) guess = gjkSolver.cached_guess;
963 
965  shape.shapes[0] = &s;
966  shape.shapes[1] = &tri;
967  shape.toshape1.noalias() = tf2.linear().transpose() * tf1.linear();
968  shape.toshape0 = tf1.inverse(Eigen::Isometry) * tf2;
969 
970  detail::GJK<S> gjk(gjkSolver.gjk_max_iterations, gjkSolver.gjk_tolerance);
971  typename detail::GJK<S>::Status gjk_status = gjk.evaluate(shape, -guess);
972  if(gjkSolver.enable_cached_guess) gjkSolver.cached_guess = gjk.getGuessFromSimplex();
973 
974  if(gjk_status == detail::GJK<S>::Valid)
975  {
978  for(size_t i = 0; i < gjk.getSimplex()->rank; ++i)
979  {
980  S p = gjk.getSimplex()->p[i];
981  w0.noalias() += shape.support(gjk.getSimplex()->c[i]->d, 0) * p;
982  w1.noalias() += shape.support(-gjk.getSimplex()->c[i]->d, 1) * p;
983  }
984 
985  if(distance) *distance = (w0 - w1).norm();
986  if(p1) p1->noalias() = tf1 * w0;
987  if(p2) p2->noalias() = tf1 * w1;
988  return true;
989  }
990  else
991  {
992  if(distance) *distance = -1;
993  return false;
994  }
995  }
996 };
997 
998 //==============================================================================
999 template<typename S>
1000 template<typename Shape>
1002  const Shape& s,
1003  const Transform3<S>& tf1,
1004  const Vector3<S>& P1,
1005  const Vector3<S>& P2,
1006  const Vector3<S>& P3,
1007  const Transform3<S>& tf2,
1008  S* dist,
1009  Vector3<S>* p1,
1010  Vector3<S>* p2) const
1011 {
1013  *this, s, tf1, P1, P2, P3, tf2, dist, p1, p2);
1014 }
1015 
1016 //==============================================================================
1017 template<typename S>
1019 {
1020  static bool run(
1021  const GJKSolver_indep<S>& /*gjkSolver*/,
1022  const Sphere<S>& s,
1023  const Transform3<S>& tf1,
1024  const Vector3<S>& P1,
1025  const Vector3<S>& P2,
1026  const Vector3<S>& P3,
1027  const Transform3<S>& tf2,
1028  S* dist,
1029  Vector3<S>* p1,
1030  Vector3<S>* p2)
1031  {
1033  s, tf1, P1, P2, P3, tf2, dist, p1, p2);
1034  }
1035 };
1036 
1037 //==============================================================================
1038 template <typename S>
1040 {
1041  gjk_max_iterations = 128;
1042  gjk_tolerance = constants<S>::gjk_default_tolerance();
1043  epa_max_face_num = 128;
1044  epa_max_vertex_num = 64;
1045  epa_max_iterations = 255;
1046  epa_tolerance = constants<S>::gjk_default_tolerance();
1047  enable_cached_guess = false;
1048  cached_guess = Vector3<S>(1, 0, 0);
1049 }
1050 
1051 //==============================================================================
1052 template <typename S>
1053 void GJKSolver_indep<S>::enableCachedGuess(bool if_enable) const
1054 {
1055  enable_cached_guess = if_enable;
1056 }
1057 
1058 //==============================================================================
1059 template <typename S>
1061 {
1062  cached_guess = guess;
1063 }
1064 
1065 //==============================================================================
1066 template <typename S>
1068 {
1069  return cached_guess;
1070 }
1071 
1072 } // namespace detail
1073 } // namespace fcl
1074 
1075 #endif
fcl::detail::sphereCapsuleIntersect
template bool sphereCapsuleIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::halfspaceTriangleIntersect
template bool halfspaceTriangleIntersect(const Halfspace< double > &s1, const Transform3< double > &tf1, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal)
fcl::detail::ShapeDistanceIndepImpl< S, Capsule< S >, Capsule< S > >::run
static bool run(const GJKSolver_indep< S > &, const Capsule< S > &s1, const Transform3< S > &tf1, const Capsule< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:840
fcl::detail::sphereBoxDistance
template FCL_EXPORT bool sphereBoxDistance(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Box< double > &box, const Transform3< double > &X_FB, double *distance, Vector3< double > *p_FSb, Vector3< double > *p_FBs)
fcl::detail::GJKSolver_indep::S
S_ S
Definition: gjk_solver_indep.h:56
fcl::Transform3
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
fcl::detail::GJKSolver_indep::enableCachedGuess
void enableCachedGuess(bool if_enable) const
Definition: gjk_solver_indep-inl.h:1053
triangle_p.h
fcl::detail::GJK::getSimplex
Simplex * getSimplex() const
get the underlying simplex using in GJK, can be used for cache in next iteration
Definition: gjk-inl.h:302
fcl::detail::MinkowskiDiff::toshape1
Matrix3< S > toshape1
rotation from shape0 to shape1
Definition: minkowski_diff.h:64
fcl::detail::capsulePlaneIntersect
template bool capsulePlaneIntersect(const Capsule< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2)
fcl::ContactPoint
Minimal contact information returned by collision.
Definition: contact_point.h:48
fcl::detail::ShapeTriangleIntersectIndepImpl< S, Sphere< S > >::run
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal)
Definition: gjk_solver_indep-inl.h:430
fcl::detail::MinkowskiDiff::shapes
const ShapeBase< S > * shapes[2]
points to two shapes
Definition: minkowski_diff.h:61
gjk.h
fcl::detail::EPA
class for EPA algorithm
Definition: epa.h:57
fcl::detail::ShapeDistanceIndepImpl< S, Sphere< S >, Capsule< S > >::run
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s1, const Transform3< S > &tf1, const Capsule< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:750
fcl::detail::cylinderHalfspaceIntersect
template bool cylinderHalfspaceIntersect(const Cylinder< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::GJKSolver_indep::shapeDistance
bool shapeDistance(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *distance=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between two shapes
Definition: gjk_solver_indep-inl.h:649
fcl::ContactPoint::normal
Vector3< S > normal
Contact normal, pointing from o1 to o2.
Definition: contact_point.h:51
fcl::detail::sphereHalfspaceIntersect
template bool sphereHalfspaceIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::planeTriangleIntersect
template bool planeTriangleIntersect(const Plane< double > &s1, const Transform3< double > &tf1, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal)
fcl::detail::ShapeDistanceIndepImpl
Definition: gjk_solver_indep-inl.h:594
fcl::detail::planeHalfspaceIntersect
template bool planeHalfspaceIntersect(const Plane< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Plane< double > &pl, Vector3< double > &p, Vector3< double > &d, double &penetration_depth, int &ret)
fcl::detail::capsuleHalfspaceIntersect
template bool capsuleHalfspaceIntersect(const Capsule< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::boxBoxIntersect
template bool boxBoxIntersect(const Box< double > &s1, const Transform3< double > &tf1, const Box< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts_)
fcl::detail::ShapeTransformedTriangleDistanceIndepImpl::run
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape &s, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, S *distance, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:948
fcl::detail::ShapeTriangleDistanceIndepImpl::run
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *distance, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:858
FCL_GJK_INDEP_SHAPE_INTERSECT
#define FCL_GJK_INDEP_SHAPE_INTERSECT(SHAPE, ALG)
Definition: gjk_solver_indep-inl.h:242
fcl::detail::ShapeDistanceIndepImpl< S, Sphere< S >, Cylinder< S > >::run
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s1, const Transform3< S > &tf1, const Cylinder< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:786
unused.h
fcl::detail::GJKSolver_indep::epa_tolerance
S epa_tolerance
the threshold used in EPA to stop iteration
Definition: gjk_solver_indep.h:171
fcl::detail::ShapeTransformedTriangleIntersectIndepImpl< S, Halfspace< S > >::run
static bool run(const GJKSolver_indep< S > &, const Halfspace< S > &s, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal)
Definition: gjk_solver_indep-inl.h:551
fcl::detail::ShapeDistanceIndepImpl< S, Capsule< S >, Sphere< S > >::run
static bool run(const GJKSolver_indep< S > &, const Capsule< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:768
fcl::detail::ShapeIntersectIndepImpl< S, Plane< S >, Plane< S > >::run
static bool run(const GJKSolver_indep< S > &, const Plane< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
Definition: gjk_solver_indep-inl.h:297
fcl::ContactPoint::penetration_depth
S penetration_depth
Penetration depth.
Definition: contact_point.h:57
fcl::detail::sphereSphereIntersect
template FCL_EXPORT bool sphereSphereIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Sphere< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::ShapeTransformedTriangleIntersectIndepImpl< S, Sphere< S > >::run
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal)
Definition: gjk_solver_indep-inl.h:529
fcl::detail::MinkowskiDiff::toshape0
Transform3< S > toshape0
transform from shape1 to shape0
Definition: minkowski_diff.h:67
fcl::detail::GJKSolver_indep::shapeTriangleIntersect
bool shapeTriangleIntersect(const Shape &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, Vector3< S > *contact_points=nullptr, S *penetration_depth=nullptr, Vector3< S > *normal=nullptr) const
intersection checking between one shape and a triangle
Definition: gjk_solver_indep-inl.h:412
fcl::detail::MinkowskiDiff::support
Vector3< S > support(const Vector3< S > &d) const
support function for the pair of shapes
Definition: minkowski_diff-inl.h:231
failed_at_this_configuration.h
fcl::detail::GJK::evaluate
Status evaluate(const MinkowskiDiff< S > &shape_, const Vector3< S > &guess)
GJK algorithm, given the initial value guess.
Definition: gjk-inl.h:82
fcl::detail::planeIntersect
template bool planeIntersect(const Plane< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::ShapeTransformedTriangleIntersectIndepImpl::run
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape &s, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal)
Definition: gjk_solver_indep-inl.h:451
fcl::detail::ShapeIntersectIndepImpl< S, Halfspace< S >, Plane< S > >::run
static bool run(const GJKSolver_indep< S > &, const Halfspace< S > &s1, const Transform3< S > &tf1, const Plane< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
Definition: gjk_solver_indep-inl.h:333
fcl::detail::EPA::normal
Vector3< S > normal
Definition: epa.h:107
fcl::detail::sphereTriangleIntersect
template bool sphereTriangleIntersect(const Sphere< double > &s, const Transform3< double > &tf, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal_)
fcl::Vector3
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
fcl::detail::GJKSolver_indep::setCachedGuess
void setCachedGuess(const Vector3< S > &guess) const
Definition: gjk_solver_indep-inl.h:1060
fcl::detail::convexHalfspaceIntersect
template bool convexHalfspaceIntersect(const Convex< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Vector3< double > *contact_points, double *penetration_depth, Vector3< double > *normal)
fcl::detail::GJKSolver_indep::epa_max_vertex_num
unsigned int epa_max_vertex_num
maximum number of simplex vertex used in EPA algorithm
Definition: gjk_solver_indep.h:165
fcl::detail::ShapeIntersectIndepImpl< S, Halfspace< S >, Halfspace< S > >::run
static bool run(const GJKSolver_indep< S > &, const Halfspace< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
Definition: gjk_solver_indep-inl.h:276
halfspace.h
fcl::detail::coneHalfspaceIntersect
template bool coneHalfspaceIntersect(const Cone< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::spherePlaneIntersect
template bool spherePlaneIntersect(const Sphere< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::GJKSolver_indep::shapeSignedDistance
bool shapeSignedDistance(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *distance=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between two shapes
Definition: gjk_solver_indep-inl.h:666
fcl::detail::ShapeDistanceIndepImpl< S, Sphere< S >, Sphere< S > >::run
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:822
fcl::detail::sphereTriangleDistance
template bool sphereTriangleDistance(const Sphere< double > &sp, const Transform3< double > &tf, const Vector3< double > &P1, const Vector3< double > &P2, const Vector3< double > &P3, double *dist)
fcl::detail::ellipsoidPlaneIntersect
template bool ellipsoidPlaneIntersect(const Ellipsoid< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::boxPlaneIntersect
template bool boxPlaneIntersect(const Box< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::ContactPoint::pos
Vector3< S > pos
Contact position, in world space.
Definition: contact_point.h:54
fcl::detail::GJKSolver_indep::gjk_tolerance
S gjk_tolerance
the threshold used in GJK to stop iteration
Definition: gjk_solver_indep.h:174
fcl::detail::conePlaneIntersect
template bool conePlaneIntersect(const Cone< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::GJKSolver_indep::GJKSolver_indep
GJKSolver_indep()
default setting for GJK algorithm
Definition: gjk_solver_indep-inl.h:1039
fcl::detail::ShapeIntersectIndepImpl
Definition: gjk_solver_indep-inl.h:112
fcl::detail::GJKSolver_indep
collision and distance solver based on GJK algorithm implemented in fcl (rewritten the code from the ...
Definition: gjk_solver_indep.h:54
fcl::TriangleP
Triangle stores the points instead of only indices of points.
Definition: triangle_p.h:50
fcl::detail::halfspaceIntersect
template bool halfspaceIntersect(const Halfspace< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, Vector3< double > &p, Vector3< double > &d, Halfspace< double > &s, double &penetration_depth, int &ret)
fcl::detail::ShapeTriangleIntersectIndepImpl
Definition: gjk_solver_indep-inl.h:353
fcl::detail::sphereSphereDistance
template FCL_EXPORT bool sphereSphereDistance(const Sphere< double > &s1, const Transform3< double > &tf1, const Sphere< double > &s2, const Transform3< double > &tf2, double *dist, Vector3< double > *p1, Vector3< double > *p2)
fcl::detail::sphereBoxIntersect
template FCL_EXPORT bool sphereBoxIntersect(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Box< double > &box, const Transform3< double > &X_FB, std::vector< ContactPoint< double >> *contacts)
fcl::Halfspace
Half Space: this is equivalent to the Planed in ODE. The separation plane is defined as n * x = d....
Definition: geometry/shape/halfspace.h:60
fcl::detail::GJK::getGuessFromSimplex
Vector3< S > getGuessFromSimplex() const
get the guess from current simplex
Definition: gjk-inl.h:75
fcl::detail::halfspacePlaneIntersect
template bool halfspacePlaneIntersect(const Halfspace< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2, Plane< double > &pl, Vector3< double > &p, Vector3< double > &d, double &penetration_depth, int &ret)
sphere_capsule.h
fcl::detail::ShapeDistanceIndepImpl< S, Sphere< S >, Box< S > >::run
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s1, const Transform3< S > &tf1, const Box< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:714
fcl::detail::distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
fcl::time::point
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition: time.h:52
fcl::Cylinder
Center at zero cylinder.
Definition: cylinder.h:51
fcl::constants::gjk_default_tolerance
static Real gjk_default_tolerance()
Definition: constants.h:145
fcl::detail::boxHalfspaceIntersect
template bool boxHalfspaceIntersect(const Box< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2)
fcl::detail::capsuleCapsuleDistance
template bool capsuleCapsuleDistance(const Capsule< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, double *dist, Vector3d *p1_res, Vector3d *p2_res)
fcl::detail::ShapeDistanceIndepImpl< S, Box< S >, Sphere< S > >::run
static bool run(const GJKSolver_indep< S > &, const Box< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:732
fcl::detail::EPA::evaluate
Status evaluate(GJK< S > &gjk, const Vector3< S > &guess)
Definition: epa-inl.h:225
fcl::Box
Center at zero point, axis aligned box.
Definition: box.h:51
fcl::detail::GJKSolver_indep::getCachedGuess
Vector3< S > getCachedGuess() const
Definition: gjk_solver_indep-inl.h:1067
FCL_UNUSED
#define FCL_UNUSED(x)
Definition: unused.h:39
fcl::detail::ShapeTriangleDistanceIndepImpl< S, Sphere< S > >::run
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:929
gjk_solver_indep.h
fcl::Sphere
Center at zero point sphere.
Definition: sphere.h:51
fcl::detail::GJKSolver_indep::enable_cached_guess
bool enable_cached_guess
Whether smart guess can be provided.
Definition: gjk_solver_indep.h:180
fcl::detail::ShapeTransformedTriangleDistanceIndepImpl
Definition: gjk_solver_indep-inl.h:946
fcl::detail::GJKSolver_indep::gjk_max_iterations
S gjk_max_iterations
maximum number of iterations used for GJK iterations
Definition: gjk_solver_indep.h:177
fcl::detail::sphereCylinderDistance
template FCL_EXPORT bool sphereCylinderDistance(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Cylinder< double > &cylinder, const Transform3< double > &X_FC, double *distance, Vector3< double > *p_FSc, Vector3< double > *p_FCs)
fcl::detail::GJK
class for GJK algorithm
Definition: gjk.h:52
fcl::detail::ShapeTriangleDistanceIndepImpl
Definition: gjk_solver_indep-inl.h:856
fcl::detail::GJKSolver_indep::shapeIntersect
FCL_DEPRECATED bool shapeIntersect(const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal) const
intersection checking between two shapes
FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT
#define FCL_GJK_INDEP_SHAPE_SHAPE_INTERSECT(SHAPE1, SHAPE2, ALG)
Definition: gjk_solver_indep-inl.h:245
fcl::detail::GJK::Status
Status
Definition: gjk.h:74
fcl::detail::ThrowDetailedConfiguration
void ThrowDetailedConfiguration(const Shape1 &s1, const Transform3< S > &X_FS1, const Shape2 &s2, const Transform3< S > &X_FS2, const Solver &solver, const std::exception &e)
Definition: failed_at_this_configuration.h:142
fcl::detail::EPA::Status
Status
Definition: epa.h:103
box_box.h
fcl::detail::ShapeDistanceIndepImpl::run
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, S *distance, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:596
sphere_box.h
fcl::detail::ShapeDistanceIndepImpl< S, Cylinder< S >, Sphere< S > >::run
static bool run(const GJKSolver_indep< S > &, const Cylinder< S > &s1, const Transform3< S > &tf1, const Sphere< S > &s2, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:804
fcl::detail::ShapeTransformedTriangleIntersectIndepImpl
Definition: gjk_solver_indep-inl.h:449
fcl::detail::ShapeTransformedTriangleIntersectIndepImpl< S, Plane< S > >::run
static bool run(const GJKSolver_indep< S > &, const Plane< S > &s, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal)
Definition: gjk_solver_indep-inl.h:573
fcl::detail::sphereCylinderIntersect
template FCL_EXPORT bool sphereCylinderIntersect(const Sphere< double > &sphere, const Transform3< double > &X_FS, const Cylinder< double > &cylinder, const Transform3< double > &X_FC, std::vector< ContactPoint< double >> *contacts)
fcl::Plane
Infinite plane.
Definition: geometry/shape/plane.h:51
fcl::detail::sphereCapsuleDistance
template bool sphereCapsuleDistance(const Sphere< double > &s1, const Transform3< double > &tf1, const Capsule< double > &s2, const Transform3< double > &tf2, double *dist, Vector3< double > *p1, Vector3< double > *p2)
fcl::detail::GJKSolver_indep::cached_guess
Vector3< S > cached_guess
smart guess
Definition: gjk_solver_indep.h:183
fcl::detail::GJKSolver_indep::shapeTriangleDistance
bool shapeTriangleDistance(const Shape &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, S *distance=nullptr, Vector3< S > *p1=nullptr, Vector3< S > *p2=nullptr) const
distance computation between one shape and a triangle
Definition: gjk_solver_indep-inl.h:911
fcl::detail::GJKSolver_indep::epa_max_face_num
unsigned int epa_max_face_num
maximum number of simplex face used in EPA algorithm
Definition: gjk_solver_indep.h:162
fcl::detail::cylinderPlaneIntersect
template bool cylinderPlaneIntersect(const Cylinder< double > &s1, const Transform3< double > &tf1, const Plane< double > &s2, const Transform3< double > &tf2)
fcl::detail::ShapeTransformedTriangleDistanceIndepImpl< S, Sphere< S > >::run
static bool run(const GJKSolver_indep< S > &, const Sphere< S > &s, const Transform3< S > &tf1, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, const Transform3< S > &tf2, S *dist, Vector3< S > *p1, Vector3< S > *p2)
Definition: gjk_solver_indep-inl.h:1020
fcl::detail::EPA::result
GJK< S >::Simplex result
Definition: epa.h:106
fcl::detail::EPA::depth
S depth
Definition: epa.h:108
fcl::detail::GJKSolver_indep::epa_max_iterations
unsigned int epa_max_iterations
maximum number of iterations used for EPA iterations
Definition: gjk_solver_indep.h:168
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45
fcl::detail::MinkowskiDiff
Minkowski difference class of two shapes.
Definition: minkowski_diff.h:58
fcl::detail::ellipsoidHalfspaceIntersect
template bool ellipsoidHalfspaceIntersect(const Ellipsoid< double > &s1, const Transform3< double > &tf1, const Halfspace< double > &s2, const Transform3< double > &tf2, std::vector< ContactPoint< double >> *contacts)
fcl::detail::ShapeIntersectIndepImpl::run
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape1 &s1, const Transform3< S > &tf1, const Shape2 &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
Definition: gjk_solver_indep-inl.h:114
fcl::detail::FailedAtThisConfiguration
Definition: failed_at_this_configuration.h:65
fcl::Capsule
Center at zero point capsule.
Definition: capsule.h:51
fcl::detail::ShapeTriangleIntersectIndepImpl::run
static bool run(const GJKSolver_indep< S > &gjkSolver, const Shape &s, const Transform3< S > &tf, const Vector3< S > &P1, const Vector3< S > &P2, const Vector3< S > &P3, Vector3< S > *contact_points, S *penetration_depth, Vector3< S > *normal)
Definition: gjk_solver_indep-inl.h:355
sphere_triangle.h
fcl::detail::ShapeIntersectIndepImpl< S, Plane< S >, Halfspace< S > >::run
static bool run(const GJKSolver_indep< S > &, const Plane< S > &s1, const Transform3< S > &tf1, const Halfspace< S > &s2, const Transform3< S > &tf2, std::vector< ContactPoint< S >> *contacts)
Definition: gjk_solver_indep-inl.h:312
capsule_capsule.h
plane.h
sphere_cylinder.h
sphere_sphere.h
epa.h


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:48