- fixed Bullet noResponse/ghost mode

- added ccd option (future use, very basic and inefficient)
- some internal Bullet refactoring/improvements
This commit is contained in:
Erwin Coumans 2006-04-28 00:08:18 +00:00
parent 2d6224a0d7
commit f51d1ef7d6
26 changed files with 1347 additions and 998 deletions

@ -128,6 +128,7 @@ void CollisionDispatcher::BuildAndProcessIslands(int numBodies, IslandCallback*
CollisionObject* colObj0 = static_cast<CollisionObject*>(manifold->GetBody0());
CollisionObject* colObj1 = static_cast<CollisionObject*>(manifold->GetBody1());
{
if (((colObj0) && (colObj0)->m_islandTag1 == (islandId)) ||
@ -145,7 +146,8 @@ void CollisionDispatcher::BuildAndProcessIslands(int numBodies, IslandCallback*
allSleeping = false;
}
islandmanifold.push_back(manifold);
if (NeedsResponse(*colObj0,*colObj1))
islandmanifold.push_back(manifold);
}
}
}
@ -196,7 +198,10 @@ void CollisionDispatcher::BuildAndProcessIslands(int numBodies, IslandCallback*
}
callback->ProcessIsland(&islandmanifold[0],islandmanifold.size());
if (islandmanifold.size())
{
callback->ProcessIsland(&islandmanifold[0],islandmanifold.size());
}
}
}

