export contact friction/damping through URDF and API
convert from contact friction/damping to cfm/erp btCollisionObject::setContactFrictionAndDamping
This commit is contained in:
@@ -33,6 +33,8 @@ btCollisionObject::btCollisionObject()
|
||||
m_friction(btScalar(0.5)),
|
||||
m_restitution(btScalar(0.)),
|
||||
m_rollingFriction(0.0f),
|
||||
m_contactDamping(.1),
|
||||
m_contactStiffness(1e4),
|
||||
m_internalType(CO_COLLISION_OBJECT),
|
||||
m_userObjectPointer(0),
|
||||
m_userIndex2(-1),
|
||||
@@ -92,6 +94,8 @@ const char* btCollisionObject::serialize(void* dataBuffer, btSerializer* seriali
|
||||
dataOut->m_deactivationTime = m_deactivationTime;
|
||||
dataOut->m_friction = m_friction;
|
||||
dataOut->m_rollingFriction = m_rollingFriction;
|
||||
dataOut->m_contactDamping = m_contactDamping;
|
||||
dataOut->m_contactStiffness = m_contactStiffness;
|
||||
dataOut->m_restitution = m_restitution;
|
||||
dataOut->m_internalType = m_internalType;
|
||||
|
||||
|
||||
@@ -86,6 +86,10 @@ protected:
|
||||
btScalar m_friction;
|
||||
btScalar m_restitution;
|
||||
btScalar m_rollingFriction;
|
||||
btScalar m_contactDamping;
|
||||
btScalar m_contactStiffness;
|
||||
|
||||
|
||||
|
||||
///m_internalType is reserved to distinguish Bullet's btCollisionObject, btRigidBody, btSoftBody, btGhostObject etc.
|
||||
///do not assign your own m_internalType unless you write a new dynamics object class.
|
||||
@@ -129,7 +133,8 @@ public:
|
||||
CF_CUSTOM_MATERIAL_CALLBACK = 8,//this allows per-triangle material (friction/restitution)
|
||||
CF_CHARACTER_OBJECT = 16,
|
||||
CF_DISABLE_VISUALIZE_OBJECT = 32, //disable debug drawing
|
||||
CF_DISABLE_SPU_COLLISION_PROCESSING = 64//disable parallel/SPU processing
|
||||
CF_DISABLE_SPU_COLLISION_PROCESSING = 64,//disable parallel/SPU processing
|
||||
CF_HAS_CONTACT_STIFFNESS_DAMPING = 128
|
||||
};
|
||||
|
||||
enum CollisionObjectTypes
|
||||
@@ -319,7 +324,31 @@ public:
|
||||
return m_rollingFriction;
|
||||
}
|
||||
|
||||
|
||||
void setContactStiffnessAndDamping(btScalar stiffness, btScalar damping)
|
||||
{
|
||||
m_updateRevision++;
|
||||
m_contactStiffness = stiffness;
|
||||
m_contactDamping = damping;
|
||||
|
||||
m_collisionFlags |=CF_HAS_CONTACT_STIFFNESS_DAMPING;
|
||||
|
||||
//avoid divisions by zero...
|
||||
if (m_contactStiffness< SIMD_EPSILON)
|
||||
{
|
||||
m_contactStiffness = SIMD_EPSILON;
|
||||
}
|
||||
}
|
||||
|
||||
btScalar getContactStiffness() const
|
||||
{
|
||||
return m_contactStiffness;
|
||||
}
|
||||
|
||||
btScalar getContactDamping() const
|
||||
{
|
||||
return m_contactDamping;
|
||||
}
|
||||
|
||||
///reserved for Bullet internal usage
|
||||
int getInternalType() const
|
||||
{
|
||||
@@ -541,6 +570,8 @@ struct btCollisionObjectDoubleData
|
||||
double m_deactivationTime;
|
||||
double m_friction;
|
||||
double m_rollingFriction;
|
||||
double m_contactDamping;
|
||||
double m_contactStiffness;
|
||||
double m_restitution;
|
||||
double m_hitFraction;
|
||||
double m_ccdSweptSphereRadius;
|
||||
@@ -574,7 +605,8 @@ struct btCollisionObjectFloatData
|
||||
float m_deactivationTime;
|
||||
float m_friction;
|
||||
float m_rollingFriction;
|
||||
|
||||
float m_contactDamping;
|
||||
float m_contactStiffness;
|
||||
float m_restitution;
|
||||
float m_hitFraction;
|
||||
float m_ccdSweptSphereRadius;
|
||||
|
||||
@@ -25,7 +25,7 @@ ContactAddedCallback gContactAddedCallback=0;
|
||||
|
||||
|
||||
///User can override this material combiner by implementing gContactAddedCallback and setting body0->m_collisionFlags |= btCollisionObject::customMaterialCallback;
|
||||
inline btScalar calculateCombinedRollingFriction(const btCollisionObject* body0,const btCollisionObject* body1)
|
||||
btScalar btManifoldResult::calculateCombinedRollingFriction(const btCollisionObject* body0,const btCollisionObject* body1)
|
||||
{
|
||||
btScalar friction = body0->getRollingFriction() * body1->getRollingFriction();
|
||||
|
||||
@@ -58,6 +58,22 @@ btScalar btManifoldResult::calculateCombinedRestitution(const btCollisionObject*
|
||||
return body0->getRestitution() * body1->getRestitution();
|
||||
}
|
||||
|
||||
btScalar btManifoldResult::calculateCombinedContactDamping(const btCollisionObject* body0,const btCollisionObject* body1)
|
||||
{
|
||||
return body0->getContactDamping() + body1->getContactDamping();
|
||||
}
|
||||
|
||||
btScalar btManifoldResult::calculateCombinedContactStiffness(const btCollisionObject* body0,const btCollisionObject* body1)
|
||||
{
|
||||
|
||||
btScalar s0 = body0->getContactStiffness();
|
||||
btScalar s1 = body1->getContactStiffness();
|
||||
|
||||
btScalar tmp0 = btScalar(1)/s0;
|
||||
btScalar tmp1 = btScalar(1)/s1;
|
||||
btScalar combinedStiffness = btScalar(1) / (tmp0+tmp1);
|
||||
return combinedStiffness;
|
||||
}
|
||||
|
||||
|
||||
btManifoldResult::btManifoldResult(const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
|
||||
@@ -109,6 +125,15 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b
|
||||
newPt.m_combinedFriction = calculateCombinedFriction(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject());
|
||||
newPt.m_combinedRestitution = calculateCombinedRestitution(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject());
|
||||
newPt.m_combinedRollingFriction = calculateCombinedRollingFriction(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject());
|
||||
|
||||
if ( (m_body0Wrap->getCollisionObject()->getCollisionFlags()& btCollisionObject::CF_HAS_CONTACT_STIFFNESS_DAMPING) ||
|
||||
(m_body1Wrap->getCollisionObject()->getCollisionFlags()& btCollisionObject::CF_HAS_CONTACT_STIFFNESS_DAMPING))
|
||||
{
|
||||
newPt.m_combinedContactDamping1 = calculateCombinedContactDamping(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject());
|
||||
newPt.m_combinedContactStiffness1 = calculateCombinedContactStiffness(m_body0Wrap->getCollisionObject(),m_body1Wrap->getCollisionObject());
|
||||
newPt.m_contactPointFlags |= BT_CONTACT_FLAG_CONTACT_STIFFNESS_DAMPING;
|
||||
}
|
||||
|
||||
btPlaneSpace1(newPt.m_normalWorldOnB,newPt.m_lateralFrictionDir1,newPt.m_lateralFrictionDir2);
|
||||
|
||||
|
||||
|
||||
@@ -145,6 +145,9 @@ public:
|
||||
/// in the future we can let the user override the methods to combine restitution and friction
|
||||
static btScalar calculateCombinedRestitution(const btCollisionObject* body0,const btCollisionObject* body1);
|
||||
static btScalar calculateCombinedFriction(const btCollisionObject* body0,const btCollisionObject* body1);
|
||||
static btScalar calculateCombinedRollingFriction(const btCollisionObject* body0,const btCollisionObject* body1);
|
||||
static btScalar calculateCombinedContactDamping(const btCollisionObject* body0,const btCollisionObject* body1);
|
||||
static btScalar calculateCombinedContactStiffness(const btCollisionObject* body0,const btCollisionObject* body1);
|
||||
};
|
||||
|
||||
#endif //BT_MANIFOLD_RESULT_H
|
||||
|
||||
@@ -40,6 +40,7 @@ enum btContactPointFlags
|
||||
BT_CONTACT_FLAG_LATERAL_FRICTION_INITIALIZED=1,
|
||||
BT_CONTACT_FLAG_HAS_CONTACT_CFM=2,
|
||||
BT_CONTACT_FLAG_HAS_CONTACT_ERP=4,
|
||||
BT_CONTACT_FLAG_CONTACT_STIFFNESS_DAMPING = 8,
|
||||
};
|
||||
|
||||
/// ManifoldContactPoint collects and maintains persistent contactpoints.
|
||||
@@ -116,8 +117,18 @@ class btManifoldPoint
|
||||
btScalar m_appliedImpulseLateral2;
|
||||
btScalar m_contactMotion1;
|
||||
btScalar m_contactMotion2;
|
||||
btScalar m_contactCFM;
|
||||
btScalar m_contactERP;
|
||||
|
||||
union
|
||||
{
|
||||
btScalar m_contactCFM;
|
||||
btScalar m_combinedContactStiffness1;
|
||||
};
|
||||
|
||||
union
|
||||
{
|
||||
btScalar m_contactERP;
|
||||
btScalar m_combinedContactDamping1;
|
||||
};
|
||||
|
||||
btScalar m_frictionCFM;
|
||||
|
||||
|
||||
Reference in New Issue
Block a user