tesseract_convex_convex_algorithm.cpp
Go to the documentation of this file.
1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
4 
5 This software is provided 'as-is', without any express or implied warranty.
6 In no event will the authors be held liable for any damages arising from the use of this software.
7 Permission is granted to anyone to use this software for any purpose,
8 including commercial applications, and to alter it and redistribute it freely,
9 subject to the following restrictions:
10 
11 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If
12 you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not
13 required.
14 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original
15 software.
16 3. This notice may not be removed or altered from any source distribution.
17 */
18 
22 //#define BT_DISABLE_CAPSULE_CAPSULE_COLLIDER 1
23 //#define ZERO_MARGIN
24 
27 
29 #include <BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h>
30 #include <BulletCollision/BroadphaseCollision/btBroadphaseInterface.h>
31 #include <BulletCollision/CollisionDispatch/btCollisionObject.h>
32 #include <BulletCollision/CollisionShapes/btConvexShape.h>
33 #include <BulletCollision/CollisionShapes/btCapsuleShape.h>
34 #include <BulletCollision/CollisionShapes/btTriangleShape.h>
35 #include <BulletCollision/CollisionShapes/btConvexPolyhedron.h>
36 
37 //#include <BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h>
38 #include <BulletCollision/BroadphaseCollision/btBroadphaseProxy.h>
39 #include <BulletCollision/CollisionDispatch/btCollisionDispatcher.h>
40 #include <BulletCollision/CollisionShapes/btBoxShape.h>
41 #include <BulletCollision/CollisionDispatch/btManifoldResult.h>
42 
43 #include <BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h>
44 #include <BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h>
45 #include <BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h>
46 #include <BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h>
47 
48 #include <BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h>
49 #include <BulletCollision/CollisionShapes/btSphereShape.h>
50 
51 #include <BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h>
52 
53 #include <BulletCollision/NarrowPhaseCollision/btGjkEpa2.h>
54 #include <BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h>
55 #include <BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.h>
56 #include <BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h>
58 
60 extern btScalar gContactBreakingThreshold; // NOLINT
61 
62 // LCOV_EXCL_START
64 {
65 static SIMD_FORCE_INLINE void segmentsClosestPoints(btVector3& ptsVector,
66  btVector3& offsetA,
67  btVector3& offsetB,
68  btScalar& tA,
69  btScalar& tB,
70  const btVector3& translation,
71  const btVector3& dirA,
72  btScalar hlenA,
73  const btVector3& dirB,
74  btScalar hlenB)
75 {
76  // compute the parameters of the closest points on each line segment
77 
78  btScalar dirA_dot_dirB = btDot(dirA, dirB);
79  btScalar dirA_dot_trans = btDot(dirA, translation);
80  btScalar dirB_dot_trans = btDot(dirB, translation);
81 
82  btScalar denom = btScalar(1.0) - (dirA_dot_dirB * dirA_dot_dirB);
83 
84  if (denom == btScalar(0.0))
85  {
86  tA = btScalar(0.0);
87  }
88  else
89  {
90  tA = (dirA_dot_trans - dirB_dot_trans * dirA_dot_dirB) / denom;
91  if (tA < -hlenA)
92  tA = -hlenA;
93  else if (tA > hlenA)
94  tA = hlenA;
95  }
96 
97  tB = tA * dirA_dot_dirB - dirB_dot_trans;
98 
99  if (tB < -hlenB)
100  {
101  tB = -hlenB;
102  tA = tB * dirA_dot_dirB + dirA_dot_trans;
103 
104  if (tA < -hlenA)
105  tA = -hlenA;
106  else if (tA > hlenA)
107  tA = hlenA;
108  }
109  else if (tB > hlenB)
110  {
111  tB = hlenB;
112  tA = tB * dirA_dot_dirB + dirA_dot_trans;
113 
114  if (tA < -hlenA)
115  tA = -hlenA;
116  else if (tA > hlenA)
117  tA = hlenA;
118  }
119 
120  // compute the closest points relative to segment centers.
121 
122  offsetA = dirA * tA;
123  offsetB = dirB * tB;
124 
125  ptsVector = translation - offsetA + offsetB;
126 }
127 
128 static SIMD_FORCE_INLINE btScalar capsuleCapsuleDistance(btVector3& normalOnB,
129  btVector3& pointOnB,
130  btScalar capsuleLengthA,
131  btScalar capsuleRadiusA,
132  btScalar capsuleLengthB,
133  btScalar capsuleRadiusB,
134  int capsuleAxisA,
135  int capsuleAxisB,
136  const btTransform& transformA,
137  const btTransform& transformB,
138  btScalar distanceThreshold)
139 {
140  btVector3 directionA = transformA.getBasis().getColumn(capsuleAxisA);
141  btVector3 translationA = transformA.getOrigin();
142  btVector3 directionB = transformB.getBasis().getColumn(capsuleAxisB);
143  btVector3 translationB = transformB.getOrigin();
144 
145  // translation between centers
146 
147  btVector3 translation = translationB - translationA;
148 
149  // compute the closest points of the capsule line segments
150 
151  btVector3 ptsVector; // the vector between the closest points
152 
153  btVector3 offsetA, offsetB; // offsets from segment centers to their closest points
154  btScalar tA{ std::numeric_limits<btScalar>::max() },
155  tB{ std::numeric_limits<btScalar>::max() }; // parameters on line segment
156 
158  ptsVector, offsetA, offsetB, tA, tB, translation, directionA, capsuleLengthA, directionB, capsuleLengthB);
159 
160  btScalar distance = ptsVector.length() - capsuleRadiusA - capsuleRadiusB;
161 
162  if (distance > distanceThreshold)
163  return distance;
164 
165  btScalar lenSqr = ptsVector.length2();
166  if (lenSqr <= (SIMD_EPSILON * SIMD_EPSILON))
167  {
168  // degenerate case where 2 capsules are likely at the same location: take a vector tangential to 'directionA'
169  btVector3 q;
170  btPlaneSpace1(directionA, normalOnB, q);
171  }
172  else
173  {
174  // compute the contact normal
175  normalOnB = ptsVector * -btRecipSqrt(lenSqr);
176  }
177  pointOnB = transformB.getOrigin() + offsetB + normalOnB * capsuleRadiusB;
178 
179  return distance;
180 }
181 
183 
184 TesseractConvexConvexAlgorithm::CreateFunc::CreateFunc(btConvexPenetrationDepthSolver* pdSolver) : m_pdSolver(pdSolver)
185 {
186 }
187 
189  const btCollisionAlgorithmConstructionInfo& ci,
190  const btCollisionObjectWrapper* body0Wrap,
191  const btCollisionObjectWrapper* body1Wrap,
192  btConvexPenetrationDepthSolver* pdSolver,
193  int numPerturbationIterations,
194  int minimumPointsPerturbationThreshold)
195  : btActivatingCollisionAlgorithm(ci, body0Wrap, body1Wrap)
196  , m_pdSolver(pdSolver)
197  , m_manifoldPtr(mf)
198  ,
199 #ifdef USE_SEPDISTANCE_UTIL2
200  m_sepDistance((static_cast<btConvexShape*>(body0->getCollisionShape()))->getAngularMotionDisc(),
201  (static_cast<btConvexShape*>(body1->getCollisionShape()))->getAngularMotionDisc())
202  ,
203 #endif
204  m_numPerturbationIterations(numPerturbationIterations)
205  , m_minimumPointsPerturbationThreshold(minimumPointsPerturbationThreshold)
206  , m_cdata(static_cast<ContactTestData*>(body0Wrap->m_collisionObject->getUserPointer()))
207 {
208  (void)body0Wrap;
209  (void)body1Wrap;
210  assert(m_cdata != nullptr);
211 }
212 
214 {
215  if (m_ownManifold)
216  {
217  if (m_manifoldPtr != nullptr)
218  m_dispatcher->releaseManifold(m_manifoldPtr);
219  }
220 }
221 
223 
224 struct btPerturbedContactResult : public btManifoldResult // NOLINT
225 {
226  btManifoldResult* m_originalManifoldResult;
227  btTransform m_transformA;
228  btTransform m_transformB;
231  btIDebugDraw* m_debugDrawer;
232 
233  btPerturbedContactResult(btManifoldResult* originalResult,
234  const btTransform& transformA,
235  const btTransform& transformB,
236  const btTransform& unPerturbedTransform,
237  bool perturbA,
238  btIDebugDraw* debugDrawer)
239  : m_originalManifoldResult(originalResult)
240  , m_transformA(transformA)
241  , m_transformB(transformB)
242  , m_unPerturbedTransform(unPerturbedTransform)
243  , m_perturbA(perturbA)
244  , m_debugDrawer(debugDrawer)
245  {
246  }
247  ~btPerturbedContactResult() override = default;
248 
249  void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar orgDepth) override
250  {
251  btVector3 endPt, startPt;
252  btScalar newDepth{ std::numeric_limits<btScalar>::max() };
253  btVector3 newNormal;
254 
255  if (m_perturbA)
256  {
257  btVector3 endPtOrg = pointInWorld + normalOnBInWorld * orgDepth;
258  endPt = (m_unPerturbedTransform * m_transformA.inverse())(endPtOrg);
259  newDepth = (endPt - pointInWorld).dot(normalOnBInWorld);
260  startPt = endPt - normalOnBInWorld * newDepth;
261  }
262  else
263  {
264  endPt = pointInWorld + normalOnBInWorld * orgDepth;
265  startPt = (m_unPerturbedTransform * m_transformB.inverse())(pointInWorld);
266  newDepth = (endPt - startPt).dot(normalOnBInWorld);
267  }
268 
269 //#define DEBUG_CONTACTS 1
270 #ifdef DEBUG_CONTACTS
271  m_debugDrawer->drawLine(startPt, endPt, btVector3(1, 0, 0));
272  m_debugDrawer->drawSphere(startPt, 0.05, btVector3(0, 1, 0));
273  m_debugDrawer->drawSphere(endPt, 0.05, btVector3(0, 0, 1));
274 #endif // DEBUG_CONTACTS
275 
276  m_originalManifoldResult->addContactPoint(normalOnBInWorld, startPt, newDepth);
277  }
278 };
279 
280 //
281 // Convex-Convex collision algorithm
282 //
283 void TesseractConvexConvexAlgorithm::processCollision(const btCollisionObjectWrapper* body0Wrap,
284  const btCollisionObjectWrapper* body1Wrap,
285  const btDispatcherInfo& dispatchInfo,
286  btManifoldResult* resultOut)
287 {
288  if (m_manifoldPtr == nullptr)
289  {
290  // swapped?
291  m_manifoldPtr = m_dispatcher->getNewManifold(body0Wrap->getCollisionObject(), body1Wrap->getCollisionObject());
292  m_ownManifold = true;
293  }
294  resultOut->setPersistentManifold(m_manifoldPtr);
295 
296  // comment-out next line to test multi-contact generation
297  // resultOut->getPersistentManifold()->clearManifold();
298 
299  const auto* min0 = static_cast<const btConvexShape*>(body0Wrap->getCollisionShape());
300  const auto* min1 = static_cast<const btConvexShape*>(body1Wrap->getCollisionShape());
301 
302  btVector3 normalOnB;
303  btVector3 pointOnBWorld;
304 #ifndef BT_DISABLE_CAPSULE_CAPSULE_COLLIDER
305  if ((min0->getShapeType() == CAPSULE_SHAPE_PROXYTYPE) && (min1->getShapeType() == CAPSULE_SHAPE_PROXYTYPE))
306  {
307  // m_manifoldPtr->clearManifold();
308 
309  auto* capsuleA = (btCapsuleShape*)min0; // NOLINT
310  auto* capsuleB = (btCapsuleShape*)min1; // NOLINT
311 
312  btScalar threshold = m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
313 
314  btScalar dist = capsuleCapsuleDistance(normalOnB,
315  pointOnBWorld,
316  capsuleA->getHalfHeight(),
317  capsuleA->getRadius(),
318  capsuleB->getHalfHeight(),
319  capsuleB->getRadius(),
320  capsuleA->getUpAxis(),
321  capsuleB->getUpAxis(),
322  body0Wrap->getWorldTransform(),
323  body1Wrap->getWorldTransform(),
324  threshold);
325 
326  if (dist < threshold)
327  {
328  btAssert(normalOnB.length2() >= (SIMD_EPSILON * SIMD_EPSILON));
329  resultOut->addContactPoint(normalOnB, pointOnBWorld, dist);
330  }
331  resultOut->refreshContactPoints();
332  return;
333  }
334 
335  if ((min0->getShapeType() == CAPSULE_SHAPE_PROXYTYPE) && (min1->getShapeType() == SPHERE_SHAPE_PROXYTYPE))
336  {
337  // m_manifoldPtr->clearManifold();
338 
339  auto* capsuleA = (btCapsuleShape*)min0; // NOLINT
340  auto* capsuleB = (btSphereShape*)min1; // NOLINT
341 
342  btScalar threshold = m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
343 
344  btScalar dist = capsuleCapsuleDistance(normalOnB,
345  pointOnBWorld,
346  capsuleA->getHalfHeight(),
347  capsuleA->getRadius(),
348  0.,
349  capsuleB->getRadius(),
350  capsuleA->getUpAxis(),
351  1,
352  body0Wrap->getWorldTransform(),
353  body1Wrap->getWorldTransform(),
354  threshold);
355 
356  if (dist < threshold)
357  {
358  btAssert(normalOnB.length2() >= (SIMD_EPSILON * SIMD_EPSILON));
359  resultOut->addContactPoint(normalOnB, pointOnBWorld, dist);
360  }
361  resultOut->refreshContactPoints();
362  return;
363  }
364 
365  if ((min0->getShapeType() == SPHERE_SHAPE_PROXYTYPE) && (min1->getShapeType() == CAPSULE_SHAPE_PROXYTYPE))
366  {
367  // m_manifoldPtr->clearManifold();
368 
369  auto* capsuleA = (btSphereShape*)min0; // NOLINT
370  auto* capsuleB = (btCapsuleShape*)min1; // NOLINT
371 
372  btScalar threshold = m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
373 
374  btScalar dist = capsuleCapsuleDistance(normalOnB,
375  pointOnBWorld,
376  0.,
377  capsuleA->getRadius(),
378  capsuleB->getHalfHeight(),
379  capsuleB->getRadius(),
380  1,
381  capsuleB->getUpAxis(),
382  body0Wrap->getWorldTransform(),
383  body1Wrap->getWorldTransform(),
384  threshold);
385 
386  if (dist < threshold)
387  {
388  btAssert(normalOnB.length2() >= (SIMD_EPSILON * SIMD_EPSILON));
389  resultOut->addContactPoint(normalOnB, pointOnBWorld, dist);
390  }
391  resultOut->refreshContactPoints();
392  return;
393  }
394 #endif // BT_DISABLE_CAPSULE_CAPSULE_COLLIDER
395 
396 #ifdef USE_SEPDISTANCE_UTIL2
397  if (dispatchInfo.m_useConvexConservativeDistanceUtil)
398  {
399  m_sepDistance.updateSeparatingDistance(body0->getWorldTransform(), body1->getWorldTransform());
400  }
401 
402  if (!dispatchInfo.m_useConvexConservativeDistanceUtil || m_sepDistance.getConservativeSeparatingDistance() <= 0.f)
403 #endif // USE_SEPDISTANCE_UTIL2
404 
405  {
406  // btGjkPairDetector::ClosestPointInput input;
407  // btVoronoiSimplexSolver simplexSolver;
408  // btGjkPairDetector gjkPairDetector(min0, min1, &simplexSolver, nullptr); // m_pdSolver);
409  TesseractGjkPairDetector::ClosestPointInput input;
410  btVoronoiSimplexSolver simplexSolver;
411  TesseractGjkPairDetector gjkPairDetector(min0, min1, &simplexSolver, m_pdSolver, m_cdata);
412  // TODO: if (dispatchInfo.m_useContinuous)
413  gjkPairDetector.setMinkowskiA(min0);
414  gjkPairDetector.setMinkowskiB(min1);
415 
416 #ifdef USE_SEPDISTANCE_UTIL2
417  if (dispatchInfo.m_useConvexConservativeDistanceUtil)
418  {
419  input.m_maximumDistanceSquared = BT_LARGE_FLOAT;
420  }
421  else
422 #endif // USE_SEPDISTANCE_UTIL2
423  {
424  // if (dispatchInfo.m_convexMaxDistanceUseCPT)
425  //{
426  // input.m_maximumDistanceSquared = min0->getMargin() + min1->getMargin() +
427  // m_manifoldPtr->getContactProcessingThreshold(); } else
428  //{
429  input.m_maximumDistanceSquared = min0->getMargin() + min1->getMargin() +
430  m_manifoldPtr->getContactBreakingThreshold() +
431  resultOut->m_closestPointDistanceThreshold;
432  // }
433 
434  input.m_maximumDistanceSquared *= input.m_maximumDistanceSquared;
435  }
436 
437  input.m_transformA = body0Wrap->getWorldTransform();
438  input.m_transformB = body1Wrap->getWorldTransform();
439 
440 #ifdef USE_SEPDISTANCE_UTIL2
441  btScalar sepDist = 0.f;
442  if (dispatchInfo.m_useConvexConservativeDistanceUtil)
443  {
444  sepDist = gjkPairDetector.getCachedSeparatingDistance();
445  if (sepDist > SIMD_EPSILON)
446  {
447  sepDist += dispatchInfo.m_convexConservativeDistanceThreshold;
448  // now perturbe directions to get multiple contact points
449  }
450  }
451 #endif // USE_SEPDISTANCE_UTIL2
452 
453  if (min0->isPolyhedral() && min1->isPolyhedral())
454  {
455  struct btDummyResult : public btDiscreteCollisionDetectorInterface::Result
456  {
457  btVector3 m_normalOnBInWorld;
458  btVector3 m_pointInWorld;
459  btScalar m_depth{ std::numeric_limits<btScalar>::max() };
460  bool m_hasContact{ false };
461 
462  btDummyResult() = default;
463 
464  void setShapeIdentifiersA(int /*partId0*/, int /*index0*/) override {}
465  void setShapeIdentifiersB(int /*partId1*/, int /*index1*/) override {}
466  void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) override
467  {
468  m_hasContact = true;
469  m_normalOnBInWorld = normalOnBInWorld;
470  m_pointInWorld = pointInWorld;
471  m_depth = depth;
472  }
473  };
474 
475  struct btWithoutMarginResult : public btDiscreteCollisionDetectorInterface::Result
476  {
477  btDiscreteCollisionDetectorInterface::Result* m_originalResult;
478  btVector3 m_reportedNormalOnWorld;
479  btScalar m_marginOnA;
480  btScalar m_marginOnB;
481  btScalar m_reportedDistance{ 0 };
482 
483  bool m_foundResult{ false };
484  btWithoutMarginResult(btDiscreteCollisionDetectorInterface::Result* result,
485  btScalar marginOnA,
486  btScalar marginOnB)
487  : m_originalResult(result), m_marginOnA(marginOnA), m_marginOnB(marginOnB)
488  {
489  }
490 
491  void setShapeIdentifiersA(int /*partId0*/, int /*index0*/) override {}
492  void setShapeIdentifiersB(int /*partId1*/, int /*index1*/) override {}
493  void addContactPoint(const btVector3& normalOnBInWorld,
494  const btVector3& pointInWorldOrg,
495  btScalar depthOrg) override
496  {
497  m_reportedDistance = depthOrg;
498  m_reportedNormalOnWorld = normalOnBInWorld;
499 
500  btVector3 adjustedPointB = pointInWorldOrg - normalOnBInWorld * m_marginOnB;
501  m_reportedDistance = depthOrg + (m_marginOnA + m_marginOnB);
502  if (m_reportedDistance < btScalar(0.))
503  {
504  m_foundResult = true;
505  }
506  m_originalResult->addContactPoint(normalOnBInWorld, adjustedPointB, m_reportedDistance);
507  }
508  };
509 
510  btDummyResult dummy;
511 
513 
514  btScalar min0Margin = min0->getShapeType() == BOX_SHAPE_PROXYTYPE ? btScalar(0.) : min0->getMargin();
515  btScalar min1Margin = min1->getShapeType() == BOX_SHAPE_PROXYTYPE ? btScalar(0.) : min1->getMargin();
516 
517  btWithoutMarginResult withoutMargin(resultOut, min0Margin, min1Margin);
518 
519  auto* polyhedronA = (btPolyhedralConvexShape*)min0; // NOLINT
520  auto* polyhedronB = (btPolyhedralConvexShape*)min1; // NOLINT
521 
522  if (polyhedronA->getConvexPolyhedron() != nullptr && polyhedronB->getConvexPolyhedron() != nullptr)
523  {
524  btScalar threshold = m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
525 
526  auto minDist = btScalar(-1e30);
527  btVector3 sepNormalWorldSpace;
528  bool foundSepAxis = true;
529 
530  if (dispatchInfo.m_enableSatConvex)
531  {
532  foundSepAxis = btPolyhedralContactClipping::findSeparatingAxis(*polyhedronA->getConvexPolyhedron(),
533  *polyhedronB->getConvexPolyhedron(),
534  body0Wrap->getWorldTransform(),
535  body1Wrap->getWorldTransform(),
536  sepNormalWorldSpace,
537  *resultOut);
538  }
539  else
540  {
541 #ifdef ZERO_MARGIN
542  gjkPairDetector.setIgnoreMargin(true);
543  gjkPairDetector.getClosestPoints(input, *resultOut, dispatchInfo.m_debugDraw);
544 #else
545 
546  gjkPairDetector.getClosestPoints(input, withoutMargin, dispatchInfo.m_debugDraw);
547  // gjkPairDetector.getClosestPoints(input,dummy,dispatchInfo.m_debugDraw);
548 #endif // ZERO_MARGIN
549  // btScalar l2 = gjkPairDetector.getCachedSeparatingAxis().length2();
550  // if (l2>SIMD_EPSILON)
551  {
552  sepNormalWorldSpace =
553  withoutMargin.m_reportedNormalOnWorld; // gjkPairDetector.getCachedSeparatingAxis()*(1.f/l2);
554  // minDist = -1e30f;//gjkPairDetector.getCachedSeparatingDistance();
555  minDist =
556  withoutMargin
557  .m_reportedDistance; // gjkPairDetector.getCachedSeparatingDistance()+min0->getMargin()+min1->getMargin();
558 
559 #ifdef ZERO_MARGIN
560  foundSepAxis = true; // gjkPairDetector.getCachedSeparatingDistance()<0.f;
561 #else
562  foundSepAxis = withoutMargin.m_foundResult && minDist < 0; //-(min0->getMargin()+min1->getMargin());
563 #endif
564  }
565  }
566  if (foundSepAxis)
567  {
568  // printf("sepNormalWorldSpace=%f,%f,%f\n",sepNormalWorldSpace.getX(),sepNormalWorldSpace.getY(),sepNormalWorldSpace.getZ());
569 
570  worldVertsB1.resize(0);
571  btPolyhedralContactClipping::clipHullAgainstHull(sepNormalWorldSpace,
572  *polyhedronA->getConvexPolyhedron(),
573  *polyhedronB->getConvexPolyhedron(),
574  body0Wrap->getWorldTransform(),
575  body1Wrap->getWorldTransform(),
576  minDist - threshold,
577  threshold,
578  worldVertsB1,
579  worldVertsB2,
580  *resultOut);
581  }
582  if (m_ownManifold)
583  {
584  resultOut->refreshContactPoints();
585  }
586  return;
587  }
588  else // NOLINT
589  {
590  // we can also deal with convex versus triangle (without connectivity data)
591  if (dispatchInfo.m_enableSatConvex && polyhedronA->getConvexPolyhedron() != nullptr &&
592  polyhedronB->getShapeType() == TRIANGLE_SHAPE_PROXYTYPE)
593  {
594  btVertexArray worldSpaceVertices;
595  auto* tri = (btTriangleShape*)polyhedronB; // NOLINT
596  worldSpaceVertices.push_back(body1Wrap->getWorldTransform() * tri->m_vertices1[0]);
597  worldSpaceVertices.push_back(body1Wrap->getWorldTransform() * tri->m_vertices1[1]);
598  worldSpaceVertices.push_back(body1Wrap->getWorldTransform() * tri->m_vertices1[2]);
599 
600  // tri->initializePolyhedralFeatures();
601 
602  btScalar threshold =
603  m_manifoldPtr->getContactBreakingThreshold() + resultOut->m_closestPointDistanceThreshold;
604 
605  btVector3 sepNormalWorldSpace;
606  auto minDist = btScalar(-1e30);
607  btScalar maxDist = threshold;
608 
609  bool foundSepAxis = false;
610  bool useSatSepNormal = true;
611 
612  if (useSatSepNormal)
613  {
614 #if 0 // NOLINT
615  if (0)
616  {
617  //initializePolyhedralFeatures performs a convex hull computation, not needed for a single triangle
618  polyhedronB->initializePolyhedralFeatures();
619  } else
620 #endif
621  {
622  btVector3 uniqueEdges[3] = { tri->m_vertices1[1] - tri->m_vertices1[0], // NOLINT
623  tri->m_vertices1[2] - tri->m_vertices1[1],
624  tri->m_vertices1[0] - tri->m_vertices1[2] };
625 
626  uniqueEdges[0].normalize();
627  uniqueEdges[1].normalize();
628  uniqueEdges[2].normalize();
629 
630  btConvexPolyhedron polyhedron;
631  polyhedron.m_vertices.push_back(tri->m_vertices1[2]);
632  polyhedron.m_vertices.push_back(tri->m_vertices1[0]);
633  polyhedron.m_vertices.push_back(tri->m_vertices1[1]);
634 
635  {
636  btFace combinedFaceA;
637  combinedFaceA.m_indices.push_back(0);
638  combinedFaceA.m_indices.push_back(1);
639  combinedFaceA.m_indices.push_back(2);
640  btVector3 faceNormal = uniqueEdges[0].cross(uniqueEdges[1]);
641  faceNormal.normalize();
642  auto planeEq = btScalar(1e30);
643  for (int v = 0; v < combinedFaceA.m_indices.size(); v++)
644  {
645  btScalar eq = tri->m_vertices1[combinedFaceA.m_indices[v]].dot(faceNormal);
646  planeEq = std::min(planeEq, eq);
647  }
648  combinedFaceA.m_plane[0] = faceNormal[0];
649  combinedFaceA.m_plane[1] = faceNormal[1];
650  combinedFaceA.m_plane[2] = faceNormal[2];
651  combinedFaceA.m_plane[3] = -planeEq;
652  polyhedron.m_faces.push_back(combinedFaceA);
653  }
654  {
655  btFace combinedFaceB;
656  combinedFaceB.m_indices.push_back(0);
657  combinedFaceB.m_indices.push_back(2);
658  combinedFaceB.m_indices.push_back(1);
659  btVector3 faceNormal = -uniqueEdges[0].cross(uniqueEdges[1]);
660  faceNormal.normalize();
661  auto planeEq = btScalar(1e30);
662  for (int v = 0; v < combinedFaceB.m_indices.size(); v++)
663  {
664  btScalar eq = tri->m_vertices1[combinedFaceB.m_indices[v]].dot(faceNormal);
665  planeEq = std::min(planeEq, eq);
666  }
667 
668  combinedFaceB.m_plane[0] = faceNormal[0];
669  combinedFaceB.m_plane[1] = faceNormal[1];
670  combinedFaceB.m_plane[2] = faceNormal[2];
671  combinedFaceB.m_plane[3] = -planeEq;
672  polyhedron.m_faces.push_back(combinedFaceB);
673  }
674 
675  polyhedron.m_uniqueEdges.push_back(uniqueEdges[0]);
676  polyhedron.m_uniqueEdges.push_back(uniqueEdges[1]);
677  polyhedron.m_uniqueEdges.push_back(uniqueEdges[2]);
678  polyhedron.initialize2();
679 
680  polyhedronB->setPolyhedralFeatures(polyhedron);
681  }
682 
683  foundSepAxis = btPolyhedralContactClipping::findSeparatingAxis(*polyhedronA->getConvexPolyhedron(),
684  *polyhedronB->getConvexPolyhedron(),
685  body0Wrap->getWorldTransform(),
686  body1Wrap->getWorldTransform(),
687  sepNormalWorldSpace,
688  *resultOut);
689  // printf("sepNormalWorldSpace=%f,%f,%f\n",sepNormalWorldSpace.getX(),sepNormalWorldSpace.getY(),sepNormalWorldSpace.getZ());
690  }
691  else
692  {
693 #ifdef ZERO_MARGIN
694  gjkPairDetector.setIgnoreMargin(true);
695  gjkPairDetector.getClosestPoints(input, *resultOut, dispatchInfo.m_debugDraw);
696 #else
697  gjkPairDetector.getClosestPoints(input, dummy, dispatchInfo.m_debugDraw);
698 #endif // ZERO_MARGIN
699 
700  if (dummy.m_hasContact && dummy.m_depth < 0)
701  {
702  if (foundSepAxis)
703  {
704  if (dummy.m_normalOnBInWorld.dot(sepNormalWorldSpace) < 0.99)
705  {
706  printf("?\n");
707  }
708  }
709  else
710  {
711  printf("!\n");
712  }
713  sepNormalWorldSpace.setValue(0, 0, 1); // = dummy.m_normalOnBInWorld;
714  // minDist = dummy.m_depth;
715  foundSepAxis = true;
716  }
717 #if 0 // NOLINT
718  btScalar l2 = gjkPairDetector.getCachedSeparatingAxis().length2();
719  if (l2>SIMD_EPSILON)
720  {
721  sepNormalWorldSpace = gjkPairDetector.getCachedSeparatingAxis()*(1.f/l2);
722  //minDist = gjkPairDetector.getCachedSeparatingDistance();
723  //maxDist = threshold;
724  minDist = gjkPairDetector.getCachedSeparatingDistance()-min0->getMargin()-min1->getMargin();
725  foundSepAxis = true;
726  }
727 #endif
728  }
729 
730  if (foundSepAxis)
731  {
732  worldVertsB2.resize(0);
733  btPolyhedralContactClipping::clipFaceAgainstHull(sepNormalWorldSpace,
734  *polyhedronA->getConvexPolyhedron(),
735  body0Wrap->getWorldTransform(),
736  worldSpaceVertices,
737  worldVertsB2,
738  minDist - threshold,
739  maxDist,
740  *resultOut);
741  }
742 
743  if (m_ownManifold)
744  {
745  resultOut->refreshContactPoints();
746  }
747 
748  return;
749  }
750  }
751  }
752 
753  gjkPairDetector.getClosestPoints(input, *resultOut, dispatchInfo.m_debugDraw);
754 
755  // now perform 'm_numPerturbationIterations' collision queries with the perturbated collision objects
756 
757  // perform perturbation when more then 'm_minimumPointsPerturbationThreshold' points
758  if (m_numPerturbationIterations != 0 &&
759  resultOut->getPersistentManifold()->getNumContacts() < m_minimumPointsPerturbationThreshold)
760  {
761  btVector3 v0, v1;
762  btVector3 sepNormalWorldSpace;
763  btScalar l2 = gjkPairDetector.getCachedSeparatingAxis().length2();
764 
765  if (l2 > SIMD_EPSILON)
766  {
767  sepNormalWorldSpace = gjkPairDetector.getCachedSeparatingAxis() * (btScalar(1.) / l2);
768 
769  btPlaneSpace1(sepNormalWorldSpace, v0, v1);
770 
771  bool perturbeA = true;
772  const btScalar angleLimit = btScalar(0.125) * SIMD_PI;
773  btScalar perturbeAngle{ std::numeric_limits<btScalar>::max() };
774  btScalar radiusA = min0->getAngularMotionDisc();
775  btScalar radiusB = min1->getAngularMotionDisc();
776  if (radiusA < radiusB)
777  {
778  perturbeAngle = gContactBreakingThreshold / radiusA;
779  perturbeA = true;
780  }
781  else
782  {
783  perturbeAngle = gContactBreakingThreshold / radiusB;
784  perturbeA = false;
785  }
786  perturbeAngle = std::min(perturbeAngle, angleLimit);
787 
788  btTransform unPerturbedTransform;
789  if (perturbeA)
790  {
791  unPerturbedTransform = input.m_transformA;
792  }
793  else
794  {
795  unPerturbedTransform = input.m_transformB;
796  }
797 
798  for (int i = 0; i < m_numPerturbationIterations; i++)
799  {
800  if (v0.length2() > SIMD_EPSILON)
801  {
802  btQuaternion perturbeRot(v0, perturbeAngle);
803  btScalar iterationAngle = (btScalar(i) * (SIMD_2_PI / btScalar(m_numPerturbationIterations)));
804  btQuaternion rotq(sepNormalWorldSpace, iterationAngle);
805 
806  if (perturbeA)
807  {
808  input.m_transformA.setBasis(btMatrix3x3(rotq.inverse() * perturbeRot * rotq) *
809  body0Wrap->getWorldTransform().getBasis());
810  input.m_transformB = body1Wrap->getWorldTransform();
811 #ifdef DEBUG_CONTACTS
812  dispatchInfo.m_debugDraw->drawTransform(input.m_transformA, 10.0);
813 #endif // DEBUG_CONTACTS
814  }
815  else
816  {
817  input.m_transformA = body0Wrap->getWorldTransform();
818  input.m_transformB.setBasis(btMatrix3x3(rotq.inverse() * perturbeRot * rotq) *
819  body1Wrap->getWorldTransform().getBasis());
820 #ifdef DEBUG_CONTACTS
821  dispatchInfo.m_debugDraw->drawTransform(input.m_transformB, 10.0);
822 #endif
823  }
824 
825  btPerturbedContactResult perturbedResultOut(resultOut,
826  input.m_transformA,
827  input.m_transformB,
828  unPerturbedTransform,
829  perturbeA,
830  dispatchInfo.m_debugDraw);
831  gjkPairDetector.getClosestPoints(input, perturbedResultOut, dispatchInfo.m_debugDraw);
832  }
833  }
834  }
835  }
836 
837 #ifdef USE_SEPDISTANCE_UTIL2
838  if (dispatchInfo.m_useConvexConservativeDistanceUtil && (sepDist > SIMD_EPSILON))
839  {
840  m_sepDistance.initSeparatingDistance(
841  gjkPairDetector.getCachedSeparatingAxis(), sepDist, body0->getWorldTransform(), body1->getWorldTransform());
842  }
843 #endif // USE_SEPDISTANCE_UTIL2
844  }
845 
846  if (m_ownManifold)
847  {
848  resultOut->refreshContactPoints();
849  }
850 }
851 
852 static const bool disableCcd = false;
854  btCollisionObject* body1,
855  const btDispatcherInfo& dispatchInfo,
856  btManifoldResult* resultOut)
857 {
858  (void)resultOut;
859  (void)dispatchInfo;
861 
864  auto resultFraction = btScalar(1.);
865 
866  btScalar squareMot0 =
867  (body0->getInterpolationWorldTransform().getOrigin() - body0->getWorldTransform().getOrigin()).length2();
868  btScalar squareMot1 =
869  (body1->getInterpolationWorldTransform().getOrigin() - body1->getWorldTransform().getOrigin()).length2();
870 
871  if (squareMot0 < body0->getCcdSquareMotionThreshold() && squareMot1 < body1->getCcdSquareMotionThreshold())
872  return resultFraction;
873 
874  if (disableCcd)
875  return btScalar(1.);
876 
877  // An adhoc way of testing the Continuous Collision Detection algorithms
878  // One object is approximated as a sphere, to simplify things
879  // Starting in penetration should report no time of impact
880  // For proper CCD, better accuracy and handling of 'allowed' penetration should be added
881  // also the mainloop of the physics should have a kind of toi queue (something like Brian Mirtich's application of
882  // Timewarp for Rigidbodies)
883 
885  {
886  auto* convex0 = static_cast<btConvexShape*>(body0->getCollisionShape());
887 
888  btSphereShape sphere1(body1->getCcdSweptSphereRadius()); // todo: allow non-zero sphere sizes, for better
889  // approximation
890  btConvexCast::CastResult result;
891  btVoronoiSimplexSolver voronoiSimplex;
892  // SubsimplexConvexCast ccd0(&sphere,min0,&voronoiSimplex);
894  btGjkConvexCast ccd1(convex0, &sphere1, &voronoiSimplex);
895  // ContinuousConvexCollision ccd(min0,min1,&voronoiSimplex,0);
896  if (ccd1.calcTimeOfImpact(body0->getWorldTransform(),
897  body0->getInterpolationWorldTransform(),
898  body1->getWorldTransform(),
899  body1->getInterpolationWorldTransform(),
900  result))
901  {
902  // store result.m_fraction in both bodies
903 
904  if (body0->getHitFraction() > result.m_fraction)
905  body0->setHitFraction(result.m_fraction);
906 
907  if (body1->getHitFraction() > result.m_fraction)
908  body1->setHitFraction(result.m_fraction);
909 
910  resultFraction = std::min(resultFraction, result.m_fraction);
911  }
912  }
913 
915  {
916  auto* convex1 = static_cast<btConvexShape*>(body1->getCollisionShape());
917 
918  btSphereShape sphere0(body0->getCcdSweptSphereRadius()); // todo: allow non-zero sphere sizes, for better
919  // approximation
920  btConvexCast::CastResult result;
921  btVoronoiSimplexSolver voronoiSimplex;
922  // SubsimplexConvexCast ccd0(&sphere,min0,&voronoiSimplex);
924  btGjkConvexCast ccd1(&sphere0, convex1, &voronoiSimplex);
925  // ContinuousConvexCollision ccd(min0,min1,&voronoiSimplex,0);
926  if (ccd1.calcTimeOfImpact(body0->getWorldTransform(),
927  body0->getInterpolationWorldTransform(),
928  body1->getWorldTransform(),
929  body1->getInterpolationWorldTransform(),
930  result))
931  {
932  // store result.m_fraction in both bodies
933 
934  if (body0->getHitFraction() > result.m_fraction)
935  body0->setHitFraction(result.m_fraction);
936 
937  if (body1->getHitFraction() > result.m_fraction)
938  body1->setHitFraction(result.m_fraction);
939 
940  resultFraction = std::min(resultFraction, result.m_fraction);
941  }
942  }
943 
944  return resultFraction;
945 }
946 } // namespace tesseract_collision::tesseract_collision_bullet
947 // LCOV_EXCL_STOP
tesseract_collision::tesseract_collision_bullet::TesseractGjkPairDetector::getClosestPoints
void getClosestPoints(const ClosestPointInput &input, Result &output, class btIDebugDraw *debugDraw, bool swapResults=false) override
Definition: tesseract_gjk_pair_detector.cpp:93
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::setLowLevelOfDetail
void setLowLevelOfDetail(bool useLowLevel)
Definition: tesseract_convex_convex_algorithm.cpp:222
tesseract_collision::tesseract_collision_bullet
Definition: bullet_cast_bvh_manager.h:48
tesseract_collision::ContactTestData
This data is intended only to be used internal to the collision checkers as a container and should no...
Definition: types.h:328
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::m_manifoldPtr
btPersistentManifold * m_manifoldPtr
Definition: tesseract_convex_convex_algorithm.h:76
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult::m_perturbA
bool m_perturbA
Definition: tesseract_convex_convex_algorithm.cpp:230
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::calculateTimeOfImpact
btScalar calculateTimeOfImpact(btCollisionObject *body0, btCollisionObject *body1, const btDispatcherInfo &dispatchInfo, btManifoldResult *resultOut) override
Definition: tesseract_convex_convex_algorithm.cpp:853
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::m_numPerturbationIterations
int m_numPerturbationIterations
Definition: tesseract_convex_convex_algorithm.h:79
tesseract_gjk_pair_detector.h
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult::m_transformA
btTransform m_transformA
Definition: tesseract_convex_convex_algorithm.cpp:227
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_collision::tesseract_collision_bullet::segmentsClosestPoints
static SIMD_FORCE_INLINE void segmentsClosestPoints(btVector3 &ptsVector, btVector3 &offsetA, btVector3 &offsetB, btScalar &tA, btScalar &tB, const btVector3 &translation, const btVector3 &dirA, btScalar hlenA, const btVector3 &dirB, btScalar hlenB)
Definition: tesseract_convex_convex_algorithm.cpp:65
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::~TesseractConvexConvexAlgorithm
~TesseractConvexConvexAlgorithm() override
Definition: tesseract_convex_convex_algorithm.cpp:213
tesseract_collision::tesseract_collision_bullet::TesseractGjkPairDetector::getCachedSeparatingDistance
btScalar getCachedSeparatingDistance() const
Definition: tesseract_gjk_pair_detector.h:104
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::m_cdata
ContactTestData * m_cdata
Definition: tesseract_convex_convex_algorithm.h:82
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::TesseractConvexConvexAlgorithm
TesseractConvexConvexAlgorithm(btPersistentManifold *mf, const btCollisionAlgorithmConstructionInfo &ci, const btCollisionObjectWrapper *body0Wrap, const btCollisionObjectWrapper *body1Wrap, btConvexPenetrationDepthSolver *pdSolver, int numPerturbationIterations, int minimumPointsPerturbationThreshold)
cache separating vector to speedup collision detection
Definition: tesseract_convex_convex_algorithm.cpp:188
tesseract_collision::tesseract_collision_bullet::capsuleCapsuleDistance
static SIMD_FORCE_INLINE btScalar capsuleCapsuleDistance(btVector3 &normalOnB, btVector3 &pointOnB, btScalar capsuleLengthA, btScalar capsuleRadiusA, btScalar capsuleLengthB, btScalar capsuleRadiusB, int capsuleAxisA, int capsuleAxisB, const btTransform &transformA, const btTransform &transformB, btScalar distanceThreshold)
Definition: tesseract_convex_convex_algorithm.cpp:128
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::worldVertsB2
btVertexArray worldVertsB2
Definition: tesseract_convex_convex_algorithm.h:73
tesseract_collision::tesseract_collision_bullet::TesseractGjkPairDetector::setMinkowskiB
void setMinkowskiB(const btConvexShape *minkB)
Definition: tesseract_gjk_pair_detector.h:100
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::CreateFunc::CreateFunc
CreateFunc(btConvexPenetrationDepthSolver *pdSolver)
Definition: tesseract_convex_convex_algorithm.cpp:184
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::m_minimumPointsPerturbationThreshold
int m_minimumPointsPerturbationThreshold
Definition: tesseract_convex_convex_algorithm.h:80
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::m_pdSolver
btConvexPenetrationDepthSolver * m_pdSolver
Definition: tesseract_convex_convex_algorithm.h:70
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult::m_unPerturbedTransform
btTransform m_unPerturbedTransform
Definition: tesseract_convex_convex_algorithm.cpp:229
TESSERACT_COMMON_IGNORE_WARNINGS_POP
Definition: create_convex_hull.cpp:37
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
tesseract_convex_convex_algorithm.h
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult::addContactPoint
void addContactPoint(const btVector3 &normalOnBInWorld, const btVector3 &pointInWorld, btScalar orgDepth) override
Definition: tesseract_convex_convex_algorithm.cpp:249
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult
Definition: tesseract_convex_convex_algorithm.cpp:224
tesseract_collision::tesseract_collision_bullet::TesseractGjkPairDetector::getCachedSeparatingAxis
const btVector3 & getCachedSeparatingAxis() const
Definition: tesseract_gjk_pair_detector.h:103
tesseract_collision::tesseract_collision_bullet::TesseractGjkPairDetector::setIgnoreMargin
void setIgnoreMargin(bool ignoreMargin)
don't use setIgnoreMargin, it's for Bullet's internal use
Definition: tesseract_gjk_pair_detector.h:112
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::processCollision
void processCollision(const btCollisionObjectWrapper *body0Wrap, const btCollisionObjectWrapper *body1Wrap, const btDispatcherInfo &dispatchInfo, btManifoldResult *resultOut) override
Definition: tesseract_convex_convex_algorithm.cpp:283
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::m_lowLevelOfDetail
bool m_lowLevelOfDetail
Definition: tesseract_convex_convex_algorithm.h:77
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult::m_originalManifoldResult
btManifoldResult * m_originalManifoldResult
Definition: tesseract_convex_convex_algorithm.cpp:226
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::worldVertsB1
btVertexArray worldVertsB1
Definition: tesseract_convex_convex_algorithm.h:72
tesseract_collision::tesseract_collision_bullet::disableCcd
static const bool disableCcd
Definition: tesseract_convex_convex_algorithm.cpp:852
gContactBreakingThreshold
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH TESSERACT_COMMON_IGNORE_WARNINGS_POP btScalar gContactBreakingThreshold
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult::m_transformB
btTransform m_transformB
Definition: tesseract_convex_convex_algorithm.cpp:228
tesseract_collision::tesseract_collision_bullet::TesseractConvexConvexAlgorithm::m_ownManifold
bool m_ownManifold
Definition: tesseract_convex_convex_algorithm.h:75
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult::btPerturbedContactResult
btPerturbedContactResult(btManifoldResult *originalResult, const btTransform &transformA, const btTransform &transformB, const btTransform &unPerturbedTransform, bool perturbA, btIDebugDraw *debugDrawer)
Definition: tesseract_convex_convex_algorithm.cpp:233
tesseract_collision::tesseract_collision_bullet::TesseractGjkPairDetector::setMinkowskiA
void setMinkowskiA(const btConvexShape *minkA)
Definition: tesseract_gjk_pair_detector.h:98
tesseract_collision::tesseract_collision_bullet::TesseractGjkPairDetector
This is a modifed Convex to Convex collision algorithm.
Definition: tesseract_gjk_pair_detector.h:50
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult::~btPerturbedContactResult
~btPerturbedContactResult() override=default
tesseract_collision::tesseract_collision_bullet::btPerturbedContactResult::m_debugDrawer
btIDebugDraw * m_debugDrawer
Definition: tesseract_convex_convex_algorithm.cpp:231


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:52