@ -17,8 +17,14 @@ subject to the following restrictions:
#include "CollisionDispatcher.h"
#include "CollisionDispatch/CollisionObject.h"
#include "CollisionShapes/CollisionShape.h"
#include "CollisionShapes/SphereShape.h" //for raycasting
#include "CollisionShapes/TriangleMeshShape.h" //for raycasting
#include "NarrowPhaseCollision/RaycastCallback.h"
#include "NarrowPhaseCollision/SubSimplexConvexCast.h"
#include "BroadphaseCollision/BroadphaseInterface.h"
#include "AabbUtil2.h"
#include <algorithm>
void CollisionWorld::UpdateActivationState()
@ -145,3 +151,147 @@ void CollisionWorld::RemoveCollisionObject(CollisionObject* collisionObject)
m_collisionObjects.pop_back();
}
}
void CollisionWorld::RayTest(const SimdVector3& rayFromWorld, const SimdVector3& rayToWorld, RayResultCallback& resultCallback)
{
SimdTransform rayFromTrans,rayToTrans;
rayFromTrans.setIdentity();
rayFromTrans.setOrigin(rayFromWorld);
rayToTrans.setIdentity();
rayToTrans.setOrigin(rayToWorld);
//do culling based on aabb (rayFrom/rayTo)
SimdVector3 rayAabbMin = rayFromWorld;
SimdVector3 rayAabbMax = rayFromWorld;
rayAabbMin.setMin(rayToWorld);
rayAabbMax.setMax(rayToWorld);
SphereShape pointShape(0.0f);
/// brute force go over all objects. Once there is a broadphase, use that, or
/// add a raycast against aabb first.
std::vector<CollisionObject*>::iterator iter;
for (iter=m_collisionObjects.begin();
!(iter==m_collisionObjects.end()); iter++)
{
CollisionObject* collisionObject= (*iter);
//RigidcollisionObject* collisionObject = ctrl->GetRigidcollisionObject();
SimdVector3 collisionObjectAabbMin,collisionObjectAabbMax;
collisionObject->m_collisionShape->GetAabb(collisionObject->m_worldTransform,collisionObjectAabbMin,collisionObjectAabbMax);
//check aabb overlap
if (TestAabbAgainstAabb2(rayAabbMin,rayAabbMax,collisionObjectAabbMin,collisionObjectAabbMax))
{
if (collisionObject->m_collisionShape->IsConvex())
{
ConvexCast::CastResult castResult;
castResult.m_fraction = 1.f;//??
ConvexShape* convexShape = (ConvexShape*) collisionObject->m_collisionShape;
VoronoiSimplexSolver simplexSolver;
SubsimplexConvexCast convexCaster(&pointShape,convexShape,&simplexSolver);
//GjkConvexCast convexCaster(&pointShape,convexShape,&simplexSolver);
//ContinuousConvexCollision convexCaster(&pointShape,convexShape,&simplexSolver,0);
if (convexCaster.calcTimeOfImpact(rayFromTrans,rayToTrans,collisionObject->m_worldTransform,collisionObject->m_worldTransform,castResult))
{
//add hit
if (castResult.m_normal.length2() > 0.0001f)
{
castResult.m_normal.normalize();
if (castResult.m_fraction < resultCallback.m_closestHitFraction)
{
CollisionWorld::LocalRayResult localRayResult
(
collisionObject,
0,
castResult.m_normal,
castResult.m_fraction
);
resultCallback.AddSingleResult(localRayResult);
}
}
}
}
else
{
if (collisionObject->m_collisionShape->IsConcave())
{
TriangleMeshShape* triangleMesh = (TriangleMeshShape*)collisionObject->m_collisionShape;
SimdTransform worldTocollisionObject = collisionObject->m_worldTransform.inverse();
SimdVector3 rayFromLocal = worldTocollisionObject * rayFromTrans.getOrigin();
SimdVector3 rayToLocal = worldTocollisionObject * rayToTrans.getOrigin();
//ConvexCast::CastResult
struct BridgeTriangleRaycastCallback : public TriangleRaycastCallback
{
RayResultCallback* m_resultCallback;
CollisionObject* m_collisionObject;
TriangleMeshShape* m_triangleMesh;
BridgeTriangleRaycastCallback( const SimdVector3& from,const SimdVector3& to,
RayResultCallback* resultCallback, CollisionObject* collisionObject,TriangleMeshShape* triangleMesh):
TriangleRaycastCallback(from,to),
m_resultCallback(resultCallback),
m_collisionObject(collisionObject),
m_triangleMesh(triangleMesh)
{
}
virtual void ReportHit(const SimdVector3& hitNormalLocal, float hitFraction, int partId, int triangleIndex )
{
LocalShapeInfo shapeInfo;
shapeInfo.m_shapePart = partId;
shapeInfo.m_triangleIndex = triangleIndex;
LocalRayResult rayResult
(m_collisionObject,
&shapeInfo,
hitNormalLocal,
hitFraction);
m_resultCallback->AddSingleResult(rayResult);
}
};
BridgeTriangleRaycastCallback rcb(rayFromLocal,rayToLocal,&resultCallback,collisionObject,triangleMesh);
rcb.m_hitFraction = resultCallback.m_closestHitFraction;
SimdVector3 rayAabbMinLocal = rayFromLocal;
rayAabbMinLocal.setMin(rayToLocal);
SimdVector3 rayAabbMaxLocal = rayFromLocal;
rayAabbMaxLocal.setMax(rayToLocal);
triangleMesh->ProcessAllTriangles(&rcb,rayAabbMinLocal,rayAabbMaxLocal);
}
}
}
}
}

