Bullet Collision Detection & Physics Library
btInternalEdgeUtility.cpp
Go to the documentation of this file.
2 
10 
11 //#define DEBUG_INTERNAL_EDGE
12 
13 #ifdef DEBUG_INTERNAL_EDGE
14 #include <stdio.h>
15 #endif //DEBUG_INTERNAL_EDGE
16 
17 
18 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
19 static btIDebugDraw* gDebugDrawer = 0;
20 
21 void btSetDebugDrawer(btIDebugDraw* debugDrawer)
22 {
23  gDebugDrawer = debugDrawer;
24 }
25 
26 static void btDebugDrawLine(const btVector3& from,const btVector3& to, const btVector3& color)
27 {
28  if (gDebugDrawer)
29  gDebugDrawer->drawLine(from,to,color);
30 }
31 #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
32 
33 
34 static int btGetHash(int partId, int triangleIndex)
35 {
36  int hash = (partId<<(31-MAX_NUM_PARTS_IN_BITS)) | triangleIndex;
37  return hash;
38 }
39 
40 
41 
42 static btScalar btGetAngle(const btVector3& edgeA, const btVector3& normalA,const btVector3& normalB)
43 {
44  const btVector3 refAxis0 = edgeA;
45  const btVector3 refAxis1 = normalA;
46  const btVector3 swingAxis = normalB;
47  btScalar angle = btAtan2(swingAxis.dot(refAxis0), swingAxis.dot(refAxis1));
48  return angle;
49 }
50 
51 
53 {
54  int m_partIdA;
58 
59 
60  virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex)
61  {
62  //skip self-collisions
63  if ((m_partIdA == partId) && (m_triangleIndexA == triangleIndex))
64  return;
65 
66  //skip duplicates (disabled for now)
67  //if ((m_partIdA <= partId) && (m_triangleIndexA <= triangleIndex))
68  // return;
69 
70  //search for shared vertices and edges
71  int numshared = 0;
72  int sharedVertsA[3]={-1,-1,-1};
73  int sharedVertsB[3]={-1,-1,-1};
74 
76  btScalar crossBSqr = ((triangle[1]-triangle[0]).cross(triangle[2]-triangle[0])).length2();
77  if (crossBSqr < m_triangleInfoMap->m_equalVertexThreshold)
78  return;
79 
80 
81  btScalar crossASqr = ((m_triangleVerticesA[1]-m_triangleVerticesA[0]).cross(m_triangleVerticesA[2]-m_triangleVerticesA[0])).length2();
83  if (crossASqr< m_triangleInfoMap->m_equalVertexThreshold)
84  return;
85 
86 #if 0
87  printf("triangle A[0] = (%f,%f,%f)\ntriangle A[1] = (%f,%f,%f)\ntriangle A[2] = (%f,%f,%f)\n",
88  m_triangleVerticesA[0].getX(),m_triangleVerticesA[0].getY(),m_triangleVerticesA[0].getZ(),
89  m_triangleVerticesA[1].getX(),m_triangleVerticesA[1].getY(),m_triangleVerticesA[1].getZ(),
90  m_triangleVerticesA[2].getX(),m_triangleVerticesA[2].getY(),m_triangleVerticesA[2].getZ());
91 
92  printf("partId=%d, triangleIndex=%d\n",partId,triangleIndex);
93  printf("triangle B[0] = (%f,%f,%f)\ntriangle B[1] = (%f,%f,%f)\ntriangle B[2] = (%f,%f,%f)\n",
94  triangle[0].getX(),triangle[0].getY(),triangle[0].getZ(),
95  triangle[1].getX(),triangle[1].getY(),triangle[1].getZ(),
96  triangle[2].getX(),triangle[2].getY(),triangle[2].getZ());
97 #endif
98 
99  for (int i=0;i<3;i++)
100  {
101  for (int j=0;j<3;j++)
102  {
103  if ( (m_triangleVerticesA[i]-triangle[j]).length2() < m_triangleInfoMap->m_equalVertexThreshold)
104  {
105  sharedVertsA[numshared] = i;
106  sharedVertsB[numshared] = j;
107  numshared++;
109  if(numshared >= 3)
110  return;
111  }
112  }
114  if(numshared >= 3)
115  return;
116  }
117  switch (numshared)
118  {
119  case 0:
120  {
121  break;
122  }
123  case 1:
124  {
125  //shared vertex
126  break;
127  }
128  case 2:
129  {
130  //shared edge
131  //we need to make sure the edge is in the order V2V0 and not V0V2 so that the signs are correct
132  if (sharedVertsA[0] == 0 && sharedVertsA[1] == 2)
133  {
134  sharedVertsA[0] = 2;
135  sharedVertsA[1] = 0;
136  int tmp = sharedVertsB[1];
137  sharedVertsB[1] = sharedVertsB[0];
138  sharedVertsB[0] = tmp;
139  }
140 
141  int hash = btGetHash(m_partIdA,m_triangleIndexA);
142 
143  btTriangleInfo* info = m_triangleInfoMap->find(hash);
144  if (!info)
145  {
146  btTriangleInfo tmp;
147  m_triangleInfoMap->insert(hash,tmp);
148  info = m_triangleInfoMap->find(hash);
149  }
150 
151  int sumvertsA = sharedVertsA[0]+sharedVertsA[1];
152  int otherIndexA = 3-sumvertsA;
153 
154 
155  btVector3 edge(m_triangleVerticesA[sharedVertsA[1]]-m_triangleVerticesA[sharedVertsA[0]]);
156 
157  btTriangleShape tA(m_triangleVerticesA[0],m_triangleVerticesA[1],m_triangleVerticesA[2]);
158  int otherIndexB = 3-(sharedVertsB[0]+sharedVertsB[1]);
159 
160  btTriangleShape tB(triangle[sharedVertsB[1]],triangle[sharedVertsB[0]],triangle[otherIndexB]);
161  //btTriangleShape tB(triangle[0],triangle[1],triangle[2]);
162 
163  btVector3 normalA;
164  btVector3 normalB;
165  tA.calcNormal(normalA);
166  tB.calcNormal(normalB);
167  edge.normalize();
168  btVector3 edgeCrossA = edge.cross(normalA).normalize();
169 
170  {
171  btVector3 tmp = m_triangleVerticesA[otherIndexA]-m_triangleVerticesA[sharedVertsA[0]];
172  if (edgeCrossA.dot(tmp) < 0)
173  {
174  edgeCrossA*=-1;
175  }
176  }
177 
178  btVector3 edgeCrossB = edge.cross(normalB).normalize();
179 
180  {
181  btVector3 tmp = triangle[otherIndexB]-triangle[sharedVertsB[0]];
182  if (edgeCrossB.dot(tmp) < 0)
183  {
184  edgeCrossB*=-1;
185  }
186  }
187 
188  btScalar angle2 = 0;
189  btScalar ang4 = 0.f;
190 
191 
192  btVector3 calculatedEdge = edgeCrossA.cross(edgeCrossB);
193  btScalar len2 = calculatedEdge.length2();
194 
195  btScalar correctedAngle(0);
196  //btVector3 calculatedNormalB = normalA;
197  bool isConvex = false;
198 
199  if (len2<m_triangleInfoMap->m_planarEpsilon)
200  {
201  angle2 = 0.f;
202  ang4 = 0.f;
203  } else
204  {
205 
206  calculatedEdge.normalize();
207  btVector3 calculatedNormalA = calculatedEdge.cross(edgeCrossA);
208  calculatedNormalA.normalize();
209  angle2 = btGetAngle(calculatedNormalA,edgeCrossA,edgeCrossB);
210  ang4 = SIMD_PI-angle2;
211  btScalar dotA = normalA.dot(edgeCrossB);
213  isConvex = (dotA<0.);
214 
215  correctedAngle = isConvex ? ang4 : -ang4;
216  }
217 
218 
219 
220 
221 
222  //alternatively use
223  //btVector3 calculatedNormalB2 = quatRotate(orn,normalA);
224 
225 
226  switch (sumvertsA)
227  {
228  case 1:
229  {
230  btVector3 edge = m_triangleVerticesA[0]-m_triangleVerticesA[1];
231  btQuaternion orn(edge,-correctedAngle);
232  btVector3 computedNormalB = quatRotate(orn,normalA);
233  btScalar bla = computedNormalB.dot(normalB);
234  if (bla<0)
235  {
236  computedNormalB*=-1;
238  }
239 #ifdef DEBUG_INTERNAL_EDGE
240  if ((computedNormalB-normalB).length()>0.0001)
241  {
242  printf("warning: normals not identical\n");
243  }
244 #endif//DEBUG_INTERNAL_EDGE
245 
246  info->m_edgeV0V1Angle = -correctedAngle;
247 
248  if (isConvex)
249  info->m_flags |= TRI_INFO_V0V1_CONVEX;
250  break;
251  }
252  case 2:
253  {
254  btVector3 edge = m_triangleVerticesA[2]-m_triangleVerticesA[0];
255  btQuaternion orn(edge,-correctedAngle);
256  btVector3 computedNormalB = quatRotate(orn,normalA);
257  if (computedNormalB.dot(normalB)<0)
258  {
259  computedNormalB*=-1;
261  }
262 
263 #ifdef DEBUG_INTERNAL_EDGE
264  if ((computedNormalB-normalB).length()>0.0001)
265  {
266  printf("warning: normals not identical\n");
267  }
268 #endif //DEBUG_INTERNAL_EDGE
269  info->m_edgeV2V0Angle = -correctedAngle;
270  if (isConvex)
271  info->m_flags |= TRI_INFO_V2V0_CONVEX;
272  break;
273  }
274  case 3:
275  {
276  btVector3 edge = m_triangleVerticesA[1]-m_triangleVerticesA[2];
277  btQuaternion orn(edge,-correctedAngle);
278  btVector3 computedNormalB = quatRotate(orn,normalA);
279  if (computedNormalB.dot(normalB)<0)
280  {
282  computedNormalB*=-1;
283  }
284 #ifdef DEBUG_INTERNAL_EDGE
285  if ((computedNormalB-normalB).length()>0.0001)
286  {
287  printf("warning: normals not identical\n");
288  }
289 #endif //DEBUG_INTERNAL_EDGE
290  info->m_edgeV1V2Angle = -correctedAngle;
291 
292  if (isConvex)
293  info->m_flags |= TRI_INFO_V1V2_CONVEX;
294  break;
295  }
296  }
297 
298  break;
299  }
300  default:
301  {
302  // printf("warning: duplicate triangle\n");
303  }
304 
305  }
306  }
307 };
310 
312 {
313  //the user pointer shouldn't already be used for other purposes, we intend to store connectivity info there!
314  if (trimeshShape->getTriangleInfoMap())
315  return;
316 
317  trimeshShape->setTriangleInfoMap(triangleInfoMap);
318 
319  btStridingMeshInterface* meshInterface = trimeshShape->getMeshInterface();
320  const btVector3& meshScaling = meshInterface->getScaling();
321 
322  for (int partId = 0; partId< meshInterface->getNumSubParts();partId++)
323  {
324  const unsigned char *vertexbase = 0;
325  int numverts = 0;
327  int stride = 0;
328  const unsigned char *indexbase = 0;
329  int indexstride = 0;
330  int numfaces = 0;
331  PHY_ScalarType indicestype = PHY_INTEGER;
332  //PHY_ScalarType indexType=0;
333 
334  btVector3 triangleVerts[3];
335  meshInterface->getLockedReadOnlyVertexIndexBase(&vertexbase,numverts, type,stride,&indexbase,indexstride,numfaces,indicestype,partId);
336  btVector3 aabbMin,aabbMax;
337 
338  for (int triangleIndex = 0 ; triangleIndex < numfaces;triangleIndex++)
339  {
340  unsigned int* gfxbase = (unsigned int*)(indexbase+triangleIndex*indexstride);
341 
342  for (int j=2;j>=0;j--)
343  {
344 
345  int graphicsindex = indicestype==PHY_SHORT?((unsigned short*)gfxbase)[j]:gfxbase[j];
346  if (type == PHY_FLOAT)
347  {
348  float* graphicsbase = (float*)(vertexbase+graphicsindex*stride);
349  triangleVerts[j] = btVector3(
350  graphicsbase[0]*meshScaling.getX(),
351  graphicsbase[1]*meshScaling.getY(),
352  graphicsbase[2]*meshScaling.getZ());
353  }
354  else
355  {
356  double* graphicsbase = (double*)(vertexbase+graphicsindex*stride);
357  triangleVerts[j] = btVector3( btScalar(graphicsbase[0]*meshScaling.getX()), btScalar(graphicsbase[1]*meshScaling.getY()), btScalar(graphicsbase[2]*meshScaling.getZ()));
358  }
359  }
362  aabbMin.setMin(triangleVerts[0]);
363  aabbMax.setMax(triangleVerts[0]);
364  aabbMin.setMin(triangleVerts[1]);
365  aabbMax.setMax(triangleVerts[1]);
366  aabbMin.setMin(triangleVerts[2]);
367  aabbMax.setMax(triangleVerts[2]);
368 
369  btConnectivityProcessor connectivityProcessor;
370  connectivityProcessor.m_partIdA = partId;
371  connectivityProcessor.m_triangleIndexA = triangleIndex;
372  connectivityProcessor.m_triangleVerticesA = &triangleVerts[0];
373  connectivityProcessor.m_triangleInfoMap = triangleInfoMap;
374 
375  trimeshShape->processAllTriangles(&connectivityProcessor,aabbMin,aabbMax);
376  }
377 
378  }
379 
380 }
381 
382 
383 
384 
385 // Given a point and a line segment (defined by two points), compute the closest point
386 // in the line. Cap the point at the endpoints of the line segment.
387 void btNearestPointInLineSegment(const btVector3 &point, const btVector3& line0, const btVector3& line1, btVector3& nearestPoint)
388 {
389  btVector3 lineDelta = line1 - line0;
390 
391  // Handle degenerate lines
392  if ( lineDelta.fuzzyZero())
393  {
394  nearestPoint = line0;
395  }
396  else
397  {
398  btScalar delta = (point-line0).dot(lineDelta) / (lineDelta).dot(lineDelta);
399 
400  // Clamp the point to conform to the segment's endpoints
401  if ( delta < 0 )
402  delta = 0;
403  else if ( delta > 1 )
404  delta = 1;
405 
406  nearestPoint = line0 + lineDelta*delta;
407  }
408 }
409 
410 
411 
412 
413 bool btClampNormal(const btVector3& edge,const btVector3& tri_normal_org,const btVector3& localContactNormalOnB, btScalar correctedEdgeAngle, btVector3 & clampedLocalNormal)
414 {
415  btVector3 tri_normal = tri_normal_org;
416  //we only have a local triangle normal, not a local contact normal -> only normal in world space...
417  //either compute the current angle all in local space, or all in world space
418 
419  btVector3 edgeCross = edge.cross(tri_normal).normalize();
420  btScalar curAngle = btGetAngle(edgeCross,tri_normal,localContactNormalOnB);
421 
422  if (correctedEdgeAngle<0)
423  {
424  if (curAngle < correctedEdgeAngle)
425  {
426  btScalar diffAngle = correctedEdgeAngle-curAngle;
427  btQuaternion rotation(edge,diffAngle );
428  clampedLocalNormal = btMatrix3x3(rotation)*localContactNormalOnB;
429  return true;
430  }
431  }
432 
433  if (correctedEdgeAngle>=0)
434  {
435  if (curAngle > correctedEdgeAngle)
436  {
437  btScalar diffAngle = correctedEdgeAngle-curAngle;
438  btQuaternion rotation(edge,diffAngle );
439  clampedLocalNormal = btMatrix3x3(rotation)*localContactNormalOnB;
440  return true;
441  }
442  }
443  return false;
444 }
445 
446 
447 
449 void btAdjustInternalEdgeContacts(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,const btCollisionObjectWrapper* colObj1Wrap, int partId0, int index0, int normalAdjustFlags)
450 {
451  //btAssert(colObj0->getCollisionShape()->getShapeType() == TRIANGLE_SHAPE_PROXYTYPE);
453  return;
454 
455  btBvhTriangleMeshShape* trimesh = 0;
456 
458  {
459  trimesh = ((btScaledBvhTriangleMeshShape*)colObj0Wrap->getCollisionObject()->getCollisionShape())->getChildShape();
460  }
461  else
462  {
464  {
465  trimesh = (btBvhTriangleMeshShape*)colObj0Wrap->getCollisionObject()->getCollisionShape();
466  }
467  }
468  if (trimesh==0)
469  return;
470 
471  btTriangleInfoMap* triangleInfoMapPtr = (btTriangleInfoMap*) trimesh->getTriangleInfoMap();
472  if (!triangleInfoMapPtr)
473  return;
474 
475  int hash = btGetHash(partId0,index0);
476 
477 
478  btTriangleInfo* info = triangleInfoMapPtr->find(hash);
479  if (!info)
480  return;
481 
482  btScalar frontFacing = (normalAdjustFlags & BT_TRIANGLE_CONVEX_BACKFACE_MODE)==0? 1.f : -1.f;
483 
484  const btTriangleShape* tri_shape = static_cast<const btTriangleShape*>(colObj0Wrap->getCollisionShape());
485  btVector3 v0,v1,v2;
486  tri_shape->getVertex(0,v0);
487  tri_shape->getVertex(1,v1);
488  tri_shape->getVertex(2,v2);
489 
490  //btVector3 center = (v0+v1+v2)*btScalar(1./3.);
491 
492  btVector3 red(1,0,0), green(0,1,0),blue(0,0,1),white(1,1,1),black(0,0,0);
493  btVector3 tri_normal;
494  tri_shape->calcNormal(tri_normal);
495 
496  //btScalar dot = tri_normal.dot(cp.m_normalWorldOnB);
497  btVector3 nearest;
498  btNearestPointInLineSegment(cp.m_localPointB,v0,v1,nearest);
499 
500  btVector3 contact = cp.m_localPointB;
501 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
502  const btTransform& tr = colObj0->getWorldTransform();
503  btDebugDrawLine(tr*nearest,tr*cp.m_localPointB,red);
504 #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
505 
506 
507 
508  bool isNearEdge = false;
509 
510  int numConcaveEdgeHits = 0;
511  int numConvexEdgeHits = 0;
512 
513  btVector3 localContactNormalOnB = colObj0Wrap->getWorldTransform().getBasis().transpose() * cp.m_normalWorldOnB;
514  localContactNormalOnB.normalize();//is this necessary?
515 
516  // Get closest edge
517  int bestedge=-1;
518  btScalar disttobestedge=BT_LARGE_FLOAT;
519  //
520  // Edge 0 -> 1
521  if (btFabs(info->m_edgeV0V1Angle)< triangleInfoMapPtr->m_maxEdgeAngleThreshold)
522  {
523  btVector3 nearest;
524  btNearestPointInLineSegment( cp.m_localPointB, v0, v1, nearest );
525  btScalar len=(contact-nearest).length();
526  //
527  if( len < disttobestedge )
528  {
529  bestedge=0;
530  disttobestedge=len;
531  }
532  }
533  // Edge 1 -> 2
534  if (btFabs(info->m_edgeV1V2Angle)< triangleInfoMapPtr->m_maxEdgeAngleThreshold)
535  {
536  btVector3 nearest;
537  btNearestPointInLineSegment( cp.m_localPointB, v1, v2, nearest );
538  btScalar len=(contact-nearest).length();
539  //
540  if( len < disttobestedge )
541  {
542  bestedge=1;
543  disttobestedge=len;
544  }
545  }
546  // Edge 2 -> 0
547  if (btFabs(info->m_edgeV2V0Angle)< triangleInfoMapPtr->m_maxEdgeAngleThreshold)
548  {
549  btVector3 nearest;
550  btNearestPointInLineSegment( cp.m_localPointB, v2, v0, nearest );
551  btScalar len=(contact-nearest).length();
552  //
553  if( len < disttobestedge )
554  {
555  bestedge=2;
556  disttobestedge=len;
557  }
558  }
559 
560 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
561  btVector3 upfix=tri_normal * btVector3(0.1f,0.1f,0.1f);
562  btDebugDrawLine(tr * v0 + upfix, tr * v1 + upfix, red );
563 #endif
564  if (btFabs(info->m_edgeV0V1Angle)< triangleInfoMapPtr->m_maxEdgeAngleThreshold)
565  {
566 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
567  btDebugDrawLine(tr*contact,tr*(contact+cp.m_normalWorldOnB*10),black);
568 #endif
569  btScalar len = (contact-nearest).length();
570  if(len<triangleInfoMapPtr->m_edgeDistanceThreshold)
571  if( bestedge==0 )
572  {
573  btVector3 edge(v0-v1);
574  isNearEdge = true;
575 
576  if (info->m_edgeV0V1Angle==btScalar(0))
577  {
578  numConcaveEdgeHits++;
579  } else
580  {
581 
582  bool isEdgeConvex = (info->m_flags & TRI_INFO_V0V1_CONVEX);
583  btScalar swapFactor = isEdgeConvex ? btScalar(1) : btScalar(-1);
584  #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
585  btDebugDrawLine(tr*nearest,tr*(nearest+swapFactor*tri_normal*10),white);
586  #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
587 
588  btVector3 nA = swapFactor * tri_normal;
589 
590  btQuaternion orn(edge,info->m_edgeV0V1Angle);
591  btVector3 computedNormalB = quatRotate(orn,tri_normal);
593  computedNormalB*=-1;
594  btVector3 nB = swapFactor*computedNormalB;
595 
596  btScalar NdotA = localContactNormalOnB.dot(nA);
597  btScalar NdotB = localContactNormalOnB.dot(nB);
598  bool backFacingNormal = (NdotA< triangleInfoMapPtr->m_convexEpsilon) && (NdotB<triangleInfoMapPtr->m_convexEpsilon);
599 
600 #ifdef DEBUG_INTERNAL_EDGE
601  {
602 
603  btDebugDrawLine(cp.getPositionWorldOnB(),cp.getPositionWorldOnB()+tr.getBasis()*(nB*20),red);
604  }
605 #endif //DEBUG_INTERNAL_EDGE
606 
607 
608  if (backFacingNormal)
609  {
610  numConcaveEdgeHits++;
611  }
612  else
613  {
614  numConvexEdgeHits++;
615  btVector3 clampedLocalNormal;
616  bool isClamped = btClampNormal(edge,swapFactor*tri_normal,localContactNormalOnB, info->m_edgeV0V1Angle,clampedLocalNormal);
617  if (isClamped)
618  {
619  if (((normalAdjustFlags & BT_TRIANGLE_CONVEX_DOUBLE_SIDED)!=0) || (clampedLocalNormal.dot(frontFacing*tri_normal)>0))
620  {
621  btVector3 newNormal = colObj0Wrap->getWorldTransform().getBasis() * clampedLocalNormal;
622  // cp.m_distance1 = cp.m_distance1 * newNormal.dot(cp.m_normalWorldOnB);
623  cp.m_normalWorldOnB = newNormal;
624  // Reproject collision point along normal. (what about cp.m_distance1?)
627 
628  }
629  }
630  }
631  }
632  }
633  }
634 
635  btNearestPointInLineSegment(contact,v1,v2,nearest);
636 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
637  btDebugDrawLine(tr*nearest,tr*cp.m_localPointB,green);
638 #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
639 
640 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
641  btDebugDrawLine(tr * v1 + upfix, tr * v2 + upfix , green );
642 #endif
643 
644  if (btFabs(info->m_edgeV1V2Angle)< triangleInfoMapPtr->m_maxEdgeAngleThreshold)
645  {
646 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
647  btDebugDrawLine(tr*contact,tr*(contact+cp.m_normalWorldOnB*10),black);
648 #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
649 
650 
651 
652  btScalar len = (contact-nearest).length();
653  if(len<triangleInfoMapPtr->m_edgeDistanceThreshold)
654  if( bestedge==1 )
655  {
656  isNearEdge = true;
657 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
658  btDebugDrawLine(tr*nearest,tr*(nearest+tri_normal*10),white);
659 #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
660 
661  btVector3 edge(v1-v2);
662 
663  isNearEdge = true;
664 
665  if (info->m_edgeV1V2Angle == btScalar(0))
666  {
667  numConcaveEdgeHits++;
668  } else
669  {
670  bool isEdgeConvex = (info->m_flags & TRI_INFO_V1V2_CONVEX)!=0;
671  btScalar swapFactor = isEdgeConvex ? btScalar(1) : btScalar(-1);
672  #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
673  btDebugDrawLine(tr*nearest,tr*(nearest+swapFactor*tri_normal*10),white);
674  #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
675 
676  btVector3 nA = swapFactor * tri_normal;
677 
678  btQuaternion orn(edge,info->m_edgeV1V2Angle);
679  btVector3 computedNormalB = quatRotate(orn,tri_normal);
681  computedNormalB*=-1;
682  btVector3 nB = swapFactor*computedNormalB;
683 
684 #ifdef DEBUG_INTERNAL_EDGE
685  {
686  btDebugDrawLine(cp.getPositionWorldOnB(),cp.getPositionWorldOnB()+tr.getBasis()*(nB*20),red);
687  }
688 #endif //DEBUG_INTERNAL_EDGE
689 
690 
691  btScalar NdotA = localContactNormalOnB.dot(nA);
692  btScalar NdotB = localContactNormalOnB.dot(nB);
693  bool backFacingNormal = (NdotA< triangleInfoMapPtr->m_convexEpsilon) && (NdotB<triangleInfoMapPtr->m_convexEpsilon);
694 
695  if (backFacingNormal)
696  {
697  numConcaveEdgeHits++;
698  }
699  else
700  {
701  numConvexEdgeHits++;
702  btVector3 localContactNormalOnB = colObj0Wrap->getWorldTransform().getBasis().transpose() * cp.m_normalWorldOnB;
703  btVector3 clampedLocalNormal;
704  bool isClamped = btClampNormal(edge,swapFactor*tri_normal,localContactNormalOnB, info->m_edgeV1V2Angle,clampedLocalNormal);
705  if (isClamped)
706  {
707  if (((normalAdjustFlags & BT_TRIANGLE_CONVEX_DOUBLE_SIDED)!=0) || (clampedLocalNormal.dot(frontFacing*tri_normal)>0))
708  {
709  btVector3 newNormal = colObj0Wrap->getWorldTransform().getBasis() * clampedLocalNormal;
710  // cp.m_distance1 = cp.m_distance1 * newNormal.dot(cp.m_normalWorldOnB);
711  cp.m_normalWorldOnB = newNormal;
712  // Reproject collision point along normal.
715  }
716  }
717  }
718  }
719  }
720  }
721 
722  btNearestPointInLineSegment(contact,v2,v0,nearest);
723 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
724  btDebugDrawLine(tr*nearest,tr*cp.m_localPointB,blue);
725 #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
726 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
727  btDebugDrawLine(tr * v2 + upfix, tr * v0 + upfix , blue );
728 #endif
729 
730  if (btFabs(info->m_edgeV2V0Angle)< triangleInfoMapPtr->m_maxEdgeAngleThreshold)
731  {
732 
733 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
734  btDebugDrawLine(tr*contact,tr*(contact+cp.m_normalWorldOnB*10),black);
735 #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
736 
737  btScalar len = (contact-nearest).length();
738  if(len<triangleInfoMapPtr->m_edgeDistanceThreshold)
739  if( bestedge==2 )
740  {
741  isNearEdge = true;
742 #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
743  btDebugDrawLine(tr*nearest,tr*(nearest+tri_normal*10),white);
744 #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
745 
746  btVector3 edge(v2-v0);
747 
748  if (info->m_edgeV2V0Angle==btScalar(0))
749  {
750  numConcaveEdgeHits++;
751  } else
752  {
753 
754  bool isEdgeConvex = (info->m_flags & TRI_INFO_V2V0_CONVEX)!=0;
755  btScalar swapFactor = isEdgeConvex ? btScalar(1) : btScalar(-1);
756  #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW
757  btDebugDrawLine(tr*nearest,tr*(nearest+swapFactor*tri_normal*10),white);
758  #endif //BT_INTERNAL_EDGE_DEBUG_DRAW
759 
760  btVector3 nA = swapFactor * tri_normal;
761  btQuaternion orn(edge,info->m_edgeV2V0Angle);
762  btVector3 computedNormalB = quatRotate(orn,tri_normal);
764  computedNormalB*=-1;
765  btVector3 nB = swapFactor*computedNormalB;
766 
767 #ifdef DEBUG_INTERNAL_EDGE
768  {
769  btDebugDrawLine(cp.getPositionWorldOnB(),cp.getPositionWorldOnB()+tr.getBasis()*(nB*20),red);
770  }
771 #endif //DEBUG_INTERNAL_EDGE
772 
773  btScalar NdotA = localContactNormalOnB.dot(nA);
774  btScalar NdotB = localContactNormalOnB.dot(nB);
775  bool backFacingNormal = (NdotA< triangleInfoMapPtr->m_convexEpsilon) && (NdotB<triangleInfoMapPtr->m_convexEpsilon);
776 
777  if (backFacingNormal)
778  {
779  numConcaveEdgeHits++;
780  }
781  else
782  {
783  numConvexEdgeHits++;
784  // printf("hitting convex edge\n");
785 
786 
787  btVector3 localContactNormalOnB = colObj0Wrap->getWorldTransform().getBasis().transpose() * cp.m_normalWorldOnB;
788  btVector3 clampedLocalNormal;
789  bool isClamped = btClampNormal(edge,swapFactor*tri_normal,localContactNormalOnB,info->m_edgeV2V0Angle,clampedLocalNormal);
790  if (isClamped)
791  {
792  if (((normalAdjustFlags & BT_TRIANGLE_CONVEX_DOUBLE_SIDED)!=0) || (clampedLocalNormal.dot(frontFacing*tri_normal)>0))
793  {
794  btVector3 newNormal = colObj0Wrap->getWorldTransform().getBasis() * clampedLocalNormal;
795  // cp.m_distance1 = cp.m_distance1 * newNormal.dot(cp.m_normalWorldOnB);
796  cp.m_normalWorldOnB = newNormal;
797  // Reproject collision point along normal.
800  }
801  }
802  }
803  }
804 
805 
806  }
807  }
808 
809 #ifdef DEBUG_INTERNAL_EDGE
810  {
811  btVector3 color(0,1,1);
812  btDebugDrawLine(cp.getPositionWorldOnB(),cp.getPositionWorldOnB()+cp.m_normalWorldOnB*10,color);
813  }
814 #endif //DEBUG_INTERNAL_EDGE
815 
816  if (isNearEdge)
817  {
818 
819  if (numConcaveEdgeHits>0)
820  {
821  if ((normalAdjustFlags & BT_TRIANGLE_CONCAVE_DOUBLE_SIDED)!=0)
822  {
823  //fix tri_normal so it pointing the same direction as the current local contact normal
824  if (tri_normal.dot(localContactNormalOnB) < 0)
825  {
826  tri_normal *= -1;
827  }
828  cp.m_normalWorldOnB = colObj0Wrap->getWorldTransform().getBasis()*tri_normal;
829  } else
830  {
831  btVector3 newNormal = tri_normal *frontFacing;
832  //if the tri_normal is pointing opposite direction as the current local contact normal, skip it
833  btScalar d = newNormal.dot(localContactNormalOnB) ;
834  if (d< 0)
835  {
836  return;
837  }
838  //modify the normal to be the triangle normal (or backfacing normal)
839  cp.m_normalWorldOnB = colObj0Wrap->getWorldTransform().getBasis() *newNormal;
840  }
841 
842  // Reproject collision point along normal.
845  }
846  }
847 }
void btNearestPointInLineSegment(const btVector3 &point, const btVector3 &line0, const btVector3 &line1, btVector3 &nearestPoint)
btScalar length(const btQuaternion &q)
Return the length of a quaternion.
Definition: btQuaternion.h:906
int getShapeType() const
#define BT_LARGE_FLOAT
Definition: btScalar.h:294
const btTriangleInfoMap * getTriangleInfoMap() const
#define TRI_INFO_V0V1_SWAP_NORMALB
void setValue(const btScalar &_x, const btScalar &_y, const btScalar &_z)
Definition: btVector3.h:652
btScalar m_edgeV1V2Angle
#define TRI_INFO_V1V2_CONVEX
virtual void drawLine(const btVector3 &from, const btVector3 &to, const btVector3 &color)=0
virtual void processAllTriangles(btTriangleCallback *callback, const btVector3 &aabbMin, const btVector3 &aabbMax) const
btScalar m_maxEdgeAngleThreshold
used to determine edge contacts: if the closest distance between a contact point and an edge is small...
const btVector3 & getScaling() const
static int btGetHash(int partId, int triangleIndex)
ManifoldContactPoint collects and maintains persistent contactpoints.
btScalar m_edgeV0V1Angle
btScalar m_equalVertexThreshold
used to determine if a triangle edge is planar with zero angle
#define TRI_INFO_V1V2_SWAP_NORMALB
btScalar dot(const btVector3 &v) const
Return the dot product.
Definition: btVector3.h:235
btVector3 & normalize()
Normalize this vector x^2 + y^2 + z^2 = 1.
Definition: btVector3.h:309
void calcNormal(btVector3 &normal) const
btVector3 quatRotate(const btQuaternion &rotation, const btVector3 &v)
Definition: btQuaternion.h:937
const btScalar & getZ() const
Return the z value.
Definition: btVector3.h:577
virtual void getVertex(int index, btVector3 &vert) const
The btBvhTriangleMeshShape is a static-triangle mesh shape, it can only be used for fixed/non-moving ...
#define MAX_NUM_PARTS_IN_BITS
void btAdjustInternalEdgeContacts(btManifoldPoint &cp, const btCollisionObjectWrapper *colObj0Wrap, const btCollisionObjectWrapper *colObj1Wrap, int partId0, int index0, int normalAdjustFlags)
Changes a btManifoldPoint collision normal to the normal from the mesh.
#define SIMD_PI
Definition: btScalar.h:504
btVector3 m_normalWorldOnB
btVector3 m_positionWorldOnB
btTriangleInfoMap * m_triangleInfoMap
The btTriangleCallback provides a callback for each overlapping triangle when calling processAllTrian...
btScalar btAtan2(btScalar x, btScalar y)
Definition: btScalar.h:496
btVector3 cross(const btVector3 &v) const
Return the cross product between this and another vector.
Definition: btVector3.h:389
void btGenerateInternalEdgeInfo(btBvhTriangleMeshShape *trimeshShape, btTriangleInfoMap *triangleInfoMap)
Call btGenerateInternalEdgeInfo to create triangle info, store in the shape &#39;userInfo&#39;.
const btScalar & getY() const
Return the y value.
Definition: btVector3.h:575
const btTransform & getWorldTransform() const
btMatrix3x3 & getBasis()
Return the basis matrix for the rotation.
Definition: btTransform.h:112
The btTriangleInfo structure stores information to adjust collision normals to avoid collisions again...
const btScalar & getX() const
Return the x value.
Definition: btVector3.h:573
void insert(const Key &key, const Value &value)
Definition: btHashMap.h:262
The btIDebugDraw interface class allows hooking up a debug renderer to visually debug simulations...
Definition: btIDebugDraw.h:29
btVector3 m_positionWorldOnA
m_positionWorldOnA is redundant information, see getPositionWorldOnA(), but for clarity ...
bool fuzzyZero() const
Definition: btVector3.h:701
const btCollisionShape * getCollisionShape() const
const btVector3 & getPositionWorldOnB() const
btVector3 invXform(const btVector3 &inVec) const
Definition: btTransform.h:223
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:83
virtual int getNumSubParts() const =0
getNumSubParts returns the number of seperate subparts each subpart has a continuous array of vertice...
const Value * find(const Key &key) const
Definition: btHashMap.h:422
#define TRI_INFO_V0V1_CONVEX
for btTriangleInfo m_flags
btScalar length2() const
Return the length of the vector squared.
Definition: btVector3.h:257
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition: btTransform.h:34
#define TRI_INFO_V2V0_SWAP_NORMALB
The btStridingMeshInterface is the interface class for high performance generic access to triangle me...
btVector3 m_localPointB
btScalar m_edgeV2V0Angle
btMatrix3x3 transpose() const
Return the transpose of the matrix.
Definition: btMatrix3x3.h:1030
static btScalar btGetAngle(const btVector3 &edgeA, const btVector3 &normalA, const btVector3 &normalB)
#define TRI_INFO_V2V0_CONVEX
virtual void getLockedReadOnlyVertexIndexBase(const unsigned char **vertexbase, int &numverts, PHY_ScalarType &type, int &stride, const unsigned char **indexbase, int &indexstride, int &numfaces, PHY_ScalarType &indicestype, int subpart=0) const =0
bool btClampNormal(const btVector3 &edge, const btVector3 &tri_normal_org, const btVector3 &localContactNormalOnB, btScalar correctedEdgeAngle, btVector3 &clampedLocalNormal)
The btScaledBvhTriangleMeshShape allows to instance a scaled version of an existing btBvhTriangleMesh...
void setTriangleInfoMap(btTriangleInfoMap *triangleInfoMap)
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
Definition: btMatrix3x3.h:48
btScalar dot(const btQuaternion &q1, const btQuaternion &q2)
Calculate the dot product between two quaternions.
Definition: btQuaternion.h:898
The btTriangleInfoMap stores edge angle information for some triangles. You can compute this informat...
The btQuaternion implements quaternion to perform linear algebra rotations in combination with btMatr...
Definition: btQuaternion.h:55
btStridingMeshInterface * getMeshInterface()
void setMax(const btVector3 &other)
Set each element to the max of the current values and the values of another btVector3.
Definition: btVector3.h:621
const btCollisionShape * getCollisionShape() const
virtual void processTriangle(btVector3 *triangle, int partId, int triangleIndex)
void setMin(const btVector3 &other)
Set each element to the min of the current values and the values of another btVector3.
Definition: btVector3.h:638
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
PHY_ScalarType
PHY_ScalarType enumerates possible scalar types.
const btCollisionObject * getCollisionObject() const
btScalar btFabs(btScalar x)
Definition: btScalar.h:475