rename treshold into thresold (spelling mistake)

added cr/linefeed at end of btDefaultMotionState.h
This commit is contained in:
ejcoumans
2006-10-30 05:06:46 +00:00
parent dd8297c86e
commit b14ccdaa57
14 changed files with 40 additions and 40 deletions

View File

@@ -356,7 +356,7 @@ void CcdPhysicsDemo::initPhysics()
// Only do CCD if motion in one timestep (1.f/60.f) exceeds CUBE_HALF_EXTENTS // Only do CCD if motion in one timestep (1.f/60.f) exceeds CUBE_HALF_EXTENTS
body->m_ccdSquareMotionTreshold = CUBE_HALF_EXTENTS; body->m_ccdSquareMotionThreshold = CUBE_HALF_EXTENTS;
//Experimental: better estimation of CCD Time of Impact: //Experimental: better estimation of CCD Time of Impact:
body->m_ccdSweptSphereRadius = 0.2*CUBE_HALF_EXTENTS; body->m_ccdSweptSphereRadius = 0.2*CUBE_HALF_EXTENTS;

View File

@@ -602,8 +602,8 @@ void ColladaConverter::prepareConstraints(ConstraintInput& input)
//see daeMetaAttribute.cpp //see daeMetaAttribute.cpp
//INF -> 999999.9 //INF -> 999999.9
//-INF -> -999999.9 //-INF -> -999999.9
float linearCheckTreshold = 999999.0; float linearCheckThreshold = 999999.0;
float angularCheckTreshold = 180.0;//check this float angularCheckThreshold = 180.0;//check this
@@ -620,16 +620,16 @@ void ColladaConverter::prepareConstraints(ConstraintInput& input)
{ {
for (int i=0;i<3;i++) for (int i=0;i<3;i++)
{ {
if ((linearLowerLimits[i] < -linearCheckTreshold) || if ((linearLowerLimits[i] < -linearCheckThreshold) ||
(linearUpperLimits[i] > linearCheckTreshold)) (linearUpperLimits[i] > linearCheckThreshold))
{ {
//disable limits //disable limits
linearLowerLimits[i] = 1; linearLowerLimits[i] = 1;
linearUpperLimits[i] = 0; linearUpperLimits[i] = 0;
} }
if ((angularLowerLimits[i] < -angularCheckTreshold) || if ((angularLowerLimits[i] < -angularCheckThreshold) ||
(angularUpperLimits[i] > angularCheckTreshold)) (angularUpperLimits[i] > angularCheckThreshold))
{ {
//disable limits //disable limits
angularLowerLimits[i] = 1; angularLowerLimits[i] = 1;

View File

@@ -102,10 +102,10 @@ bool SphereTriangleDetector::collide(const btVector3& sphereCenter,btVector3 &po
normal *= -1.f; normal *= -1.f;
} }
///todo: move this gContactBreakingTreshold into a proper structure ///todo: move this gContactBreakingThreshold into a proper structure
extern float gContactBreakingTreshold; extern float gContactBreakingThreshold;
float contactMargin = gContactBreakingTreshold; float contactMargin = gContactBreakingThreshold;
bool isInsideContactPlane = distanceFromPlane < r + contactMargin; bool isInsideContactPlane = distanceFromPlane < r + contactMargin;
bool isInsideShellPlane = distanceFromPlane < r; bool isInsideShellPlane = distanceFromPlane < r;

View File

@@ -24,7 +24,7 @@ btCollisionObject::btCollisionObject()
m_userObjectPointer(0), m_userObjectPointer(0),
m_hitFraction(1.f), m_hitFraction(1.f),
m_ccdSweptSphereRadius(0.f), m_ccdSweptSphereRadius(0.f),
m_ccdSquareMotionTreshold(0.f) m_ccdSquareMotionThreshold(0.f)
{ {
} }

View File

@@ -73,8 +73,8 @@ struct btCollisionObject
///Swept sphere radius (0.0 by default), see btConvexConvexAlgorithm:: ///Swept sphere radius (0.0 by default), see btConvexConvexAlgorithm::
float m_ccdSweptSphereRadius; float m_ccdSweptSphereRadius;
/// Don't do continuous collision detection if square motion (in one step) is less then m_ccdSquareMotionTreshold /// Don't do continuous collision detection if square motion (in one step) is less then m_ccdSquareMotionThreshold
float m_ccdSquareMotionTreshold; float m_ccdSquareMotionThreshold;
inline bool mergesSimulationIslands() const inline bool mergesSimulationIslands() const
{ {

View File

@@ -205,10 +205,10 @@ float btConvexConcaveCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject
//quick approximation using raycast, todo: hook up to the continuous collision detection (one of the btConvexCast) //quick approximation using raycast, todo: hook up to the continuous collision detection (one of the btConvexCast)
//only perform CCD above a certain treshold, this prevents blocking on the long run //only perform CCD above a certain threshold, this prevents blocking on the long run
//because object in a blocked ccd state (hitfraction<1) get their linear velocity halved each frame... //because object in a blocked ccd state (hitfraction<1) get their linear velocity halved each frame...
float squareMot0 = (convexbody->m_interpolationWorldTransform.getOrigin() - convexbody->m_worldTransform.getOrigin()).length2(); float squareMot0 = (convexbody->m_interpolationWorldTransform.getOrigin() - convexbody->m_worldTransform.getOrigin()).length2();
if (squareMot0 < convexbody->m_ccdSquareMotionTreshold) if (squareMot0 < convexbody->m_ccdSquareMotionThreshold)
{ {
return 1.f; return 1.f;
} }

View File

@@ -165,7 +165,7 @@ void btConvexConvexAlgorithm ::processCollision (btCollisionObject* body0,btColl
//TODO: if (dispatchInfo.m_useContinuous) //TODO: if (dispatchInfo.m_useContinuous)
m_gjkPairDetector.setMinkowskiA(min0); m_gjkPairDetector.setMinkowskiA(min0);
m_gjkPairDetector.setMinkowskiB(min1); m_gjkPairDetector.setMinkowskiB(min1);
input.m_maximumDistanceSquared = min0->getMargin() + min1->getMargin() + m_manifoldPtr->getContactBreakingTreshold(); input.m_maximumDistanceSquared = min0->getMargin() + min1->getMargin() + m_manifoldPtr->getContactBreakingThreshold();
input.m_maximumDistanceSquared*= input.m_maximumDistanceSquared; input.m_maximumDistanceSquared*= input.m_maximumDistanceSquared;
// input.m_maximumDistanceSquared = 1e30f; // input.m_maximumDistanceSquared = 1e30f;
@@ -183,17 +183,17 @@ void btConvexConvexAlgorithm ::processCollision (btCollisionObject* body0,btColl
bool disableCcd = false; bool disableCcd = false;
float btConvexConvexAlgorithm::calculateTimeOfImpact(btCollisionObject* col0,btCollisionObject* col1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut) float btConvexConvexAlgorithm::calculateTimeOfImpact(btCollisionObject* col0,btCollisionObject* col1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
{ {
///Rather then checking ALL pairs, only calculate TOI when motion exceeds treshold ///Rather then checking ALL pairs, only calculate TOI when motion exceeds threshold
///Linear motion for one of objects needs to exceed m_ccdSquareMotionTreshold ///Linear motion for one of objects needs to exceed m_ccdSquareMotionThreshold
///col0->m_worldTransform, ///col0->m_worldTransform,
float resultFraction = 1.f; float resultFraction = 1.f;
float squareMot0 = (col0->m_interpolationWorldTransform.getOrigin() - col0->m_worldTransform.getOrigin()).length2(); float squareMot0 = (col0->m_interpolationWorldTransform.getOrigin() - col0->m_worldTransform.getOrigin()).length2();
if (squareMot0 < col0->m_ccdSquareMotionTreshold && if (squareMot0 < col0->m_ccdSquareMotionThreshold &&
squareMot0 < col0->m_ccdSquareMotionTreshold) squareMot0 < col0->m_ccdSquareMotionThreshold)
return resultFraction; return resultFraction;

View File

@@ -58,7 +58,7 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b
assert(m_manifoldPtr); assert(m_manifoldPtr);
//order in manifold needs to match //order in manifold needs to match
if (depth > m_manifoldPtr->getContactBreakingTreshold()) if (depth > m_manifoldPtr->getContactBreakingThreshold())
return; return;
bool isSwapped = m_manifoldPtr->getBody0() != m_body0; bool isSwapped = m_manifoldPtr->getBody0() != m_body0;

View File

@@ -18,7 +18,7 @@ subject to the following restrictions:
#include "LinearMath/btTransform.h" #include "LinearMath/btTransform.h"
#include <assert.h> #include <assert.h>
float gContactBreakingTreshold = 0.02f; float gContactBreakingThreshold = 0.02f;
ContactDestroyedCallback gContactDestroyedCallback = 0; ContactDestroyedCallback gContactDestroyedCallback = 0;
@@ -151,7 +151,7 @@ int btPersistentManifold::sortCachedPoints(const btManifoldPoint& pt)
int btPersistentManifold::getCacheEntry(const btManifoldPoint& newPoint) const int btPersistentManifold::getCacheEntry(const btManifoldPoint& newPoint) const
{ {
btScalar shortestDist = getContactBreakingTreshold() * getContactBreakingTreshold(); btScalar shortestDist = getContactBreakingThreshold() * getContactBreakingThreshold();
int size = getNumContacts(); int size = getNumContacts();
int nearestPoint = -1; int nearestPoint = -1;
for( int i = 0; i < size; i++ ) for( int i = 0; i < size; i++ )
@@ -193,9 +193,9 @@ void btPersistentManifold::AddManifoldPoint(const btManifoldPoint& newPoint)
replaceContactPoint(newPoint,insertIndex); replaceContactPoint(newPoint,insertIndex);
} }
float btPersistentManifold::getContactBreakingTreshold() const float btPersistentManifold::getContactBreakingThreshold() const
{ {
return gContactBreakingTreshold; return gContactBreakingThreshold;
} }
void btPersistentManifold::refreshContactPoints(const btTransform& trA,const btTransform& trB) void btPersistentManifold::refreshContactPoints(const btTransform& trA,const btTransform& trB)
@@ -229,7 +229,7 @@ void btPersistentManifold::refreshContactPoints(const btTransform& trA,const btT
projectedPoint = manifoldPoint.m_positionWorldOnA - manifoldPoint.m_normalWorldOnB * manifoldPoint.m_distance1; projectedPoint = manifoldPoint.m_positionWorldOnA - manifoldPoint.m_normalWorldOnB * manifoldPoint.m_distance1;
projectedDifference = manifoldPoint.m_positionWorldOnB - projectedPoint; projectedDifference = manifoldPoint.m_positionWorldOnB - projectedPoint;
distance2d = projectedDifference.dot(projectedDifference); distance2d = projectedDifference.dot(projectedDifference);
if (distance2d > getContactBreakingTreshold()*getContactBreakingTreshold() ) if (distance2d > getContactBreakingThreshold()*getContactBreakingThreshold() )
{ {
removeContactPoint(i); removeContactPoint(i);
} }

View File

@@ -23,8 +23,8 @@ subject to the following restrictions:
struct btCollisionResult; struct btCollisionResult;
///contact breaking and merging treshold ///contact breaking and merging threshold
extern float gContactBreakingTreshold; extern float gContactBreakingThreshold;
typedef bool (*ContactDestroyedCallback)(void* userPersistentData); typedef bool (*ContactDestroyedCallback)(void* userPersistentData);
extern ContactDestroyedCallback gContactDestroyedCallback; extern ContactDestroyedCallback gContactDestroyedCallback;
@@ -97,7 +97,7 @@ public:
} }
/// todo: get this margin from the current physics / collision environment /// todo: get this margin from the current physics / collision environment
float getContactBreakingTreshold() const; float getContactBreakingThreshold() const;
int getCacheEntry(const btManifoldPoint& newPoint) const; int getCacheEntry(const btManifoldPoint& newPoint) const;
@@ -124,7 +124,7 @@ public:
bool validContactDistance(const btManifoldPoint& pt) const bool validContactDistance(const btManifoldPoint& pt) const
{ {
return pt.m_distance1 <= getContactBreakingTreshold(); return pt.m_distance1 <= getContactBreakingThreshold();
} }
/// calculated new worldspace coordinates and depth, and reject points that exceed the collision margin /// calculated new worldspace coordinates and depth, and reject points that exceed the collision margin
void refreshContactPoints( const btTransform& trA,const btTransform& trB); void refreshContactPoints( const btTransform& trA,const btTransform& trB);

View File

@@ -24,8 +24,8 @@ float gLinearAirDamping = 1.f;
float gDeactivationTime = 2.f; float gDeactivationTime = 2.f;
bool gDisableDeactivation = false; bool gDisableDeactivation = false;
float gLinearSleepingTreshold = 0.8f; float gLinearSleepingThreshold = 0.8f;
float gAngularSleepingTreshold = 1.0f; float gAngularSleepingThreshold = 1.0f;
static int uniqueId = 0; static int uniqueId = 0;
btRigidBody::btRigidBody(float mass, btMotionState* motionState, btCollisionShape* collisionShape, const btVector3& localInertia,btScalar linearDamping,btScalar angularDamping,btScalar friction,btScalar restitution) btRigidBody::btRigidBody(float mass, btMotionState* motionState, btCollisionShape* collisionShape, const btVector3& localInertia,btScalar linearDamping,btScalar angularDamping,btScalar friction,btScalar restitution)

View File

@@ -34,8 +34,8 @@ extern bool gUseEpa;
extern float gDeactivationTime; extern float gDeactivationTime;
extern bool gDisableDeactivation; extern bool gDisableDeactivation;
extern float gLinearSleepingTreshold; extern float gLinearSleepingThreshold;
extern float gAngularSleepingTreshold; extern float gAngularSleepingThreshold;
/// btRigidBody class for btRigidBody Dynamics /// btRigidBody class for btRigidBody Dynamics
@@ -250,8 +250,8 @@ public:
if ( (GetActivationState() == ISLAND_SLEEPING) || (GetActivationState() == DISABLE_DEACTIVATION)) if ( (GetActivationState() == ISLAND_SLEEPING) || (GetActivationState() == DISABLE_DEACTIVATION))
return; return;
if ((getLinearVelocity().length2() < gLinearSleepingTreshold*gLinearSleepingTreshold) && if ((getLinearVelocity().length2() < gLinearSleepingThreshold*gLinearSleepingThreshold) &&
(getAngularVelocity().length2() < gAngularSleepingTreshold*gAngularSleepingTreshold)) (getAngularVelocity().length2() < gAngularSleepingThreshold*gAngularSleepingThreshold))
{ {
m_deactivationTime += timeStep; m_deactivationTime += timeStep;
} else } else

View File

@@ -17,7 +17,7 @@ subject to the following restrictions:
#define SIMD_TRANSFORM_UTIL_H #define SIMD_TRANSFORM_UTIL_H
#include "LinearMath/btTransform.h" #include "LinearMath/btTransform.h"
#define ANGULAR_MOTION_TRESHOLD 0.5f*SIMD_HALF_PI #define ANGULAR_MOTION_THRESHOLD 0.5f*SIMD_HALF_PI
@@ -82,9 +82,9 @@ public:
btVector3 axis; btVector3 axis;
btScalar fAngle = angvel.length(); btScalar fAngle = angvel.length();
//limit the angular motion //limit the angular motion
if (fAngle*timeStep > ANGULAR_MOTION_TRESHOLD) if (fAngle*timeStep > ANGULAR_MOTION_THRESHOLD)
{ {
fAngle = ANGULAR_MOTION_TRESHOLD / timeStep; fAngle = ANGULAR_MOTION_THRESHOLD / timeStep;
} }
if ( fAngle < 0.001f ) if ( fAngle < 0.001f )