@ -16,9 +16,13 @@ subject to the following restrictions:
#ifndef COLLISION_WORLD_H
#define COLLISION_WORLD_H
struct CollisionObject;
class CollisionShape;
class CollisionDispatcher;
class BroadphaseInterface;
#include "SimdVector3.h"
#include "SimdTransform.h"
#include "CollisionObject.h"
#include <vector>
@ -26,13 +30,15 @@ class BroadphaseInterface;
class CollisionWorld
{
std::vector<CollisionObject*> m_collisionObjects;
CollisionDispatcher* m_dispatcher;
BroadphaseInterface* m_broadphase;
public:
public:
CollisionWorld(CollisionDispatcher* dispatcher,BroadphaseInterface* broadphase)
:m_dispatcher(dispatcher),
@ -54,11 +60,93 @@ class CollisionWorld
return m_dispatcher;
}
///LocalShapeInfo gives extra information for complex shapes
///Currently, only TriangleMeshShape is available, so it just contains triangleIndex and subpart
struct LocalShapeInfo
{
int m_shapePart;
int m_triangleIndex;
//const CollisionShape* m_shapeTemp;
//const SimdTransform* m_shapeLocalTransform;
};
struct LocalRayResult
{
LocalRayResult(const CollisionObject* collisionObject,
LocalShapeInfo* localShapeInfo,
const SimdVector3& hitNormalLocal,
float hitFraction)
:m_collisionObject(collisionObject),
m_localShapeInfo(m_localShapeInfo),
m_hitNormalLocal(hitNormalLocal),
m_hitFraction(hitFraction)
{
}
const CollisionObject* m_collisionObject;
LocalShapeInfo* m_localShapeInfo;
const SimdVector3& m_hitNormalLocal;
float m_hitFraction;
};
///RayResultCallback is used to report new raycast results
struct RayResultCallback
{
float m_closestHitFraction;
bool HasHit()
{
return (m_closestHitFraction < 1.f);
}
RayResultCallback()
:m_closestHitFraction(1.f)
{
}
virtual float AddSingleResult(const LocalRayResult& rayResult) = 0;
};
struct ClosestRayResultCallback : public RayResultCallback
{
ClosestRayResultCallback(SimdVector3 rayFromWorld,SimdVector3 rayToWorld)
:m_rayFromWorld(rayFromWorld),
m_rayToWorld(rayToWorld),
m_collisionObject(0)
{
}
SimdVector3 m_rayFromWorld;//used to calculate hitPointWorld from hitFraction
SimdVector3 m_rayToWorld;
SimdVector3 m_hitNormalWorld;
SimdVector3 m_hitPointWorld;
const CollisionObject* m_collisionObject;
virtual float AddSingleResult(const LocalRayResult& rayResult)
{
//caller already does the filter on the m_closestHitFraction
assert(rayResult.m_hitFraction < m_closestHitFraction);
m_closestHitFraction = rayResult.m_hitFraction;
m_collisionObject = rayResult.m_collisionObject;
m_hitNormalWorld = m_collisionObject->m_worldTransform.getBasis()*rayResult.m_hitNormalLocal;
m_hitPointWorld.setInterpolate3(m_rayFromWorld,m_rayToWorld,rayResult.m_hitFraction);
return rayResult.m_hitFraction;
}
};
int GetNumCollisionObjects() const
{
return m_collisionObjects.size();
}
void RayTest(const SimdVector3& rayFromWorld, const SimdVector3& rayToWorld, RayResultCallback& resultCallback);
void AddCollisionObject(CollisionObject* collisionObject);
void RemoveCollisionObject(CollisionObject* collisionObject);

