Bullet Collision Detection & Physics Library
btConvex2dConvex2dAlgorithm.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 you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
12 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13 3. This notice may not be removed or altered from any source distribution.
14 */
15 
17 
18 //#include <stdio.h>
24 
25 
31 
36 
37 
38 
41 
43 
47 
49 {
50  m_simplexSolver = simplexSolver;
51  m_pdSolver = pdSolver;
52 }
53 
55 {
56 }
57 
58 btConvex2dConvex2dAlgorithm::btConvex2dConvex2dAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btSimplexSolverInterface* simplexSolver, btConvexPenetrationDepthSolver* pdSolver,int /* numPerturbationIterations */, int /* minimumPointsPerturbationThreshold */)
59 : btActivatingCollisionAlgorithm(ci,body0Wrap,body1Wrap),
60 m_simplexSolver(simplexSolver),
61 m_pdSolver(pdSolver),
62 m_ownManifold (false),
63 m_manifoldPtr(mf),
64 m_lowLevelOfDetail(false)
65 {
66  (void)body0Wrap;
67  (void)body1Wrap;
68 }
69 
70 
71 
72 
74 {
75  if (m_ownManifold)
76  {
77  if (m_manifoldPtr)
79  }
80 }
81 
83 {
84  m_lowLevelOfDetail = useLowLevel;
85 }
86 
87 
88 
90 
91 
92 //
93 // Convex-Convex collision algorithm
94 //
96 {
97 
98  if (!m_manifoldPtr)
99  {
100  //swapped?
102  m_ownManifold = true;
103  }
105 
106  //comment-out next line to test multi-contact generation
107  //resultOut->getPersistentManifold()->clearManifold();
108 
109 
110  const btConvexShape* min0 = static_cast<const btConvexShape*>(body0Wrap->getCollisionShape());
111  const btConvexShape* min1 = static_cast<const btConvexShape*>(body1Wrap->getCollisionShape());
112 
113  btVector3 normalOnB;
114  btVector3 pointOnBWorld;
115 
116  {
117 
118 
120 
121  btGjkPairDetector gjkPairDetector(min0,min1,m_simplexSolver,m_pdSolver);
122  //TODO: if (dispatchInfo.m_useContinuous)
123  gjkPairDetector.setMinkowskiA(min0);
124  gjkPairDetector.setMinkowskiB(min1);
125 
126  {
129  }
130 
131  input.m_transformA = body0Wrap->getWorldTransform();
132  input.m_transformB = body1Wrap->getWorldTransform();
133 
134  gjkPairDetector.getClosestPoints(input,*resultOut,dispatchInfo.m_debugDraw);
135 
136  btVector3 v0,v1;
137  btVector3 sepNormalWorldSpace;
138 
139  }
140 
141  if (m_ownManifold)
142  {
143  resultOut->refreshContactPoints();
144  }
145 
146 }
147 
148 
149 
150 
152 {
153  (void)resultOut;
154  (void)dispatchInfo;
156 
159  btScalar resultFraction = btScalar(1.);
160 
161 
162  btScalar squareMot0 = (col0->getInterpolationWorldTransform().getOrigin() - col0->getWorldTransform().getOrigin()).length2();
163  btScalar squareMot1 = (col1->getInterpolationWorldTransform().getOrigin() - col1->getWorldTransform().getOrigin()).length2();
164 
165  if (squareMot0 < col0->getCcdSquareMotionThreshold() &&
166  squareMot1 < col1->getCcdSquareMotionThreshold())
167  return resultFraction;
168 
169 
170  //An adhoc way of testing the Continuous Collision Detection algorithms
171  //One object is approximated as a sphere, to simplify things
172  //Starting in penetration should report no time of impact
173  //For proper CCD, better accuracy and handling of 'allowed' penetration should be added
174  //also the mainloop of the physics should have a kind of toi queue (something like Brian Mirtich's application of Timewarp for Rigidbodies)
175 
176 
178  {
179  btConvexShape* convex0 = static_cast<btConvexShape*>(col0->getCollisionShape());
180 
181  btSphereShape sphere1(col1->getCcdSweptSphereRadius()); //todo: allow non-zero sphere sizes, for better approximation
183  btVoronoiSimplexSolver voronoiSimplex;
184  //SubsimplexConvexCast ccd0(&sphere,min0,&voronoiSimplex);
186  btGjkConvexCast ccd1( convex0 ,&sphere1,&voronoiSimplex);
187  //ContinuousConvexCollision ccd(min0,min1,&voronoiSimplex,0);
189  col1->getWorldTransform(),col1->getInterpolationWorldTransform(),result))
190  {
191 
192  //store result.m_fraction in both bodies
193 
194  if (col0->getHitFraction()> result.m_fraction)
195  col0->setHitFraction( result.m_fraction );
196 
197  if (col1->getHitFraction() > result.m_fraction)
198  col1->setHitFraction( result.m_fraction);
199 
200  if (resultFraction > result.m_fraction)
201  resultFraction = result.m_fraction;
202 
203  }
204 
205 
206 
207 
208  }
209 
211  {
212  btConvexShape* convex1 = static_cast<btConvexShape*>(col1->getCollisionShape());
213 
214  btSphereShape sphere0(col0->getCcdSweptSphereRadius()); //todo: allow non-zero sphere sizes, for better approximation
216  btVoronoiSimplexSolver voronoiSimplex;
217  //SubsimplexConvexCast ccd0(&sphere,min0,&voronoiSimplex);
219  btGjkConvexCast ccd1(&sphere0,convex1,&voronoiSimplex);
220  //ContinuousConvexCollision ccd(min0,min1,&voronoiSimplex,0);
222  col1->getWorldTransform(),col1->getInterpolationWorldTransform(),result))
223  {
224 
225  //store result.m_fraction in both bodies
226 
227  if (col0->getHitFraction() > result.m_fraction)
228  col0->setHitFraction( result.m_fraction);
229 
230  if (col1->getHitFraction() > result.m_fraction)
231  col1->setHitFraction( result.m_fraction);
232 
233  if (resultFraction > result.m_fraction)
234  resultFraction = result.m_fraction;
235 
236  }
237  }
238 
239  return resultFraction;
240 
241 }
242 
virtual void releaseManifold(btPersistentManifold *manifold)=0
btPersistentManifold is a contact point cache, it stays persistent as long as objects are overlapping...
btScalar getCcdSweptSphereRadius() const
Swept sphere radius (0.0 by default), see btConvexConvexAlgorithm::
btScalar getContactBreakingThreshold() const
ConvexPenetrationDepthSolver provides an interface for penetration depth calculation.
void setMinkowskiB(const btConvexShape *minkB)
void setPersistentManifold(btPersistentManifold *manifoldPtr)
This class is not enabled yet (work-in-progress) to more aggressively activate objects.
void setHitFraction(btScalar hitFraction)
void setMinkowskiA(const btConvexShape *minkA)
virtual btScalar calculateTimeOfImpact(btCollisionObject *body0, btCollisionObject *body1, const btDispatcherInfo &dispatchInfo, btManifoldResult *resultOut)
The btSphereShape implements an implicit sphere, centered around a local origin with radius...
Definition: btSphereShape.h:22
btManifoldResult is a helper class to manage contact results.
class btIDebugDraw * m_debugDraw
Definition: btDispatcher.h:59
btScalar getCcdSquareMotionThreshold() const
The btConvexShape is an abstract shape interface, implemented by all convex shapes such as btBoxShape...
Definition: btConvexShape.h:31
const btTransform & getInterpolationWorldTransform() const
GjkConvexCast performs a raycast on a convex object using support mapping.
virtual bool calcTimeOfImpact(const btTransform &fromA, const btTransform &toA, const btTransform &fromB, const btTransform &toB, CastResult &result)
cast a convex against another convex object
btTransform & getWorldTransform()
RayResult stores the closest result alternatively, add a callback method to decide about closest/all ...
Definition: btConvexCast.h:36
btVector3 & getOrigin()
Return the origin vector translation.
Definition: btTransform.h:117
#define btSimplexSolverInterface
btVoronoiSimplexSolver is an implementation of the closest point distance algorithm from a 1-4 points...
const btTransform & getWorldTransform() const
btCollisionObject can be used to manage collision detection objects.
virtual btPersistentManifold * getNewManifold(const btCollisionObject *b0, const btCollisionObject *b1)=0
virtual btScalar getMargin() const =0
const btCollisionShape * getCollisionShape() const
btScalar getHitFraction() const
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:83
btSimplexSolverInterface * m_simplexSolver
CreateFunc(btSimplexSolverInterface *simplexSolver, btConvexPenetrationDepthSolver *pdSolver)
btGjkPairDetector uses GJK to implement the btDiscreteCollisionDetectorInterface
btConvex2dConvex2dAlgorithm(btPersistentManifold *mf, const btCollisionAlgorithmConstructionInfo &ci, const btCollisionObjectWrapper *body0Wrap, const btCollisionObjectWrapper *body1Wrap, btSimplexSolverInterface *simplexSolver, btConvexPenetrationDepthSolver *pdSolver, int numPerturbationIterations, int minimumPointsPerturbationThreshold)
virtual void processCollision(const btCollisionObjectWrapper *body0Wrap, const btCollisionObjectWrapper *body1Wrap, const btDispatcherInfo &dispatchInfo, btManifoldResult *resultOut)
const btCollisionShape * getCollisionShape() const
btScalar gContactBreakingThreshold
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
btConvexPenetrationDepthSolver * m_pdSolver
virtual void getClosestPoints(const ClosestPointInput &input, Result &output, class btIDebugDraw *debugDraw, bool swapResults=false)
const btCollisionObject * getCollisionObject() const