mesh_collision_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_MESHCOLLISIONTRAVERSALNODE_INL_H
39 #define FCL_TRAVERSAL_MESHCOLLISIONTRAVERSALNODE_INL_H
40 
42 
43 #include "fcl/common/unused.h"
44 
46 
47 namespace fcl
48 {
49 
50 namespace detail
51 {
52 
53 //==============================================================================
54 extern template
56 
57 //==============================================================================
58 extern template
59 bool initialize(
60  MeshCollisionTraversalNodeOBB<double>& node,
61  const BVHModel<OBB<double>>& model1,
62  const Transform3<double>& tf1,
63  const BVHModel<OBB<double>>& model2,
64  const Transform3<double>& tf2,
65  const CollisionRequest<double>& request,
66  CollisionResult<double>& result);
67 
68 //==============================================================================
69 extern template
71 
72 //==============================================================================
73 extern template
74 bool initialize(
75  MeshCollisionTraversalNodeRSS<double>& node,
76  const BVHModel<RSS<double>>& model1,
77  const Transform3<double>& tf1,
78  const BVHModel<RSS<double>>& model2,
79  const Transform3<double>& tf2,
80  const CollisionRequest<double>& request,
81  CollisionResult<double>& result);
82 
83 //==============================================================================
84 extern template
86 
87 //==============================================================================
88 extern template
89 bool initialize(
90  MeshCollisionTraversalNodekIOS<double>& node,
91  const BVHModel<kIOS<double>>& model1,
92  const Transform3<double>& tf1,
93  const BVHModel<kIOS<double>>& model2,
94  const Transform3<double>& tf2,
95  const CollisionRequest<double>& request,
96  CollisionResult<double>& result);
97 
98 //==============================================================================
99 extern template
101 
102 //==============================================================================
103 extern template
104 bool initialize(
105  MeshCollisionTraversalNodeOBBRSS<double>& node,
106  const BVHModel<OBBRSS<double>>& model1,
107  const Transform3<double>& tf1,
108  const BVHModel<OBBRSS<double>>& model2,
109  const Transform3<double>& tf2,
110  const CollisionRequest<double>& request,
111  CollisionResult<double>& result);
112 
113 //==============================================================================
114 template <typename BV>
117 {
118  vertices1 = nullptr;
119  vertices2 = nullptr;
120  tri_indices1 = nullptr;
121  tri_indices2 = nullptr;
122 }
123 
124 //==============================================================================
125 template <typename BV>
127 {
128  if(this->enable_statistics) this->num_leaf_tests++;
129 
130  const BVNode<BV>& node1 = this->model1->getBV(b1);
131  const BVNode<BV>& node2 = this->model2->getBV(b2);
132 
133  int primitive_id1 = node1.primitiveId();
134  int primitive_id2 = node2.primitiveId();
135 
136  const Triangle& tri_id1 = tri_indices1[primitive_id1];
137  const Triangle& tri_id2 = tri_indices2[primitive_id2];
138 
139  const Vector3<S>& p1 = vertices1[tri_id1[0]];
140  const Vector3<S>& p2 = vertices1[tri_id1[1]];
141  const Vector3<S>& p3 = vertices1[tri_id1[2]];
142  const Vector3<S>& q1 = vertices2[tri_id2[0]];
143  const Vector3<S>& q2 = vertices2[tri_id2[1]];
144  const Vector3<S>& q3 = vertices2[tri_id2[2]];
145 
146  if(this->model1->isOccupied() && this->model2->isOccupied())
147  {
148  bool is_intersect = false;
149 
150  if(!this->request.enable_contact) // only interested in collision or not
151  {
152  if(Intersect<S>::intersect_Triangle(p1, p2, p3, q1, q2, q3))
153  {
154  is_intersect = true;
155  if(this->result->numContacts() < this->request.num_max_contacts)
156  this->result->addContact(Contact<S>(this->model1, this->model2, primitive_id1, primitive_id2));
157  }
158  }
159  else // need compute the contact information
160  {
161  S penetration;
162  Vector3<S> normal;
163  unsigned int n_contacts;
164  Vector3<S> contacts[2];
165 
166  if(Intersect<S>::intersect_Triangle(p1, p2, p3, q1, q2, q3,
167  contacts,
168  &n_contacts,
169  &penetration,
170  &normal))
171  {
172  is_intersect = true;
173 
174  if(this->request.num_max_contacts < n_contacts + this->result->numContacts())
175  n_contacts = (this->request.num_max_contacts >= this->result->numContacts()) ? (this->request.num_max_contacts - this->result->numContacts()) : 0;
176 
177  for(unsigned int i = 0; i < n_contacts; ++i)
178  {
179  this->result->addContact(Contact<S>(this->model1, this->model2, primitive_id1, primitive_id2, contacts[i], normal, penetration));
180  }
181  }
182  }
183 
184  if(is_intersect && this->request.enable_cost)
185  {
186  AABB<S> overlap_part;
187  AABB<S>(p1, p2, p3).overlap(AABB<S>(q1, q2, q3), overlap_part);
188  this->result->addCostSource(CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
189  }
190  }
191  else if((!this->model1->isFree() && !this->model2->isFree()) && this->request.enable_cost)
192  {
193  if(Intersect<S>::intersect_Triangle(p1, p2, p3, q1, q2, q3))
194  {
195  AABB<S> overlap_part;
196  AABB<S>(p1, p2, p3).overlap(AABB<S>(q1, q2, q3), overlap_part);
197  this->result->addCostSource(CostSource<S>(overlap_part, cost_density), this->request.num_max_cost_sources);
198  }
199  }
200 }
201 
202 //==============================================================================
203 template <typename BV>
205 {
206  return this->request.isSatisfied(*(this->result));
207 }
208 
209 //==============================================================================
210 template <typename BV>
213  BVHModel<BV>& model1,
215  BVHModel<BV>& model2,
217  const CollisionRequest<typename BV::S>& request,
219  bool use_refit,
220  bool refit_bottomup)
221 {
222  using S = typename BV::S;
223 
224  if(model1.getModelType() != BVH_MODEL_TRIANGLES
225  || model2.getModelType() != BVH_MODEL_TRIANGLES)
226  return false;
227 
228  if(!tf1.matrix().isIdentity())
229  {
230  std::vector<Vector3<S>> vertices_transformed1(model1.num_vertices);
231  for(int i = 0; i < model1.num_vertices; ++i)
232  {
233  Vector3<S>& p = model1.vertices[i];
234  Vector3<S> new_v = tf1 * p;
235  vertices_transformed1[i] = new_v;
236  }
237 
238  model1.beginReplaceModel();
239  model1.replaceSubModel(vertices_transformed1);
240  model1.endReplaceModel(use_refit, refit_bottomup);
241 
242  tf1.setIdentity();
243  }
244 
245  if(!tf2.matrix().isIdentity())
246  {
247  std::vector<Vector3<S>> vertices_transformed2(model2.num_vertices);
248  for(int i = 0; i < model2.num_vertices; ++i)
249  {
250  Vector3<S>& p = model2.vertices[i];
251  Vector3<S> new_v = tf2 * p;
252  vertices_transformed2[i] = new_v;
253  }
254 
255  model2.beginReplaceModel();
256  model2.replaceSubModel(vertices_transformed2);
257  model2.endReplaceModel(use_refit, refit_bottomup);
258 
259  tf2.setIdentity();
260  }
261 
262  node.model1 = &model1;
263  node.tf1 = tf1;
264  node.model2 = &model2;
265  node.tf2 = tf2;
266 
267  node.vertices1 = model1.vertices;
268  node.vertices2 = model2.vertices;
269 
270  node.tri_indices1 = model1.tri_indices;
271  node.tri_indices2 = model2.tri_indices;
272 
273  node.request = request;
274  node.result = &result;
275 
276  node.cost_density = model1.cost_density * model2.cost_density;
277 
278  return true;
279 }
280 
281 //==============================================================================
282 template <typename S>
285  R(Matrix3<S>::Identity())
286 {
287  // Do nothing
288 }
289 
290 //==============================================================================
291 template <typename S>
293 {
294  if(this->enable_statistics) this->num_bv_tests++;
295 
296  return !overlap(R, T, this->model1->getBV(b1).bv, this->model2->getBV(b2).bv);
297 }
298 
299 //==============================================================================
300 template <typename S>
302 {
304  b1,
305  b2,
306  this->model1,
307  this->model2,
308  this->vertices1,
309  this->vertices2,
310  this->tri_indices1,
311  this->tri_indices2,
312  R,
313  T,
314  this->tf1,
315  this->tf2,
316  this->enable_statistics,
317  this->cost_density,
318  this->num_leaf_tests,
319  this->request,
320  *this->result);
321 }
322 
323 //==============================================================================
324 template <typename S>
326  int b1, int b2, const Matrix3<S>& Rc, const Vector3<S>& Tc) const
327 {
328  if(this->enable_statistics) this->num_bv_tests++;
329 
330  return obbDisjoint(
331  Rc, Tc,
332  this->model1->getBV(b1).bv.extent,
333  this->model2->getBV(b2).bv.extent);
334 }
335 
336 //==============================================================================
337 template <typename S>
339  int b1, int b2, const Transform3<S>& tf) const
340 {
341  if(this->enable_statistics) this->num_bv_tests++;
342 
343  return obbDisjoint(tf,
344  this->model1->getBV(b1).bv.extent,
345  this->model2->getBV(b2).bv.extent);
346 }
347 
348 //==============================================================================
349 template <typename S>
351  int b1, int b2, const Matrix3<S>& Rc, const Vector3<S>& Tc) const
352 {
353  FCL_UNUSED(Rc);
354  FCL_UNUSED(Tc);
355 
357  b1,
358  b2,
359  this->model1,
360  this->model2,
361  this->vertices1,
362  this->vertices2,
363  this->tri_indices1,
364  this->tri_indices2,
365  R,
366  T,
367  this->tf1,
368  this->tf2,
369  this->enable_statistics,
370  this->cost_density,
371  this->num_leaf_tests,
372  this->request,
373  *this->result);
374 }
375 
376 //==============================================================================
377 template <typename S>
379  int b1, int b2, const Transform3<S>& tf) const
380 {
382  b1,
383  b2,
384  this->model1,
385  this->model2,
386  this->vertices1,
387  this->vertices2,
388  this->tri_indices1,
389  this->tri_indices2,
390  tf,
391  this->tf1,
392  this->tf2,
393  this->enable_statistics,
394  this->cost_density,
395  this->num_leaf_tests,
396  this->request,
397  *this->result);
398 }
399 
400 //==============================================================================
401 template <typename S>
404  R(Matrix3<S>::Identity())
405 {
406  // Do nothing
407 }
408 
409 //==============================================================================
410 template <typename S>
412 {
413  if(this->enable_statistics) this->num_bv_tests++;
414 
415  return !overlap(R, T, this->model1->getBV(b1).bv, this->model2->getBV(b2).bv);
416 }
417 
418 //==============================================================================
419 template <typename S>
421 {
423  b1,
424  b2,
425  this->model1,
426  this->model2,
427  this->vertices1,
428  this->vertices2,
429  this->tri_indices1,
430  this->tri_indices2,
431  R,
432  T,
433  this->tf1,
434  this->tf2,
435  this->enable_statistics,
436  this->cost_density,
437  this->num_leaf_tests,
438  this->request,
439  *this->result);
440 }
441 
442 //==============================================================================
443 template <typename S>
446  R(Matrix3<S>::Identity())
447 {
448  // Do nothing
449 }
450 
451 //==============================================================================
452 template <typename S>
454 {
455  if(this->enable_statistics) this->num_bv_tests++;
456 
457  return !overlap(R, T, this->model1->getBV(b1).bv, this->model2->getBV(b2).bv);
458 }
459 
460 //==============================================================================
461 template <typename S>
463 {
465  b1,
466  b2,
467  this->model1,
468  this->model2,
469  this->vertices1,
470  this->vertices2,
471  this->tri_indices1,
472  this->tri_indices2,
473  R,
474  T,
475  this->tf1,
476  this->tf2,
477  this->enable_statistics,
478  this->cost_density,
479  this->num_leaf_tests,
480  this->request,
481  *this->result);
482 }
483 
484 //==============================================================================
485 template <typename S>
488  R(Matrix3<S>::Identity())
489 {
490  // Do nothing
491 }
492 
493 //==============================================================================
494 template <typename S>
496 {
497  if(this->enable_statistics) this->num_bv_tests++;
498 
499  return !overlap(R, T, this->model1->getBV(b1).bv, this->model2->getBV(b2).bv);
500 }
501 
502 //==============================================================================
503 template <typename S>
505 {
507  b1,
508  b2,
509  this->model1,
510  this->model2,
511  this->vertices1,
512  this->vertices2,
513  this->tri_indices1,
514  this->tri_indices2,
515  R,
516  T,
517  this->tf1,
518  this->tf2,
519  this->enable_statistics,
520  this->cost_density,
521  this->num_leaf_tests,
522  this->request,
523  *this->result);
524 }
525 
526 template <typename BV>
528  int b1, int b2,
529  const BVHModel<BV>* model1,
530  const BVHModel<BV>* model2,
535  const Matrix3<typename BV::S>& R,
536  const Vector3<typename BV::S>& T,
539  bool enable_statistics,
540  typename BV::S cost_density,
541  int& num_leaf_tests,
544 {
545  using S = typename BV::S;
546 
547  if(enable_statistics) num_leaf_tests++;
548 
549  const BVNode<BV>& node1 = model1->getBV(b1);
550  const BVNode<BV>& node2 = model2->getBV(b2);
551 
552  int primitive_id1 = node1.primitiveId();
553  int primitive_id2 = node2.primitiveId();
554 
555  const Triangle& tri_id1 = tri_indices1[primitive_id1];
556  const Triangle& tri_id2 = tri_indices2[primitive_id2];
557 
558  const Vector3<S>& p1 = vertices1[tri_id1[0]];
559  const Vector3<S>& p2 = vertices1[tri_id1[1]];
560  const Vector3<S>& p3 = vertices1[tri_id1[2]];
561  const Vector3<S>& q1 = vertices2[tri_id2[0]];
562  const Vector3<S>& q2 = vertices2[tri_id2[1]];
563  const Vector3<S>& q3 = vertices2[tri_id2[2]];
564 
565  if(model1->isOccupied() && model2->isOccupied())
566  {
567  bool is_intersect = false;
568 
569  if(!request.enable_contact) // only interested in collision or not
570  {
571  if(Intersect<S>::intersect_Triangle(p1, p2, p3, q1, q2, q3, R, T))
572  {
573  is_intersect = true;
574  if(result.numContacts() < request.num_max_contacts)
575  result.addContact(Contact<S>(model1, model2, primitive_id1, primitive_id2));
576  }
577  }
578  else // need compute the contact information
579  {
580  S penetration;
581  Vector3<S> normal;
582  unsigned int n_contacts;
583  Vector3<S> contacts[2];
584 
585  if(Intersect<S>::intersect_Triangle(p1, p2, p3, q1, q2, q3,
586  R, T,
587  contacts,
588  &n_contacts,
589  &penetration,
590  &normal))
591  {
592  is_intersect = true;
593 
594  if(request.num_max_contacts < result.numContacts() + n_contacts)
595  n_contacts = (request.num_max_contacts > result.numContacts()) ? (request.num_max_contacts - result.numContacts()) : 0;
596 
597  for(unsigned int i = 0; i < n_contacts; ++i)
598  {
599  result.addContact(Contact<S>(model1, model2, primitive_id1, primitive_id2, tf1 * contacts[i], tf1.linear() * normal, penetration));
600  }
601  }
602  }
603 
604  if(is_intersect && request.enable_cost)
605  {
606  AABB<S> overlap_part;
607  AABB<S>(tf1 * p1, tf1 * p2, tf1 * p3).overlap(AABB<S>(tf2 * q1, tf2 * q2, tf2 * q3), overlap_part);
608  result.addCostSource(CostSource<S>(overlap_part, cost_density), request.num_max_cost_sources);
609  }
610  }
611  else if((!model1->isFree() && !model2->isFree()) && request.enable_cost)
612  {
613  if(Intersect<S>::intersect_Triangle(p1, p2, p3, q1, q2, q3, R, T))
614  {
615  AABB<S> overlap_part;
616  AABB<S>(tf1 * p1, tf1 * p2, tf1 * p3).overlap(AABB<S>(tf2 * q1, tf2 * q2, tf2 * q3), overlap_part);
617  result.addCostSource(CostSource<S>(overlap_part, cost_density), request.num_max_cost_sources);
618  }
619  }
620 }
621 
622 //==============================================================================
623 template <typename BV>
625  int b1,
626  int b2,
627  const BVHModel<BV>* model1,
628  const BVHModel<BV>* model2,
633  const Transform3<typename BV::S>& tf,
636  bool enable_statistics,
637  typename BV::S cost_density,
638  int& num_leaf_tests,
641 {
642  using S = typename BV::S;
643 
644  if(enable_statistics) num_leaf_tests++;
645 
646  const BVNode<BV>& node1 = model1->getBV(b1);
647  const BVNode<BV>& node2 = model2->getBV(b2);
648 
649  int primitive_id1 = node1.primitiveId();
650  int primitive_id2 = node2.primitiveId();
651 
652  const Triangle& tri_id1 = tri_indices1[primitive_id1];
653  const Triangle& tri_id2 = tri_indices2[primitive_id2];
654 
655  const Vector3<S>& p1 = vertices1[tri_id1[0]];
656  const Vector3<S>& p2 = vertices1[tri_id1[1]];
657  const Vector3<S>& p3 = vertices1[tri_id1[2]];
658  const Vector3<S>& q1 = vertices2[tri_id2[0]];
659  const Vector3<S>& q2 = vertices2[tri_id2[1]];
660  const Vector3<S>& q3 = vertices2[tri_id2[2]];
661 
662  if(model1->isOccupied() && model2->isOccupied())
663  {
664  bool is_intersect = false;
665 
666  if(!request.enable_contact) // only interested in collision or not
667  {
668  if(Intersect<S>::intersect_Triangle(p1, p2, p3, q1, q2, q3, tf))
669  {
670  is_intersect = true;
671  if(result.numContacts() < request.num_max_contacts)
672  result.addContact(Contact<S>(model1, model2, primitive_id1, primitive_id2));
673  }
674  }
675  else // need compute the contact information
676  {
677  S penetration;
678  Vector3<S> normal;
679  unsigned int n_contacts;
680  Vector3<S> contacts[2];
681 
683  p1, p2, p3, q1, q2, q3, tf, contacts, &n_contacts, &penetration, &normal))
684  {
685  is_intersect = true;
686 
687  if(request.num_max_contacts < result.numContacts() + n_contacts)
688  n_contacts = (request.num_max_contacts > result.numContacts()) ? (request.num_max_contacts - result.numContacts()) : 0;
689 
690  for(unsigned int i = 0; i < n_contacts; ++i)
691  {
692  result.addContact(Contact<S>(model1, model2, primitive_id1, primitive_id2, tf1 * contacts[i], tf1.linear() * normal, penetration));
693  }
694  }
695  }
696 
697  if(is_intersect && request.enable_cost)
698  {
699  AABB<S> overlap_part;
700  AABB<S>(tf1 * p1, tf1 * p2, tf1 * p3).overlap(AABB<S>(tf2 * q1, tf2 * q2, tf2 * q3), overlap_part);
701  result.addCostSource(CostSource<S>(overlap_part, cost_density), request.num_max_cost_sources);
702  }
703  }
704  else if((!model1->isFree() && !model2->isFree()) && request.enable_cost)
705  {
706  if(Intersect<S>::intersect_Triangle(p1, p2, p3, q1, q2, q3, tf))
707  {
708  AABB<S> overlap_part;
709  AABB<S>(tf1 * p1, tf1 * p2, tf1 * p3).overlap(AABB<S>(tf2 * q1, tf2 * q2, tf2 * q3), overlap_part);
710  result.addCostSource(CostSource<S>(overlap_part, cost_density), request.num_max_cost_sources);
711  }
712  }
713 }
714 
715 template<typename BV, typename OrientedNode>
717  OrientedNode& node,
722 {
724  return false;
725 
726  node.vertices1 = model1.vertices;
727  node.vertices2 = model2.vertices;
728 
729  node.tri_indices1 = model1.tri_indices;
730  node.tri_indices2 = model2.tri_indices;
731 
732  node.model1 = &model1;
733  node.tf1 = tf1;
734  node.model2 = &model2;
735  node.tf2 = tf2;
736 
737  node.request = request;
738  node.result = &result;
739 
740  node.cost_density = model1.cost_density * model2.cost_density;
741 
742  relativeTransform(tf1.linear(), tf1.translation(), tf2.linear(), tf2.translation(), node.R, node.T);
743 
744  return true;
745 }
746 
747 //==============================================================================
748 template <typename S>
751  const BVHModel<OBB<S>>& model1,
752  const Transform3<S>& tf1,
753  const BVHModel<OBB<S>>& model2,
754  const Transform3<S>& tf2,
757 {
759  node, model1, tf1, model2, tf2, request, result);
760 }
761 
762 //==============================================================================
763 template <typename S>
766  const BVHModel<RSS<S>>& model1,
767  const Transform3<S>& tf1,
768  const BVHModel<RSS<S>>& model2,
769  const Transform3<S>& tf2,
772 {
774  node, model1, tf1, model2, tf2, request, result);
775 }
776 
777 //==============================================================================
778 template <typename S>
781  const BVHModel<kIOS<S>>& model1,
782  const Transform3<S>& tf1,
783  const BVHModel<kIOS<S>>& model2,
784  const Transform3<S>& tf2,
787 {
789  node, model1, tf1, model2, tf2, request, result);
790 }
791 
792 //==============================================================================
793 template <typename S>
796  const BVHModel<OBBRSS<S>>& model1,
797  const Transform3<S>& tf1,
798  const BVHModel<OBBRSS<S>>& model2,
799  const Transform3<S>& tf2,
802 {
804  node, model1, tf1, model2, tf2, request, result);
805 }
806 
807 } // namespace detail
808 } // namespace fcl
809 
810 #endif
size_t numContacts() const
number of contacts found
bool enable_cost
If true, the cost sources will be computed.
template bool obbDisjoint(const Matrix3< double > &B, const Vector3< double > &T, const Vector3< double > &a, const Vector3< double > &b)
void addCostSource(const CostSource< S > &c, std::size_t num_max_cost_sources)
add one cost source into result structure
size_t num_max_contacts
The maximum number of contacts that can be returned.
Main namespace.
int replaceSubModel(const std::vector< Vector3< S >> &ps)
Replace a set of points in the old BVH model.
collision result
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
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
int beginReplaceModel()
Replace the geometry information of current frame (i.e. should have the same mesh topology with the p...
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
Contact information returned by collision.
Definition: contact.h:48
Eigen::Matrix< S, 3, 3 > Matrix3
Definition: types.h:85
template class FCL_EXPORT MeshCollisionTraversalNodeOBBRSS< double >
template class FCL_EXPORT MeshCollisionTraversalNodeOBB< double >
bool overlap(S a1, S a2, S b1, S b2)
returns 1 if the intervals overlap, and 0 otherwise
int primitiveId() const
Return the primitive index. The index is referred to the original data (i.e. vertices or tri_indices)...
template class FCL_EXPORT MeshCollisionTraversalNodeRSS< double >
Vector3< S > * vertices
Geometry point data.
Definition: BVH_model.h:162
bool isFree() const
whether the object is completely free
Eigen::Matrix< S, 3, 1 > Vector3
Definition: types.h:70
int num_vertices
Number of points.
Definition: BVH_model.h:174
CollisionRequest< BV::S > request
request setting for collision
const BVHModel< BV > * model1
The first BVH model.
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
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
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
unknown model type
Definition: BVH_internal.h:78
bool enable_contact
If true, contact information (e.g., normal, penetration depth, and contact position) will be returned...
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
Parameters for performing collision request.
size_t num_max_cost_sources
The maximum number of cost sources that can be returned.
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)
template class FCL_EXPORT MeshCollisionTraversalNodekIOS< double >
bool isOccupied() const
whether the object is completely occupied
bool setupMeshCollisionOrientedNode(OrientedNode &node, const BVHModel< BV > &model1, const Transform3< typename BV::S > &tf1, const BVHModel< BV > &model2, const Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
void leafTesting(int b1, int b2) const
Leaf test between node b1 and b2, if they are both leafs.
Traversal node for collision between BVH models.
#define FCL_UNUSED(x)
Definition: unused.h:39
template class FCL_EXPORT kIOS< double >
Traversal node for collision between two meshes.
Vector3< S > extent
Half dimensions of OBB.
Definition: OBB.h:68
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH_model.h:57
template class FCL_EXPORT OBB< double >
BV bv
bounding volume storing the geometry
Definition: BV_node.h:57
const BVNode< BV > & getBV(int id) const
We provide getBV() and getNumBVs() because BVH may be compressed (in future), so we must provide some...
BV::S cost_density
collision cost for unit volume
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
CollisionResult< BV::S > * result
collision 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
Transform3< BV::S > tf1
configuation of first object
Cost source describes an area with a cost. The area is described by an AABB<S> region.
Definition: cost_source.h:49
template class FCL_EXPORT OBBRSS< double >
Class merging the OBB and RSS, can handle collision and distance simultaneously.
Definition: OBBRSS.h:50
FCL_EXPORT void relativeTransform(const Eigen::MatrixBase< DerivedA > &R1, const Eigen::MatrixBase< DerivedB > &t1, const Eigen::MatrixBase< DerivedA > &R2, const Eigen::MatrixBase< DerivedB > &t2, Eigen::MatrixBase< DerivedC > &R, Eigen::MatrixBase< DerivedD > &t)
Definition: geometry-inl.h:659
CCD intersect kernel among primitives.
Definition: intersect.h:54
const BVHModel< BV > * model2
The second BVH model.
int endReplaceModel(bool refit=true, bool bottomup=true)
End BVH model replacement, will also refit or rebuild the bounding volume hierarchy.
bool initialize(MeshCollisionTraversalNodeOBBRSS< S > &node, const BVHModel< OBBRSS< S >> &model1, const Transform3< S > &tf1, const BVHModel< OBBRSS< S >> &model2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result)
Initialize traversal node for collision between two meshes, specialized for OBBRSS type...
A class describing the kIOS collision structure, which is a set of spheres.
Definition: kIOS.h:48
Traversal node for collision between two meshes if their underlying BVH node is oriented node (OBB...
void meshCollisionOrientedNodeLeafTesting(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, const Transform3< typename BV::S > &tf1, const Transform3< typename BV::S > &tf2, bool enable_statistics, typename BV::S cost_density, int &num_leaf_tests, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result)
bool BVTesting(int b1, int b2) const
BV test between b1 and b2.
Oriented bounding box class.
Definition: OBB.h:51
void addContact(const Contact< S > &c)
add one contact into result structure


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