added initial support for per-triangle material properties in a non-convex mesh. needs testing.
This commit is contained in:
@@ -3,7 +3,6 @@
|
|||||||
//Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
//Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// AxisSweep3
|
// AxisSweep3
|
||||||
//
|
//
|
||||||
|
|||||||
@@ -14,8 +14,8 @@ subject to the following restrictions:
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#include "SimpleBroadphase.h"
|
#include "SimpleBroadphase.h"
|
||||||
#include "BroadphaseCollision/Dispatcher.h"
|
#include <BroadphaseCollision/Dispatcher.h>
|
||||||
#include "BroadphaseCollision/CollisionAlgorithm.h"
|
#include <BroadphaseCollision/CollisionAlgorithm.h>
|
||||||
|
|
||||||
#include "SimdVector3.h"
|
#include "SimdVector3.h"
|
||||||
#include "SimdTransform.h"
|
#include "SimdTransform.h"
|
||||||
|
|||||||
@@ -45,7 +45,7 @@ struct CollisionObject
|
|||||||
{
|
{
|
||||||
isStatic = 1,
|
isStatic = 1,
|
||||||
noContactResponse = 2,
|
noContactResponse = 2,
|
||||||
|
customMaterialCallback = 4,//this allows per-triangle material (friction/restitution)
|
||||||
};
|
};
|
||||||
|
|
||||||
int m_collisionFlags;
|
int m_collisionFlags;
|
||||||
@@ -54,6 +54,9 @@ struct CollisionObject
|
|||||||
int m_activationState1;
|
int m_activationState1;
|
||||||
float m_deactivationTime;
|
float m_deactivationTime;
|
||||||
|
|
||||||
|
SimdScalar m_friction;
|
||||||
|
SimdScalar m_restitution;
|
||||||
|
|
||||||
BroadphaseProxy* m_broadphaseHandle;
|
BroadphaseProxy* m_broadphaseHandle;
|
||||||
CollisionShape* m_collisionShape;
|
CollisionShape* m_collisionShape;
|
||||||
|
|
||||||
@@ -102,6 +105,23 @@ struct CollisionObject
|
|||||||
return ((GetActivationState() != ISLAND_SLEEPING) && (GetActivationState() != DISABLE_SIMULATION));
|
return ((GetActivationState() != ISLAND_SLEEPING) && (GetActivationState() != DISABLE_SIMULATION));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void setRestitution(float rest)
|
||||||
|
{
|
||||||
|
m_restitution = rest;
|
||||||
|
}
|
||||||
|
float getRestitution() const
|
||||||
|
{
|
||||||
|
return m_restitution;
|
||||||
|
}
|
||||||
|
void setFriction(float frict)
|
||||||
|
{
|
||||||
|
m_friction = frict;
|
||||||
|
}
|
||||||
|
float getFriction() const
|
||||||
|
{
|
||||||
|
return m_friction;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -112,6 +112,7 @@ void ConvexTriangleCallback::ProcessTriangle(SimdVector3* triangle,int partId, i
|
|||||||
ob->m_collisionShape = &tm;
|
ob->m_collisionShape = &tm;
|
||||||
|
|
||||||
ConvexConvexAlgorithm cvxcvxalgo(m_manifoldPtr,ci,m_convexProxy,&m_triangleProxy);
|
ConvexConvexAlgorithm cvxcvxalgo(m_manifoldPtr,ci,m_convexProxy,&m_triangleProxy);
|
||||||
|
cvxcvxalgo.SetShapeIdentifiers(-1,-1,partId,triangleIndex);
|
||||||
cvxcvxalgo.ProcessCollision(m_convexProxy,&m_triangleProxy,*m_dispatchInfoPtr);
|
cvxcvxalgo.ProcessCollision(m_convexProxy,&m_triangleProxy,*m_dispatchInfoPtr);
|
||||||
ob->m_collisionShape = tmpShape;
|
ob->m_collisionShape = tmpShape;
|
||||||
|
|
||||||
|
|||||||
@@ -55,7 +55,13 @@ public:
|
|||||||
|
|
||||||
void SetLowLevelOfDetail(bool useLowLevel);
|
void SetLowLevelOfDetail(bool useLowLevel);
|
||||||
|
|
||||||
|
virtual void SetShapeIdentifiers(int partId0,int index0, int partId1,int index1)
|
||||||
|
{
|
||||||
|
m_gjkPairDetector.m_partId0=partId0;
|
||||||
|
m_gjkPairDetector.m_partId1=partId1;
|
||||||
|
m_gjkPairDetector.m_index0=index0;
|
||||||
|
m_gjkPairDetector.m_index1=index1;
|
||||||
|
}
|
||||||
|
|
||||||
const PersistentManifold* GetManifold()
|
const PersistentManifold* GetManifold()
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -18,6 +18,31 @@ subject to the following restrictions:
|
|||||||
#include "NarrowPhaseCollision/PersistentManifold.h"
|
#include "NarrowPhaseCollision/PersistentManifold.h"
|
||||||
#include "CollisionDispatch/CollisionObject.h"
|
#include "CollisionDispatch/CollisionObject.h"
|
||||||
|
|
||||||
|
|
||||||
|
///This is to allow MaterialCombiner/Custom Friction/Restitution values
|
||||||
|
ContactAddedCallback gContactAddedCallback=0;
|
||||||
|
|
||||||
|
///User can override this material combiner by implementing gContactAddedCallback and setting body0->m_collisionFlags |= CollisionObject::customMaterialCallback;
|
||||||
|
inline SimdScalar calculateCombinedFriction(const CollisionObject* body0,const CollisionObject* body1)
|
||||||
|
{
|
||||||
|
SimdScalar friction = body0->getFriction() * body1->getFriction();
|
||||||
|
|
||||||
|
const SimdScalar MAX_FRICTION = 10.f;
|
||||||
|
if (friction < -MAX_FRICTION)
|
||||||
|
friction = -MAX_FRICTION;
|
||||||
|
if (friction > MAX_FRICTION)
|
||||||
|
friction = MAX_FRICTION;
|
||||||
|
return friction;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
inline SimdScalar calculateCombinedRestitution(const CollisionObject* body0,const CollisionObject* body1)
|
||||||
|
{
|
||||||
|
return body0->getRestitution() * body1->getRestitution();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
ManifoldResult::ManifoldResult(CollisionObject* body0,CollisionObject* body1,PersistentManifold* manifoldPtr)
|
ManifoldResult::ManifoldResult(CollisionObject* body0,CollisionObject* body1,PersistentManifold* manifoldPtr)
|
||||||
:m_manifoldPtr(manifoldPtr),
|
:m_manifoldPtr(manifoldPtr),
|
||||||
m_body0(body0),
|
m_body0(body0),
|
||||||
@@ -56,6 +81,20 @@ void ManifoldResult::AddContactPoint(const SimdVector3& normalOnBInWorld,const S
|
|||||||
|
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
|
|
||||||
|
newPt.m_combinedFriction = calculateCombinedFriction(m_body0,m_body1);
|
||||||
|
newPt.m_combinedRestitution = calculateCombinedRestitution(m_body0,m_body1);
|
||||||
|
|
||||||
|
//User can override friction and/or restitution
|
||||||
|
if (gContactAddedCallback &&
|
||||||
|
//and if either of the two bodies requires custom material
|
||||||
|
((m_body0->m_collisionFlags & CollisionObject::customMaterialCallback) ||
|
||||||
|
(m_body1->m_collisionFlags & CollisionObject::customMaterialCallback)))
|
||||||
|
{
|
||||||
|
//experimental feature info, for per-triangle material etc.
|
||||||
|
(*gContactAddedCallback)(newPt,m_body0,m_partId0,m_index0,m_body1,m_partId1,m_index1);
|
||||||
|
}
|
||||||
|
|
||||||
m_manifoldPtr->AddManifoldPoint(newPt);
|
m_manifoldPtr->AddManifoldPoint(newPt);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -20,8 +20,10 @@ subject to the following restrictions:
|
|||||||
#include "NarrowPhaseCollision/DiscreteCollisionDetectorInterface.h"
|
#include "NarrowPhaseCollision/DiscreteCollisionDetectorInterface.h"
|
||||||
struct CollisionObject;
|
struct CollisionObject;
|
||||||
class PersistentManifold;
|
class PersistentManifold;
|
||||||
|
class ManifoldPoint;
|
||||||
|
|
||||||
|
typedef bool (*ContactAddedCallback)(ManifoldPoint& cp, const CollisionObject* colObj0,int partId0,int index0,const CollisionObject* colObj1,int partId1,int index1);
|
||||||
|
extern ContactAddedCallback gContactAddedCallback;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@@ -31,15 +33,28 @@ class ManifoldResult : public DiscreteCollisionDetectorInterface::Result
|
|||||||
PersistentManifold* m_manifoldPtr;
|
PersistentManifold* m_manifoldPtr;
|
||||||
CollisionObject* m_body0;
|
CollisionObject* m_body0;
|
||||||
CollisionObject* m_body1;
|
CollisionObject* m_body1;
|
||||||
|
int m_partId0;
|
||||||
|
int m_partId1;
|
||||||
|
int m_index0;
|
||||||
|
int m_index1;
|
||||||
public:
|
public:
|
||||||
|
|
||||||
ManifoldResult(CollisionObject* body0,CollisionObject* body1,PersistentManifold* manifoldPtr);
|
ManifoldResult(CollisionObject* body0,CollisionObject* body1,PersistentManifold* manifoldPtr);
|
||||||
|
|
||||||
virtual ~ManifoldResult() {};
|
virtual ~ManifoldResult() {};
|
||||||
|
|
||||||
|
virtual void SetShapeIdentifiers(int partId0,int index0, int partId1,int index1)
|
||||||
|
{
|
||||||
|
m_partId0=partId0;
|
||||||
|
m_partId1=partId1;
|
||||||
|
m_index0=index0;
|
||||||
|
m_index1=index1;
|
||||||
|
}
|
||||||
|
|
||||||
virtual void AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth);
|
virtual void AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif //MANIFOLD_RESULT_H
|
#endif //MANIFOLD_RESULT_H
|
||||||
|
|||||||
@@ -34,6 +34,9 @@ struct DiscreteCollisionDetectorInterface
|
|||||||
void operator delete(void* ptr) {};
|
void operator delete(void* ptr) {};
|
||||||
|
|
||||||
virtual ~Result(){}
|
virtual ~Result(){}
|
||||||
|
|
||||||
|
///SetShapeIdentifiers provides experimental support for per-triangle material / custom material combiner
|
||||||
|
virtual void SetShapeIdentifiers(int partId0,int index0, int partId1,int index1)=0;
|
||||||
virtual void AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth)=0;
|
virtual void AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth)=0;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -35,7 +35,11 @@ m_penetrationDepthSolver(penetrationDepthSolver),
|
|||||||
m_simplexSolver(simplexSolver),
|
m_simplexSolver(simplexSolver),
|
||||||
m_minkowskiA(objectA),
|
m_minkowskiA(objectA),
|
||||||
m_minkowskiB(objectB),
|
m_minkowskiB(objectB),
|
||||||
m_ignoreMargin(false)
|
m_ignoreMargin(false),
|
||||||
|
m_partId0(-1),
|
||||||
|
m_index0(-1),
|
||||||
|
m_partId1(-1),
|
||||||
|
m_index1(-1)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -207,6 +211,8 @@ int curIter = 0;
|
|||||||
|
|
||||||
if (isValid)
|
if (isValid)
|
||||||
{
|
{
|
||||||
|
output.SetShapeIdentifiers(m_partId0,m_index0,m_partId1,m_index1);
|
||||||
|
|
||||||
output.AddContactPoint(
|
output.AddContactPoint(
|
||||||
normalInB,
|
normalInB,
|
||||||
pointOnB,
|
pointOnB,
|
||||||
|
|||||||
@@ -40,8 +40,16 @@ class GjkPairDetector : public DiscreteCollisionDetectorInterface
|
|||||||
ConvexShape* m_minkowskiB;
|
ConvexShape* m_minkowskiB;
|
||||||
bool m_ignoreMargin;
|
bool m_ignoreMargin;
|
||||||
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
|
//experimental feature information, per triangle, per convex etc.
|
||||||
|
//'material combiner' / contact added callback
|
||||||
|
int m_partId0;
|
||||||
|
int m_index0;
|
||||||
|
int m_partId1;
|
||||||
|
int m_index1;
|
||||||
|
|
||||||
GjkPairDetector(ConvexShape* objectA,ConvexShape* objectB,SimplexSolverInterface* simplexSolver,ConvexPenetrationDepthSolver* penetrationDepthSolver);
|
GjkPairDetector(ConvexShape* objectA,ConvexShape* objectB,SimplexSolverInterface* simplexSolver,ConvexPenetrationDepthSolver* penetrationDepthSolver);
|
||||||
virtual ~GjkPairDetector() {};
|
virtual ~GjkPairDetector() {};
|
||||||
|
|
||||||
|
|||||||
@@ -40,6 +40,8 @@ class ManifoldPoint
|
|||||||
m_localPointB( pointB ),
|
m_localPointB( pointB ),
|
||||||
m_normalWorldOnB( normal ),
|
m_normalWorldOnB( normal ),
|
||||||
m_distance1( distance ),
|
m_distance1( distance ),
|
||||||
|
m_combinedFriction(0.f),
|
||||||
|
m_combinedRestitution(0.f),
|
||||||
m_userPersistentData(0),
|
m_userPersistentData(0),
|
||||||
m_lifeTime(0)
|
m_lifeTime(0)
|
||||||
{
|
{
|
||||||
@@ -57,6 +59,8 @@ class ManifoldPoint
|
|||||||
SimdVector3 m_normalWorldOnB;
|
SimdVector3 m_normalWorldOnB;
|
||||||
|
|
||||||
float m_distance1;
|
float m_distance1;
|
||||||
|
float m_combinedFriction;
|
||||||
|
float m_combinedRestitution;
|
||||||
|
|
||||||
|
|
||||||
void* m_userPersistentData;
|
void* m_userPersistentData;
|
||||||
|
|||||||
@@ -32,6 +32,9 @@ struct MyResult : public DiscreteCollisionDetectorInterface::Result
|
|||||||
float m_depth;
|
float m_depth;
|
||||||
bool m_hasResult;
|
bool m_hasResult;
|
||||||
|
|
||||||
|
virtual void SetShapeIdentifiers(int partId0,int index0, int partId1,int index1)
|
||||||
|
{
|
||||||
|
}
|
||||||
void AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth)
|
void AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth)
|
||||||
{
|
{
|
||||||
m_normalOnBInWorld = normalOnBInWorld;
|
m_normalOnBInWorld = normalOnBInWorld;
|
||||||
|
|||||||
@@ -19,7 +19,8 @@ subject to the following restrictions:
|
|||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
|
|
||||||
float gContactBreakingTreshold = 0.02f;
|
float gContactBreakingTreshold = 0.02f;
|
||||||
ContactDestroyedCallback gContactCallback = 0;
|
ContactDestroyedCallback gContactDestroyedCallback = 0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
PersistentManifold::PersistentManifold()
|
PersistentManifold::PersistentManifold()
|
||||||
@@ -75,9 +76,9 @@ void PersistentManifold::ClearUserCache(ManifoldPoint& pt)
|
|||||||
assert(occurance<=0);
|
assert(occurance<=0);
|
||||||
#endif //DEBUG_PERSISTENCY
|
#endif //DEBUG_PERSISTENCY
|
||||||
|
|
||||||
if (pt.m_userPersistentData && gContactCallback)
|
if (pt.m_userPersistentData && gContactDestroyedCallback)
|
||||||
{
|
{
|
||||||
(*gContactCallback)(pt.m_userPersistentData);
|
(*gContactDestroyedCallback)(pt.m_userPersistentData);
|
||||||
pt.m_userPersistentData = 0;
|
pt.m_userPersistentData = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -27,8 +27,8 @@ struct CollisionResult;
|
|||||||
extern float gContactBreakingTreshold;
|
extern float gContactBreakingTreshold;
|
||||||
|
|
||||||
typedef bool (*ContactDestroyedCallback)(void* userPersistentData);
|
typedef bool (*ContactDestroyedCallback)(void* userPersistentData);
|
||||||
|
extern ContactDestroyedCallback gContactDestroyedCallback;
|
||||||
|
|
||||||
extern ContactDestroyedCallback gContactCallback;
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -35,6 +35,11 @@ struct PointCollector : public DiscreteCollisionDetectorInterface::Result
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
virtual void SetShapeIdentifiers(int partId0,int index0, int partId1,int index1)
|
||||||
|
{
|
||||||
|
//??
|
||||||
|
}
|
||||||
|
|
||||||
virtual void AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth)
|
virtual void AddContactPoint(const SimdVector3& normalOnBInWorld,const SimdVector3& pointInWorld,float depth)
|
||||||
{
|
{
|
||||||
if (depth< m_distance)
|
if (depth< m_distance)
|
||||||
|
|||||||
@@ -33,18 +33,7 @@ SimdScalar contactTau = .02f;//0.02f;//*0.02f;
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
SimdScalar calculateCombinedFriction(RigidBody& body0,RigidBody& body1)
|
|
||||||
{
|
|
||||||
SimdScalar friction = body0.getFriction() * body1.getFriction();
|
|
||||||
|
|
||||||
const SimdScalar MAX_FRICTION = 10.f;
|
|
||||||
if (friction < -MAX_FRICTION)
|
|
||||||
friction = -MAX_FRICTION;
|
|
||||||
if (friction > MAX_FRICTION)
|
|
||||||
friction = MAX_FRICTION;
|
|
||||||
return friction;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
//bilateral constraint between two dynamic objects
|
//bilateral constraint between two dynamic objects
|
||||||
@@ -128,9 +117,6 @@ float resolveSingleCollision(
|
|||||||
SimdScalar rel_vel;
|
SimdScalar rel_vel;
|
||||||
rel_vel = normal.dot(vel);
|
rel_vel = normal.dot(vel);
|
||||||
|
|
||||||
float combinedRestitution = body1.getRestitution() * body2.getRestitution();
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
SimdScalar Kfps = 1.f / solverInfo.m_timeStep ;
|
SimdScalar Kfps = 1.f / solverInfo.m_timeStep ;
|
||||||
|
|
||||||
@@ -187,17 +173,19 @@ float resolveSingleFriction(
|
|||||||
|
|
||||||
)
|
)
|
||||||
{
|
{
|
||||||
|
|
||||||
const SimdVector3& pos1 = contactPoint.GetPositionWorldOnA();
|
const SimdVector3& pos1 = contactPoint.GetPositionWorldOnA();
|
||||||
const SimdVector3& pos2 = contactPoint.GetPositionWorldOnB();
|
const SimdVector3& pos2 = contactPoint.GetPositionWorldOnB();
|
||||||
const SimdVector3& normal = contactPoint.m_normalWorldOnB;
|
const SimdVector3& normal = contactPoint.m_normalWorldOnB;
|
||||||
|
|
||||||
SimdVector3 rel_pos1 = pos1 - body1.getCenterOfMassPosition();
|
SimdVector3 rel_pos1 = pos1 - body1.getCenterOfMassPosition();
|
||||||
SimdVector3 rel_pos2 = pos2 - body2.getCenterOfMassPosition();
|
SimdVector3 rel_pos2 = pos2 - body2.getCenterOfMassPosition();
|
||||||
float combinedFriction = calculateCombinedFriction(body1,body2);
|
|
||||||
|
|
||||||
ConstraintPersistentData* cpd = (ConstraintPersistentData*) contactPoint.m_userPersistentData;
|
ConstraintPersistentData* cpd = (ConstraintPersistentData*) contactPoint.m_userPersistentData;
|
||||||
assert(cpd);
|
assert(cpd);
|
||||||
|
|
||||||
|
float combinedFriction = cpd->m_friction;
|
||||||
|
|
||||||
SimdScalar limit = cpd->m_appliedImpulse * combinedFriction;
|
SimdScalar limit = cpd->m_appliedImpulse * combinedFriction;
|
||||||
//if (contactPoint.m_appliedImpulse>0.f)
|
//if (contactPoint.m_appliedImpulse>0.f)
|
||||||
//friction
|
//friction
|
||||||
|
|||||||
@@ -34,6 +34,7 @@ struct ConstraintPersistentData
|
|||||||
m_jacDiagABInv(0.f),
|
m_jacDiagABInv(0.f),
|
||||||
m_persistentLifeTime(0),
|
m_persistentLifeTime(0),
|
||||||
m_restitution(0.f),
|
m_restitution(0.f),
|
||||||
|
m_friction(0.f),
|
||||||
m_penetration(0.f)
|
m_penetration(0.f)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
@@ -50,6 +51,7 @@ struct ConstraintPersistentData
|
|||||||
float m_jacDiagABInvTangent1;
|
float m_jacDiagABInvTangent1;
|
||||||
int m_persistentLifeTime;
|
int m_persistentLifeTime;
|
||||||
float m_restitution;
|
float m_restitution;
|
||||||
|
float m_friction;
|
||||||
float m_penetration;
|
float m_penetration;
|
||||||
SimdVector3 m_frictionWorldTangential0;
|
SimdVector3 m_frictionWorldTangential0;
|
||||||
SimdVector3 m_frictionWorldTangential1;
|
SimdVector3 m_frictionWorldTangential1;
|
||||||
|
|||||||
@@ -47,7 +47,7 @@ bool MyContactDestroyedCallback(void* userPersistentData)
|
|||||||
|
|
||||||
SequentialImpulseConstraintSolver::SequentialImpulseConstraintSolver()
|
SequentialImpulseConstraintSolver::SequentialImpulseConstraintSolver()
|
||||||
{
|
{
|
||||||
gContactCallback = &MyContactDestroyedCallback;
|
gContactDestroyedCallback = &MyContactDestroyedCallback;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -188,10 +188,10 @@ float SequentialImpulseConstraintSolver::Solve(PersistentManifold* manifoldPtr,
|
|||||||
SimdScalar rel_vel;
|
SimdScalar rel_vel;
|
||||||
rel_vel = cp.m_normalWorldOnB.dot(vel);
|
rel_vel = cp.m_normalWorldOnB.dot(vel);
|
||||||
|
|
||||||
float combinedRestitution = body0->getRestitution() * body1->getRestitution();
|
float combinedRestitution = cp.m_combinedRestitution;
|
||||||
|
|
||||||
cpd->m_penetration = cp.GetDistance();
|
cpd->m_penetration = cp.GetDistance();
|
||||||
|
cpd->m_friction = cp.m_combinedFriction;
|
||||||
cpd->m_restitution = restitutionCurve(rel_vel, combinedRestitution);
|
cpd->m_restitution = restitutionCurve(rel_vel, combinedRestitution);
|
||||||
if (cpd->m_restitution <= 0.) //0.f)
|
if (cpd->m_restitution <= 0.) //0.f)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -178,7 +178,7 @@ void ContactJoint::GetInfo2(Info2 *info)
|
|||||||
c2[1] = relativePositionB[1];
|
c2[1] = relativePositionB[1];
|
||||||
c2[2] = relativePositionB[2];
|
c2[2] = relativePositionB[2];
|
||||||
|
|
||||||
|
//combined friction is available in the contact point
|
||||||
float friction = FRICTION_CONSTANT*m_body0->getFriction() * m_body1->getFriction();
|
float friction = FRICTION_CONSTANT*m_body0->getFriction() * m_body1->getFriction();
|
||||||
|
|
||||||
// first friction direction
|
// first friction direction
|
||||||
|
|||||||
@@ -32,10 +32,13 @@ RigidBody::RigidBody( const MassProps& massProps,SimdScalar linearDamping,SimdSc
|
|||||||
m_angularVelocity(0.f,0.f,0.f),
|
m_angularVelocity(0.f,0.f,0.f),
|
||||||
m_linearDamping(0.f),
|
m_linearDamping(0.f),
|
||||||
m_angularDamping(0.5f),
|
m_angularDamping(0.5f),
|
||||||
m_friction(friction),
|
|
||||||
m_restitution(restitution),
|
|
||||||
m_kinematicTimeStep(0.f)
|
m_kinematicTimeStep(0.f)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
//moved to CollisionObject
|
||||||
|
m_friction = friction;
|
||||||
|
m_restitution = restitution;
|
||||||
|
|
||||||
m_debugBodyId = uniqueId++;
|
m_debugBodyId = uniqueId++;
|
||||||
|
|
||||||
setMassProps(massProps.m_mass, massProps.m_inertiaLocal);
|
setMassProps(massProps.m_mass, massProps.m_inertiaLocal);
|
||||||
|
|||||||
@@ -172,22 +172,7 @@ public:
|
|||||||
void getAabb(SimdVector3& aabbMin,SimdVector3& aabbMax) const;
|
void getAabb(SimdVector3& aabbMin,SimdVector3& aabbMax) const;
|
||||||
|
|
||||||
|
|
||||||
void setRestitution(float rest)
|
|
||||||
{
|
|
||||||
m_restitution = rest;
|
|
||||||
}
|
|
||||||
float getRestitution() const
|
|
||||||
{
|
|
||||||
return m_restitution;
|
|
||||||
}
|
|
||||||
void setFriction(float frict)
|
|
||||||
{
|
|
||||||
m_friction = frict;
|
|
||||||
}
|
|
||||||
float getFriction() const
|
|
||||||
{
|
|
||||||
return m_friction;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
inline float ComputeImpulseDenominator(const SimdPoint3& pos, const SimdVector3& normal) const
|
inline float ComputeImpulseDenominator(const SimdPoint3& pos, const SimdVector3& normal) const
|
||||||
@@ -227,8 +212,6 @@ private:
|
|||||||
SimdScalar m_angularDamping;
|
SimdScalar m_angularDamping;
|
||||||
SimdScalar m_inverseMass;
|
SimdScalar m_inverseMass;
|
||||||
|
|
||||||
SimdScalar m_friction;
|
|
||||||
SimdScalar m_restitution;
|
|
||||||
|
|
||||||
SimdScalar m_kinematicTimeStep;
|
SimdScalar m_kinematicTimeStep;
|
||||||
|
|
||||||
|
|||||||
@@ -91,9 +91,69 @@ static const int NUM_TRIANGLES=4;
|
|||||||
|
|
||||||
SimdVector3 gVertices[NUM_VERTICES];
|
SimdVector3 gVertices[NUM_VERTICES];
|
||||||
int gIndices[NUM_TRIANGLES*3];
|
int gIndices[NUM_TRIANGLES*3];
|
||||||
|
const float TRIANGLE_SIZE=80.f;
|
||||||
|
|
||||||
|
|
||||||
|
///User can override this material combiner by implementing gContactAddedCallback and setting body0->m_collisionFlags |= CollisionObject::customMaterialCallback;
|
||||||
|
inline SimdScalar calculateCombinedFriction(float friction0,float friction1)
|
||||||
|
{
|
||||||
|
SimdScalar friction = friction0 * friction1;
|
||||||
|
|
||||||
|
const SimdScalar MAX_FRICTION = 10.f;
|
||||||
|
if (friction < -MAX_FRICTION)
|
||||||
|
friction = -MAX_FRICTION;
|
||||||
|
if (friction > MAX_FRICTION)
|
||||||
|
friction = MAX_FRICTION;
|
||||||
|
return friction;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
inline SimdScalar calculateCombinedRestitution(float restitution0,float restitution1)
|
||||||
|
{
|
||||||
|
return restitution0 * restitution1;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
bool CustomMaterialCombinerCallback(ManifoldPoint& cp, const CollisionObject* colObj0,int partId0,int index0,const CollisionObject* colObj1,int partId1,int index1)
|
||||||
|
{
|
||||||
|
|
||||||
|
float friction0 = colObj0->getFriction();
|
||||||
|
float friction1 = colObj1->getFriction();
|
||||||
|
float restitution0 = colObj0->getRestitution();
|
||||||
|
float restitution1 = colObj1->getRestitution();
|
||||||
|
|
||||||
|
if (colObj0->m_collisionFlags & CollisionObject::customMaterialCallback)
|
||||||
|
{
|
||||||
|
friction0 = 1.0;//partId0,index0
|
||||||
|
restitution0 = 0.f;
|
||||||
|
}
|
||||||
|
if (colObj1->m_collisionFlags & CollisionObject::customMaterialCallback)
|
||||||
|
{
|
||||||
|
if (index1&1)
|
||||||
|
{
|
||||||
|
friction1 = 1.0f;//partId1,index1
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
friction1 = 0.f;
|
||||||
|
}
|
||||||
|
restitution1 = 0.f;
|
||||||
|
}
|
||||||
|
|
||||||
|
cp.m_combinedFriction = calculateCombinedFriction(friction0,friction1);
|
||||||
|
cp.m_combinedRestitution = calculateCombinedRestitution(restitution0,restitution1);
|
||||||
|
|
||||||
|
//this return value is currently ignored, but to be on the safe side: return false if you don't calculate friction
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
extern ContactAddedCallback gContactAddedCallback;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
int main(int argc,char** argv)
|
int main(int argc,char** argv)
|
||||||
{
|
{
|
||||||
|
gContactAddedCallback = CustomMaterialCombinerCallback;
|
||||||
|
|
||||||
printf("BroadphaseProxy: %i\n",sizeof(BroadphaseProxy));
|
printf("BroadphaseProxy: %i\n",sizeof(BroadphaseProxy));
|
||||||
printf("AxisSweep3::Handle : %i\n",sizeof(AxisSweep3::Handle));
|
printf("AxisSweep3::Handle : %i\n",sizeof(AxisSweep3::Handle));
|
||||||
@@ -190,7 +250,7 @@ int main(int argc,char** argv)
|
|||||||
{
|
{
|
||||||
for (int j=0;j<NUM_VERTS_Y;j++)
|
for (int j=0;j<NUM_VERTS_Y;j++)
|
||||||
{
|
{
|
||||||
gVertices[i+j*NUM_VERTS_X].setValue((i-NUM_VERTS_X*0.5f)*10.f,2.f*sinf((float)i)*cosf((float)j),(j-NUM_VERTS_Y*0.5f)*10.f);
|
gVertices[i+j*NUM_VERTS_X].setValue((i-NUM_VERTS_X*0.5f)*TRIANGLE_SIZE,2.f*sinf((float)i)*cosf((float)j),(j-NUM_VERTS_Y*0.5f)*TRIANGLE_SIZE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -280,11 +340,13 @@ int main(int argc,char** argv)
|
|||||||
|
|
||||||
if (!i)
|
if (!i)
|
||||||
{
|
{
|
||||||
|
ccdObjectCi.m_friction = 0.0f;
|
||||||
//SimdQuaternion orn(0,0,0.1*SIMD_HALF_PI);
|
//SimdQuaternion orn(0,0,0.1*SIMD_HALF_PI);
|
||||||
//ms[i].setWorldOrientation(orn.x(),orn.y(),orn.z(),orn[3]);
|
//ms[i].setWorldOrientation(orn.x(),orn.y(),orn.z(),orn[3]);
|
||||||
//ms[i].setWorldPosition(0,-10,0);
|
//ms[i].setWorldPosition(0,-10,0);
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
|
ccdObjectCi.m_friction = 0.5f;
|
||||||
ms[i].setWorldPosition(10,i*15-10,0);
|
ms[i].setWorldPosition(10,i*15-10,0);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -299,11 +361,14 @@ int main(int argc,char** argv)
|
|||||||
{
|
{
|
||||||
shapeProps.m_mass = 0.f;
|
shapeProps.m_mass = 0.f;
|
||||||
ccdObjectCi.m_mass = shapeProps.m_mass;
|
ccdObjectCi.m_mass = shapeProps.m_mass;
|
||||||
|
ccdObjectCi.m_collisionFlags = CollisionObject::customMaterialCallback;
|
||||||
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
shapeProps.m_mass = 1.f;
|
shapeProps.m_mass = 1.f;
|
||||||
ccdObjectCi.m_mass = shapeProps.m_mass;
|
ccdObjectCi.m_mass = shapeProps.m_mass;
|
||||||
|
ccdObjectCi.m_collisionFlags =0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -315,12 +380,12 @@ int main(int argc,char** argv)
|
|||||||
{
|
{
|
||||||
localInertia.setValue(0.f,0.f,0.f);
|
localInertia.setValue(0.f,0.f,0.f);
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
ccdObjectCi.m_localInertiaTensor = localInertia;
|
ccdObjectCi.m_localInertiaTensor = localInertia;
|
||||||
|
|
||||||
ccdObjectCi.m_collisionShape = shapePtr[shapeIndex[i]];
|
ccdObjectCi.m_collisionShape = shapePtr[shapeIndex[i]];
|
||||||
|
|
||||||
|
|
||||||
physObjects[i]= new CcdPhysicsController( ccdObjectCi);
|
physObjects[i]= new CcdPhysicsController( ccdObjectCi);
|
||||||
physicsEnvironmentPtr->addCcdPhysicsController( physObjects[i]);
|
physicsEnvironmentPtr->addCcdPhysicsController( physObjects[i]);
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user