mesh_distance_traversal_node-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_TRAVERSAL_MESHDISTANCETRAVERSALNODE_INL_H
39 #define FCL_TRAVERSAL_MESHDISTANCETRAVERSALNODE_INL_H
40 
42 
43 namespace fcl
44 {
45 
46 namespace detail
47 {
48 
49 //==============================================================================
50 extern template
52 
53 //==============================================================================
54 extern template
55 bool initialize(
56  MeshDistanceTraversalNodeRSS<double>& node,
57  const BVHModel<RSS<double>>& model1,
58  const Transform3<double>& tf1,
59  const BVHModel<RSS<double>>& model2,
60  const Transform3<double>& tf2,
61  const DistanceRequest<double>& request,
62  DistanceResult<double>& result);
63 
64 //==============================================================================
65 extern template
67 
68 //==============================================================================
69 extern template
70 bool initialize(
71  MeshDistanceTraversalNodekIOS<double>& node,
72  const BVHModel<kIOS<double>>& model1,
73  const Transform3<double>& tf1,
74  const BVHModel<kIOS<double>>& model2,
75  const Transform3<double>& tf2,
76  const DistanceRequest<double>& request,
77  DistanceResult<double>& result);
78 
79 //==============================================================================
80 extern template
82 
83 //==============================================================================
84 extern template
85 bool initialize(
86  MeshDistanceTraversalNodeOBBRSS<double>& node,
87  const BVHModel<OBBRSS<double>>& model1,
88  const Transform3<double>& tf1,
89  const BVHModel<OBBRSS<double>>& model2,
90  const Transform3<double>& tf2,
91  const DistanceRequest<double>& request,
92  DistanceResult<double>& result);
93 
94 //==============================================================================
95 template <typename BV>
97 {
98  vertices1 = nullptr;
99  vertices2 = nullptr;
100  tri_indices1 = nullptr;
101  tri_indices2 = nullptr;
102 
103  rel_err = this->request.rel_err;
104  abs_err = this->request.abs_err;
105 }
106 
107 //==============================================================================
108 template <typename BV>
110 {
111  if(this->enable_statistics) this->num_leaf_tests++;
112 
113  const BVNode<BV>& node1 = this->model1->getBV(b1);
114  const BVNode<BV>& node2 = this->model2->getBV(b2);
115 
116  int primitive_id1 = node1.primitiveId();
117  int primitive_id2 = node2.primitiveId();
118 
119  const Triangle& tri_id1 = tri_indices1[primitive_id1];
120  const Triangle& tri_id2 = tri_indices2[primitive_id2];
121 
122  const Vector3<S>& t11 = vertices1[tri_id1[0]];
123  const Vector3<S>& t12 = vertices1[tri_id1[1]];
124  const Vector3<S>& t13 = vertices1[tri_id1[2]];
125 
126  const Vector3<S>& t21 = vertices2[tri_id2[0]];
127  const Vector3<S>& t22 = vertices2[tri_id2[1]];
128  const Vector3<S>& t23 = vertices2[tri_id2[2]];
129 
130  // nearest point pair
131  Vector3<S> P1, P2;
132 
133  S d = TriangleDistance<S>::triDistance(t11, t12, t13, t21, t22, t23,
134  P1, P2);
135 
136  if(this->request.enable_nearest_points)
137  {
138  this->result->update(d, this->model1, this->model2, primitive_id1, primitive_id2, P1, P2);
139  }
140  else
141  {
142  this->result->update(d, this->model1, this->model2, primitive_id1, primitive_id2);
143  }
144 }
145 
146 //==============================================================================
147 template <typename BV>
148 bool MeshDistanceTraversalNode<BV>::canStop(typename BV::S c) const
149 {
150  if((c >= this->result->min_distance - abs_err) && (c * (1 + rel_err) >= this->result->min_distance))
151  return true;
152  return false;
153 }
154 
155 //==============================================================================
156 template <typename BV>
159  BVHModel<BV>& model1,
161  BVHModel<BV>& model2,
163  const DistanceRequest<typename BV::S>& request,
165  bool use_refit,
166  bool refit_bottomup)
167 {
168  using S = typename BV::S;
169 
171  return false;
172 
173  if(!tf1.matrix().isIdentity())
174  {
175  std::vector<Vector3<S>> vertices_transformed1(model1.num_vertices);
176  for(int i = 0; i < model1.num_vertices; ++i)
177  {
178  Vector3<S>& p = model1.vertices[i];
179  Vector3<S> new_v = tf1 * p;
180  vertices_transformed1[i] = new_v;
181  }
182 
183  model1.beginReplaceModel();
184  model1.replaceSubModel(vertices_transformed1);
185  model1.endReplaceModel(use_refit, refit_bottomup);
186 
187  tf1.setIdentity();
188  }
189 
190  if(!tf2.matrix().isIdentity())
191  {
192  std::vector<Vector3<S>> vertices_transformed2(model2.num_vertices);
193  for(int i = 0; i < model2.num_vertices; ++i)
194  {
195  Vector3<S>& p = model2.vertices[i];
196  Vector3<S> new_v = tf2 * p;
197  vertices_transformed2[i] = new_v;
198  }
199 
200  model2.beginReplaceModel();
201  model2.replaceSubModel(vertices_transformed2);
202  model2.endReplaceModel(use_refit, refit_bottomup);
203 
204  tf2.setIdentity();
205  }
206 
207  node.request = request;
208  node.result = &result;
209 
210  node.model1 = &model1;
211  node.tf1 = tf1;
212  node.model2 = &model2;
213  node.tf2 = tf2;
214 
215  node.vertices1 = model1.vertices;
216  node.vertices2 = model2.vertices;
217 
218  node.tri_indices1 = model1.tri_indices;
219  node.tri_indices2 = model2.tri_indices;
220 
221  return true;
222 }
223 
224 //==============================================================================
225 template <typename S>
228  tf(Transform3<S>::Identity())
229 {
230 }
231 
232 //==============================================================================
233 template <typename S>
235 {
237  this->model1,
238  this->model2,
239  this->vertices1,
240  this->vertices2,
241  this->tri_indices1,
242  this->tri_indices2,
243  0,
244  0,
245  tf,
246  this->request,
247  *this->result);
248 }
249 
250 //==============================================================================
251 template <typename S>
253 {
255  this->model1,
256  this->model2,
257  this->tf1,
258  this->request,
259  *this->result);
260 }
261 
262 //==============================================================================
263 template <typename S>
265 {
267  b1,
268  b2,
269  this->model1,
270  this->model2,
271  this->vertices1,
272  this->vertices2,
273  this->tri_indices1,
274  this->tri_indices2,
275  tf,
276  this->enable_statistics,
277  this->num_leaf_tests,
278  this->request,
279  *this->result);
280 }
281 
282 //==============================================================================
283 template <typename S>
286  tf(Transform3<S>::Identity())
287 {
288  // Do nothing
289 }
290 
291 //==============================================================================
292 template <typename S>
294 {
296  this->model1,
297  this->model2,
298  this->vertices1,
299  this->vertices2,
300  this->tri_indices1,
301  this->tri_indices2,
302  0,
303  0,
304  tf,
305  this->request,
306  *this->result);
307 }
308 
309 //==============================================================================
310 template <typename S>
312 {
314  this->model1,
315  this->model2,
316  this->tf1,
317  this->request,
318  *this->result);
319 }
320 
321 //==============================================================================
322 template <typename S>
324 {
326  b1,
327  b2,
328  this->model1,
329  this->model2,
330  this->vertices1,
331  this->vertices2,
332  this->tri_indices1,
333  this->tri_indices2,
334  tf,
335  this->enable_statistics,
336  this->num_leaf_tests,
337  this->request,
338  *this->result);
339 }
340 
341 //==============================================================================
342 template <typename S>
345  tf(Transform3<S>::Identity())
346 {
347  // Do nothing
348 }
349 
350 //==============================================================================
351 template <typename S>
353 {
355  this->model1,
356  this->model2,
357  this->vertices1,
358  this->vertices2,
359  this->tri_indices1,
360  this->tri_indices2,
361  0,
362  0,
363  tf,
364  this->request,
365  *this->result);
366 }
367 
368 //==============================================================================
369 template <typename S>
371 {
373  this->model1,
374  this->model2,
375  this->tf1,
376  this->request,
377  *this->result);
378 }
379 
380 //==============================================================================
381 template <typename S>
383 {
385  b1,
386  b2,
387  this->model1,
388  this->model2,
389  this->vertices1,
390  this->vertices2,
391  this->tri_indices1,
392  this->tri_indices2,
393  tf,
394  this->enable_statistics,
395  this->num_leaf_tests,
396  this->request,
397  *this->result);
398 }
399 
400 //==============================================================================
401 template <typename BV>
403  int b2,
404  const BVHModel<BV>* model1,
405  const BVHModel<BV>* model2,
410  const Matrix3<typename BV::S>& R,
411  const Vector3<typename BV::S>& T,
412  bool enable_statistics,
413  int& num_leaf_tests,
416 {
417  using S = typename BV::S;
418 
419  if(enable_statistics) num_leaf_tests++;
420 
421  const BVNode<BV>& node1 = model1->getBV(b1);
422  const BVNode<BV>& node2 = model2->getBV(b2);
423 
424  int primitive_id1 = node1.primitiveId();
425  int primitive_id2 = node2.primitiveId();
426 
427  const Triangle& tri_id1 = tri_indices1[primitive_id1];
428  const Triangle& tri_id2 = tri_indices2[primitive_id2];
429 
430  const Vector3<S>& t11 = vertices1[tri_id1[0]];
431  const Vector3<S>& t12 = vertices1[tri_id1[1]];
432  const Vector3<S>& t13 = vertices1[tri_id1[2]];
433 
434  const Vector3<S>& t21 = vertices2[tri_id2[0]];
435  const Vector3<S>& t22 = vertices2[tri_id2[1]];
436  const Vector3<S>& t23 = vertices2[tri_id2[2]];
437 
438  // nearest point pair
439  Vector3<S> P1, P2;
440 
441  S d = TriangleDistance<S>::triDistance(t11, t12, t13, t21, t22, t23,
442  R, T,
443  P1, P2);
444 
445  if(request.enable_nearest_points)
446  result.update(d, model1, model2, primitive_id1, primitive_id2, P1, P2);
447  else
448  result.update(d, model1, model2, primitive_id1, primitive_id2);
449 }
450 
451 //==============================================================================
452 template <typename BV>
454  int b1,
455  int b2,
456  const BVHModel<BV>* model1,
457  const BVHModel<BV>* model2,
463  bool enable_statistics,
464  int& num_leaf_tests,
467 {
468  using S = typename BV::S;
469 
470  if(enable_statistics) num_leaf_tests++;
471 
472  const BVNode<BV>& node1 = model1->getBV(b1);
473  const BVNode<BV>& node2 = model2->getBV(b2);
474 
475  int primitive_id1 = node1.primitiveId();
476  int primitive_id2 = node2.primitiveId();
477 
478  const Triangle& tri_id1 = tri_indices1[primitive_id1];
479  const Triangle& tri_id2 = tri_indices2[primitive_id2];
480 
481  const Vector3<S>& t11 = vertices1[tri_id1[0]];
482  const Vector3<S>& t12 = vertices1[tri_id1[1]];
483  const Vector3<S>& t13 = vertices1[tri_id1[2]];
484 
485  const Vector3<S>& t21 = vertices2[tri_id2[0]];
486  const Vector3<S>& t22 = vertices2[tri_id2[1]];
487  const Vector3<S>& t23 = vertices2[tri_id2[2]];
488 
489  // nearest point pair
490  Vector3<S> P1, P2;
491 
493  t11, t12, t13, t21, t22, t23, tf, P1, P2);
494 
495  if(request.enable_nearest_points)
496  result.update(d, model1, model2, primitive_id1, primitive_id2, P1, P2);
497  else
498  result.update(d, model1, model2, primitive_id1, primitive_id2);
499 }
500 
501 //==============================================================================
502 template <typename BV>
504  const BVHModel<BV>* model1,
505  const BVHModel<BV>* model2,
510  int init_tri_id1,
511  int init_tri_id2,
512  const Matrix3<typename BV::S>& R,
513  const Vector3<typename BV::S>& T,
516 {
517  using S = typename BV::S;
518 
519  const Triangle& init_tri1 = tri_indices1[init_tri_id1];
520  const Triangle& init_tri2 = tri_indices2[init_tri_id2];
521 
522  Vector3<S> init_tri1_points[3];
523  Vector3<S> init_tri2_points[3];
524 
525  init_tri1_points[0] = vertices1[init_tri1[0]];
526  init_tri1_points[1] = vertices1[init_tri1[1]];
527  init_tri1_points[2] = vertices1[init_tri1[2]];
528 
529  init_tri2_points[0] = vertices2[init_tri2[0]];
530  init_tri2_points[1] = vertices2[init_tri2[1]];
531  init_tri2_points[2] = vertices2[init_tri2[2]];
532 
533  Vector3<S> p1, p2;
534  S distance = TriangleDistance<S>::triDistance(init_tri1_points[0], init_tri1_points[1], init_tri1_points[2],
535  init_tri2_points[0], init_tri2_points[1], init_tri2_points[2],
536  R, T, p1, p2);
537 
538  if(request.enable_nearest_points)
539  result.update(distance, model1, model2, init_tri_id1, init_tri_id2, p1, p2);
540  else
541  result.update(distance, model1, model2, init_tri_id1, init_tri_id2);
542 }
543 
544 //==============================================================================
545 template <typename BV>
547  const BVHModel<BV>* model1,
548  const BVHModel<BV>* model2,
553  int init_tri_id1,
554  int init_tri_id2,
558 {
559  using S = typename BV::S;
560 
561  const Triangle& init_tri1 = tri_indices1[init_tri_id1];
562  const Triangle& init_tri2 = tri_indices2[init_tri_id2];
563 
564  Vector3<S> init_tri1_points[3];
565  Vector3<S> init_tri2_points[3];
566 
567  init_tri1_points[0] = vertices1[init_tri1[0]];
568  init_tri1_points[1] = vertices1[init_tri1[1]];
569  init_tri1_points[2] = vertices1[init_tri1[2]];
570 
571  init_tri2_points[0] = vertices2[init_tri2[0]];
572  init_tri2_points[1] = vertices2[init_tri2[1]];
573  init_tri2_points[2] = vertices2[init_tri2[2]];
574 
575  Vector3<S> p1, p2;
576  S distance
578  init_tri1_points[0], init_tri1_points[1], init_tri1_points[2],
579  init_tri2_points[0], init_tri2_points[1], init_tri2_points[2],
580  tf, p1, p2);
581 
582  if(request.enable_nearest_points)
583  result.update(distance, model1, model2, init_tri_id1, init_tri_id2, p1, p2);
584  else
585  result.update(distance, model1, model2, init_tri_id1, init_tri_id2);
586 }
587 
588 //==============================================================================
589 template <typename BV>
591  const BVHModel<BV>* model1,
592  const BVHModel<BV>* model2,
596 {
598  if(request.enable_nearest_points && (result.o1 == model1) && (result.o2 == model2))
599  {
600  result.nearest_points[0] = tf1 * result.nearest_points[0];
601  result.nearest_points[1] = tf1 * result.nearest_points[1];
602  }
603 }
604 
605 template <typename BV, typename OrientedNode>
607  OrientedNode& node,
612 {
614  return false;
615 
616  node.request = request;
617  node.result = &result;
618 
619  node.model1 = &model1;
620  node.tf1 = tf1;
621  node.model2 = &model2;
622  node.tf2 = tf2;
623 
624  node.vertices1 = model1.vertices;
625  node.vertices2 = model2.vertices;
626 
627  node.tri_indices1 = model1.tri_indices;
628  node.tri_indices2 = model2.tri_indices;
629 
630  node.tf = tf1.inverse(Eigen::Isometry) * tf2;
631 
632  return true;
633 }
634 
635 //==============================================================================
636 template <typename S>
639  const BVHModel<RSS<S>>& model1,
640  const Transform3<S>& tf1,
641  const BVHModel<RSS<S>>& model2,
642  const Transform3<S>& tf2,
645 {
647  node, model1, tf1, model2, tf2, request, result);
648 }
649 
650 //==============================================================================
651 template <typename S>
654  const BVHModel<kIOS<S>>& model1,
655  const Transform3<S>& tf1,
656  const BVHModel<kIOS<S>>& model2,
657  const Transform3<S>& tf2,
660 {
662  node, model1, tf1, model2, tf2, request, result);
663 }
664 
665 //==============================================================================
666 template <typename S>
669  const BVHModel<OBBRSS<S>>& model1,
670  const Transform3<S>& tf1,
671  const BVHModel<OBBRSS<S>>& model2,
672  const Transform3<S>& tf2,
675 {
677  node, model1, tf1, model2, tf2, request, result);
678 }
679 
680 } // namespace detail
681 } // namespace fcl
682 
683 #endif
const BVHModel< BV > * model1
The first BVH model.
Main namespace.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
template class FCL_EXPORT MeshDistanceTraversalNodekIOS< double >
template class FCL_EXPORT MeshDistanceTraversalNodeOBBRSS< double >
A class for rectangle swept sphere bounding volume.
Definition: RSS.h:58
template class FCL_EXPORT RSS< double >
Eigen::Transform< S, 3, Eigen::Isometry > Transform3
Definition: types.h:91
BVHModelType getModelType() const
Model type described by the instance.
Definition: BVH_model-inl.h:50
int beginReplaceModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
bool initialize(MeshDistanceTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result)
Initialize traversal node for distance computation between two meshes, specialized for OBBRSS type...
distance result
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Transform3< BV::S > tf2
configuration of second object
static bool setupMeshDistanceOrientedNode(OrientedNode &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
Eigen::Matrix< S, 3, 3 > Matrix3
Definition: types.h:85
int primitiveId() const
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices)...
const CollisionGeometry< S > * o2
collision object 2
Vector3< S > * vertices
Geometry point data.
Definition: BVH_model.h:162
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
int num_vertices
Number of points.
Definition: BVH_model.h:174
Traversal node for distance computation between BVH models.
Triangle * tri_indices
Geometry triangle index data, will be nullptr for point clouds.
Definition: BVH_model.h:165
Triangle with 3 indices for points.
Definition: triangle.h:48
void distancePreprocessOrientedNode(const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, int init_tri_id1, int init_tri_id2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
unknown model type
Definition: BVH_internal.h:78
void meshDistanceOrientedNodeLeafTesting(int b1, int b2, const BVHModel< BV > *model1, const BVHModel< BV > *model2, Vector3< typename BV::S > *vertices1, Vector3< typename BV::S > *vertices2, Triangle *tri_indices1, Triangle *tri_indices2, const Matrix3< typename BV::S > &R, const Vector3< typename BV::S > &T, bool enable_statistics, int &num_leaf_tests, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
bool enable_nearest_points
whether to return the nearest points
template bool initialize(MeshCollisionTraversalNodeOBB< double > &node, const BVHModel< OBB< double >> &model1, const Transform3< double > &tf1, const BVHModel< OBB< double >> &model2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result)
DistanceRequest< BV::S > request
request setting for distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
const CollisionGeometry< S > * o1
collision object 1
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
template class FCL_EXPORT kIOS< double >
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:57
const BVHModel< BV > * model2
The second BVH model.
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
DistanceResult< BV::S > * result
distance result kept during the traversal iteration
A class describing a bounding volume node. It includes the tree structure providing in BVNodeBase and...
Definition: BV_node.h:52
Triangle distance functions.
Transform3< BV::S > tf1
configuation of first object
void update(S distance, const CollisionGeometry< S > *o1_, const CollisionGeometry< S > *o2_, int b1_, int b2_)
add distance information into the result
template class FCL_EXPORT MeshDistanceTraversalNodeRSS< double >
template class FCL_EXPORT OBBRSS< double >
Vector3< S > nearest_points[2]
Nearest points in the world coordinates.
Traversal node for distance computation between two meshes if their underlying BVH node is oriented n...
void distancePostprocessOrientedNode(const BVHModel< BV > *model1, const BVHModel< BV > *model2, const Transform3< typename BV::S > &tf1, const DistanceRequest< typename BV::S > &request, DistanceResult< typename BV::S > &result)
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: OBBRSS.h:50
request to the distance computation
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
A class describing the kIOS collision structure, which is a set of spheres.
Definition: kIOS.h:48
Traversal node for distance computation between two meshes.
static S triDistance(const Vector3< S > T1[3], const Vector3< S > T2[3], Vector3< S > &P, Vector3< S > &Q)
Compute the closest points on two triangles given their absolute coordinate, and returns the distance...


fcl_catkin
Author(s):
autogenerated on Thu Mar 23 2023 03:00:18