@ -68,7 +68,7 @@ void BoxTriangleCallback::ClearCache()
void BoxTriangleCallback::ProcessTriangle(SimdVector3* triangle)
void BoxTriangleCallback::ProcessTriangle(SimdVector3* triangle,int partId, int triangleIndex)
{
//just for debugging purposes
@ -178,17 +178,30 @@ void ConvexConcaveCollisionAlgorithm::ProcessCollision (BroadphaseProxy* ,Broadp
float ConvexConcaveCollisionAlgorithm::CalculateTimeOfImpact(BroadphaseProxy* ,BroadphaseProxy* ,const DispatcherInfo& dispatchInfo)
{
//quick approximation using raycast, todo: use proper continuou collision detection
//quick approximation using raycast, todo: hook up to the continuous collision detection (one of the ConvexCast)
CollisionObject* convexbody = (CollisionObject* )m_convex.m_clientObject;
CollisionObject* triBody = static_cast<CollisionObject* >(m_concave.m_clientObject);
const SimdVector3& from = convexbody->m_worldTransform.getOrigin();
SimdVector3 to = convexbody->m_nextPredictedWorldTransform.getOrigin();
//only do if the motion exceeds the 'radius'
//todo: only do if the motion exceeds the 'radius'
struct LocalTriangleRaycastCallback : public TriangleRaycastCallback
{
LocalTriangleRaycastCallback(const SimdVector3& from,const SimdVector3& to)
:TriangleRaycastCallback(from,to)
{
}
virtual void ReportHit(const SimdVector3& hitNormalLocal, float hitFraction, int partId, int triangleIndex )
{
}
};
RaycastCallback raycastCallback(from,to);
LocalTriangleRaycastCallback raycastCallback(from,to);
raycastCallback.m_hitFraction = convexbody->m_hitFraction;

@ -49,7 +49,7 @@ int m_triangleCount;
virtual ~BoxTriangleCallback();
virtual void ProcessTriangle(SimdVector3* triangle);
virtual void ProcessTriangle(SimdVector3* triangle, int partId, int triangleIndex);
void ClearCache();

@ -341,6 +341,11 @@ float ConvexConvexAlgorithm::CalculateTimeOfImpact(BroadphaseProxy* proxy0,Broad
CheckPenetrationDepthSolver();
//An adhoc way of testing the Continuous Collision Detection algorithms
//One object is approximated as a point, to simplify things
//Starting in penetration should report no time of impact
//For proper CCD, better accuracy and handling of 'allowed' penetration should be added
//also the mainloop of the physics should have a kind of toi queue (something like Brian Mirtich's application of Timewarp for Rigidbodies)
bool needsCollision = m_dispatcher->NeedsCollision(m_box0,m_box1);
@ -351,21 +356,25 @@ float ConvexConvexAlgorithm::CalculateTimeOfImpact(BroadphaseProxy* proxy0,Broad
CollisionObject* col0 = static_cast<CollisionObject*>(m_box0.m_clientObject);
CollisionObject* col1 = static_cast<CollisionObject*>(m_box1.m_clientObject);
SphereShape sphere(0.f);
ConvexShape* min0 = static_cast<ConvexShape*>(col0->m_collisionShape);
ConvexShape* min1 = static_cast<ConvexShape*>(col1->m_collisionShape);
ConvexCast::CastResult result;
VoronoiSimplexSolver voronoiSimplex;
//SubsimplexConvexCast ccd(&voronoiSimplex);
//GjkConvexCast ccd(&voronoiSimplex);
ContinuousConvexCollision ccd(min0,min1,&voronoiSimplex,m_penetrationDepthSolver);
SubsimplexConvexCast ccd0(&sphere,min1,&voronoiSimplex);
///Simplification, one object is simplified as a sphere
GjkConvexCast ccd1(&sphere,min0,&voronoiSimplex);
//ContinuousConvexCollision ccd(min0,min1,&voronoiSimplex,0);
if (disableCcd)
return 1.f;
if (ccd.calcTimeOfImpact(col0->m_worldTransform,col0->m_nextPredictedWorldTransform,
if (ccd1.calcTimeOfImpact(col0->m_worldTransform,col0->m_nextPredictedWorldTransform,
col1->m_worldTransform,col1->m_nextPredictedWorldTransform,result))
{
@ -381,7 +390,9 @@ float ConvexConvexAlgorithm::CalculateTimeOfImpact(BroadphaseProxy* proxy0,Broad
}
return 1.f;
}

@ -27,7 +27,7 @@ class ConvexPenetrationDepthSolver;
///ConvexConvexAlgorithm collision algorithm implements time of impact, convex closest points and penetration depth calculations.
class ConvexConvexAlgorithm : public CollisionAlgorithm
{
ConvexPenetrationDepthSolver* m_penetrationDepthSolver;
//ConvexPenetrationDepthSolver* m_penetrationDepthSolver;
VoronoiSimplexSolver m_simplexSolver;
GjkPairDetector m_gjkPairDetector;
bool m_useEpa;

@ -108,7 +108,7 @@ void BvhTriangleMeshShape::ProcessAllTriangles(TriangleCallback* callback,const
#endif //DEBUG_TRIANGLE_MESH
}
m_callback->ProcessTriangle(m_triangle);
m_callback->ProcessTriangle(m_triangle,node->m_subPart,node->m_triangleIndex);
m_meshInterface->unLockReadOnlyVertexBase(node->m_subPart);
}

@ -24,7 +24,7 @@ class TriangleCallback
public:
virtual ~TriangleCallback();
virtual void ProcessTriangle(SimdVector3* triangle) = 0;
virtual void ProcessTriangle(SimdVector3* triangle, int partId, int triangleIndex) = 0;
};
class InternalTriangleIndexCallback

@ -92,7 +92,7 @@ public:
m_supportVecLocal = supportVecWorld * m_worldTrans.getBasis();
}
virtual void ProcessTriangle( SimdVector3* triangle)
virtual void ProcessTriangle( SimdVector3* triangle,int partId, int triangleIndex)
{
for (int i=0;i<3;i++)
{
@ -158,7 +158,7 @@ void TriangleMeshShape::ProcessAllTriangles(TriangleCallback* callback,const Sim
if (TestTriangleAgainstAabb2(&triangle[0],m_aabbMin,m_aabbMax))
{
//check aabb in triangle-space, before doing this
m_callback->ProcessTriangle(triangle);
m_callback->ProcessTriangle(triangle,partId,triangleIndex);
}
}

@ -91,6 +91,10 @@ bool ContinuousConvexCollision::calcTimeOfImpact(
GjkPairDetector gjk(m_convexA,m_convexB,m_simplexSolver,m_penetrationDepthSolver);
GjkPairDetector::ClosestPointInput input;
//we don't use margins during CCD
gjk.SetIgnoreMargin(true);
input.m_transformA = fromA;
input.m_transformB = fromB;
gjk.GetClosestPoints(input,pointCollector1,0);

@ -103,11 +103,17 @@ bool GjkConvexCast::calcTimeOfImpact(
n = pointCollector1.m_normalOnBInWorld;
}
if (hasResult)
{
SimdScalar dist;
dist = (c-x).length();
if (dist < radius)
{
//penetration
lastLambda = 1.f;
}
//not close enough
while (dist > radius)
@ -153,9 +159,13 @@ bool GjkConvexCast::calcTimeOfImpact(
}
result.m_fraction = lambda;
result.m_normal = n;
return true;
if (lastLambda < 1.f)
{
result.m_fraction = lastLambda;
result.m_normal = n;
return true;
}
}
return false;

@ -29,7 +29,8 @@ GjkPairDetector::GjkPairDetector(ConvexShape* objectA,ConvexShape* objectB,Simpl
m_penetrationDepthSolver(penetrationDepthSolver),
m_simplexSolver(simplexSolver),
m_minkowskiA(objectA),
m_minkowskiB(objectB)
m_minkowskiB(objectB),
m_ignoreMargin(false)
{
}
@ -42,6 +43,13 @@ void GjkPairDetector::GetClosestPoints(const ClosestPointInput& input,Result& ou
float marginA = m_minkowskiA->GetMargin();
float marginB = m_minkowskiB->GetMargin();
//for CCD we don't use margins
if (m_ignoreMargin)
{
marginA = 0.f;
marginB = 0.f;
}
bool isValid = false;
bool checkSimplex = false;
bool checkPenetration = true;

@ -38,6 +38,7 @@ class GjkPairDetector : public DiscreteCollisionDetectorInterface
SimplexSolverInterface* m_simplexSolver;
ConvexShape* m_minkowskiA;
ConvexShape* m_minkowskiB;
bool m_ignoreMargin;
public:
@ -64,6 +65,12 @@ public:
{
m_penetrationDepthSolver = penetrationDepthSolver;
}
void SetIgnoreMargin(bool ignoreMargin)
{
m_ignoreMargin = ignoreMargin;
}
};
#endif //GJK_PAIR_DETECTOR_H

@ -16,20 +16,18 @@ subject to the following restrictions:
#include "RaycastCallback.h"
RaycastCallback::RaycastCallback(const SimdVector3& from,const SimdVector3& to)
TriangleRaycastCallback::TriangleRaycastCallback(const SimdVector3& from,const SimdVector3& to)
:
m_from(from),
m_to(to),
m_hitFraction(1.f),
m_hitProxy(0),
m_hitFound(false)
m_hitFraction(1.f)
{
}
void RaycastCallback::ProcessTriangle(SimdVector3* triangle)
void TriangleRaycastCallback::ProcessTriangle(SimdVector3* triangle,int partId, int triangleIndex)
{
@ -86,17 +84,15 @@ void RaycastCallback::ProcessTriangle(SimdVector3* triangle)
if ( (float)(cp2.dot(triangleNormal)) >=edge_tolerance)
{
m_hitFraction = distance;
if ( dist_a > 0 )
{
m_hitNormalLocal = triangleNormal;
ReportHit(triangleNormal,distance,partId,triangleIndex);
}
else
{
m_hitNormalLocal = -triangleNormal;
ReportHit(-triangleNormal,distance,partId,triangleIndex);
}
m_hitFound= true;
}
}
}

@ -20,26 +20,22 @@ subject to the following restrictions:
struct BroadphaseProxy;
class RaycastCallback: public TriangleCallback
class TriangleRaycastCallback: public TriangleCallback
{
public:
//input
SimdVector3 m_from;
SimdVector3 m_to;
//input / output
SimdScalar m_hitFraction;
BroadphaseProxy* m_hitProxy;
//output
SimdVector3 m_hitNormalLocal;
bool m_hitFound;
RaycastCallback(const SimdVector3& from,const SimdVector3& to);
float m_hitFraction;
TriangleRaycastCallback(const SimdVector3& from,const SimdVector3& to);
virtual void ProcessTriangle(SimdVector3* triangle, int partId, int triangleIndex);
virtual void ReportHit(const SimdVector3& hitNormalLocal, float hitFraction, int partId, int triangleIndex ) = 0;
virtual void ProcessTriangle(SimdVector3* triangle);
};
#endif //RAYCAST_TRI_CALLBACK_H

@ -1,3 +1,18 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "CcdPhysicsController.h"
#include "Dynamics/RigidBody.h"

@ -1,3 +1,18 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BULLET2_PHYSICSCONTROLLER_H
#define BULLET2_PHYSICSCONTROLLER_H

File diff suppressed because it is too large Load Diff

@ -1,3 +1,18 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef CCDPHYSICSENVIRONMENT
#define CCDPHYSICSENVIRONMENT
@ -24,6 +39,7 @@ class PersistentManifold;
class BroadphaseInterface;
class IDebugDraw;
/// CcdPhysicsEnvironment is experimental mainloop for physics simulation using optional continuous collision detection.
/// Physics Environment takes care of stepping the simulation and is a container for physics entities.
/// It stores rigidbodies,constraints, materials etc.
/// A derived class may be able to 'construct' entities by loading and/or converting
@ -147,6 +163,8 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
m_enableSatCollisionDetection = enableSat;
}
void UpdateAabbs(float timeStep);
int GetNumControllers();
CcdPhysicsController* GetPhysicsController( int index);

@ -79,8 +79,10 @@ typedef enum PHY_PhysicsType {
/// PHY_ConstraintType enumerates all supported Constraint Types
typedef enum PHY_ConstraintType {
PHY_POINT2POINT_CONSTRAINT=1,
PHY_LINEHINGE_CONSTRAINT,
PHY_VEHICLE_CONSTRAINT
PHY_LINEHINGE_CONSTRAINT=2,
PHY_ANGULAR_CONSTRAINT = 3,//hinge without ball socket
PHY_VEHICLE_CONSTRAINT=11,//complex 'constraint' that turns a rigidbody into a vehicle
} PHY_ConstraintType;

@ -48,6 +48,7 @@ class IDebugDraw
DBG_ProfileTimings = 128,
DBG_EnableSatComparison = 256,
DBG_DisableBulletLCP = 512,
DBG_EnableCCD = 1024,
DBG_MAX_DEBUG_DRAW_MODE
};

@ -1,3 +1,18 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#include "CcdPhysicsController.h"
#include "Dynamics/RigidBody.h"

@ -1,3 +1,18 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BULLET2_PHYSICSCONTROLLER_H
#define BULLET2_PHYSICSCONTROLLER_H

File diff suppressed because it is too large Load Diff

@ -1,3 +1,18 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef CCDPHYSICSENVIRONMENT
#define CCDPHYSICSENVIRONMENT
@ -24,6 +39,7 @@ class PersistentManifold;
class BroadphaseInterface;
class IDebugDraw;
/// CcdPhysicsEnvironment is experimental mainloop for physics simulation using optional continuous collision detection.
/// Physics Environment takes care of stepping the simulation and is a container for physics entities.
/// It stores rigidbodies,constraints, materials etc.
/// A derived class may be able to 'construct' entities by loading and/or converting
@ -147,6 +163,8 @@ class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
m_enableSatCollisionDetection = enableSat;
}
void UpdateAabbs(float timeStep);
int GetNumControllers();
CcdPhysicsController* GetPhysicsController( int index);