18# define BT_ADDITIONAL_DEBUG
104#include <emmintrin.h>
106#define btVecSplat(x, e) _mm_shuffle_ps(x, x, _MM_SHUFFLE(e, e, e, e))
113#if defined(BT_ALLOW_SSE4)
117#define USE_FMA3_INSTEAD_FMA4 1
118#define USE_SSE4_DOT 1
120#define SSE4_DP(a, b) _mm_dp_ps(a, b, 0x7f)
121#define SSE4_DP_FP(a, b) _mm_cvtss_f32(_mm_dp_ps(a, b, 0x7f))
124#define DOT_PRODUCT(a, b) SSE4_DP(a, b)
126#define DOT_PRODUCT(a, b) btSimdDot3(a, b)
130#if USE_FMA3_INSTEAD_FMA4
132#define FMADD(a, b, c) _mm_fmadd_ps(a, b, c)
134#define FMNADD(a, b, c) _mm_fnmadd_ps(a, b, c)
137#define FMADD(a, b, c) _mm_macc_ps(a, b, c)
139#define FMNADD(a, b, c) _mm_nmacc_ps(a, b, c)
143#define FMADD(a, b, c) _mm_add_ps(c, _mm_mul_ps(a, b))
145#define FMNADD(a, b, c) _mm_sub_ps(c, _mm_mul_ps(a, b))
183#if defined(BT_ALLOW_SSE4)
430 const unsigned long un =
static_cast<unsigned long>(n);
435 if (
un <= 0x00010000UL)
438 if (
un <= 0x00000100UL)
441 if (
un <= 0x00000010UL)
444 if (
un <= 0x00000004UL)
447 if (
un <= 0x00000002UL)
456 return (
int)(r %
un);
463 solverBody->internalGetDeltaLinearVelocity().setValue(0.f, 0.f, 0.f);
464 solverBody->internalGetDeltaAngularVelocity().setValue(0.f, 0.f, 0.f);
465 solverBody->internalGetPushVelocity().setValue(0.f, 0.f, 0.f);
466 solverBody->internalGetTurnVelocity().setValue(0.f, 0.f, 0.f);
476 solverBody->m_angularVelocity =
rb->getAngularVelocity();
477 solverBody->m_externalForceImpulse =
rb->getTotalForce() *
rb->getInvMass() * timeStep;
478 solverBody->m_externalTorqueImpulse =
rb->getTotalTorque() *
rb->getInvInertiaTensorWorld() * timeStep;
485 solverBody->m_angularFactor.setValue(1, 1, 1);
487 solverBody->m_linearVelocity.setValue(0, 0, 0);
488 solverBody->m_angularVelocity.setValue(0, 0, 0);
489 solverBody->m_externalForceImpulse.setValue(0, 0, 0);
490 solverBody->m_externalTorqueImpulse.setValue(0, 0, 0);
518void btSequentialImpulseConstraintSolver::setupFrictionConstraint(
btSolverConstraint&
solverConstraint,
const btVector3&
normalAxis,
int solverBodyIdA,
int solverBodyIdB,
btManifoldPoint&
cp,
const btVector3&
rel_pos1,
const btVector3&
rel_pos2,
btCollisionObject*
colObj0,
btCollisionObject*
colObj1,
btScalar relaxation,
const btContactSolverInfo&
infoGlobal,
btScalar desiredVelocity,
btScalar cfmSlip)
610btSolverConstraint&
btSequentialImpulseConstraintSolver::addFrictionConstraint(
const btVector3&
normalAxis,
int solverBodyIdA,
int solverBodyIdB,
int frictionIndex,
btManifoldPoint&
cp,
const btVector3&
rel_pos1,
const btVector3&
rel_pos2,
btCollisionObject*
colObj0,
btCollisionObject*
colObj1,
btScalar relaxation,
const btContactSolverInfo&
infoGlobal,
btScalar desiredVelocity,
btScalar cfmSlip)
682btSolverConstraint&
btSequentialImpulseConstraintSolver::addTorsionalFrictionConstraint(
const btVector3&
normalAxis,
int solverBodyIdA,
int solverBodyIdB,
int frictionIndex,
btManifoldPoint&
cp,
btScalar combinedTorsionalFriction,
const btVector3&
rel_pos1,
const btVector3&
rel_pos2,
btCollisionObject*
colObj0,
btCollisionObject*
colObj1,
btScalar relaxation,
btScalar desiredVelocity,
btScalar cfmSlip)
771 if (
rb && (
rb->getInvMass() ||
rb->isKinematicObject()))
828 cfm =
cp.m_contactCFM;
830 erp =
cp.m_contactERP;
854#ifdef COMPUTE_IMPULSE_DENOM
1020 for (
int j = 0;
j <
manifold->getNumContacts();
j++)
1024 if (
cp.getDistance() <=
manifold->getContactProcessingThreshold())
1061 addTorsionalFrictionConstraint(
cp.m_normalWorldOnB,
solverBodyIdA,
solverBodyIdB,
frictionIndex,
cp,
cp.m_combinedSpinningFriction,
rel_pos1,
rel_pos2,
colObj0,
colObj1,
relaxation);
1071 if (
axis0.length() > 0.001)
1074 if (
axis1.length() > 0.001)
1105 addFrictionConstraint(
cp.m_lateralFrictionDir1,
solverBodyIdA,
solverBodyIdB,
frictionIndex,
cp,
rel_pos1,
rel_pos2,
colObj0,
colObj1,
relaxation,
infoGlobal);
1109 cp.m_lateralFrictionDir2 =
cp.m_lateralFrictionDir1.cross(
cp.m_normalWorldOnB);
1110 cp.m_lateralFrictionDir2.normalize();
1113 addFrictionConstraint(
cp.m_lateralFrictionDir2,
solverBodyIdA,
solverBodyIdB,
frictionIndex,
cp,
rel_pos1,
rel_pos2,
colObj0,
colObj1,
relaxation,
infoGlobal);
1122 addFrictionConstraint(
cp.m_lateralFrictionDir1,
solverBodyIdA,
solverBodyIdB,
frictionIndex,
cp,
rel_pos1,
rel_pos2,
colObj0,
colObj1,
relaxation,
infoGlobal);
1128 addFrictionConstraint(
cp.m_lateralFrictionDir2,
solverBodyIdA,
solverBodyIdB,
frictionIndex,
cp,
rel_pos1,
rel_pos2,
colObj0,
colObj1,
relaxation,
infoGlobal);
1139 addFrictionConstraint(
cp.m_lateralFrictionDir1,
solverBodyIdA,
solverBodyIdB,
frictionIndex,
cp,
rel_pos1,
rel_pos2,
colObj0,
colObj1,
relaxation,
infoGlobal,
cp.m_contactMotion1,
cp.m_frictionCFM);
1142 addFrictionConstraint(
cp.m_lateralFrictionDir2,
solverBodyIdA,
solverBodyIdB,
frictionIndex,
cp,
rel_pos1,
rel_pos2,
colObj0,
colObj1,
relaxation,
infoGlobal,
cp.m_contactMotion2,
cp.m_frictionCFM);
1179 for (
int j = 0;
j <
info1.m_numConstraintRows;
j++)
1229 for (
int j = 0;
j <
info1.m_numConstraintRows;
j++)
1297 for (
int j = 0;
j < numConstraints;
j++)
1308 for (
int i = 0; i < numConstraints; i++)
1315 fb->m_appliedTorqueBodyA.setZero();
1316 fb->m_appliedForceBodyB.setZero();
1317 fb->m_appliedTorqueBodyB.setZero();
1326 info1.m_numConstraintRows = 0;
1336 for (
int i = 0; i < numConstraints; i++)
1340 if (
info1.m_numConstraintRows)
1361 for (
int i = 0; i < numBodies; i++)
1375 for (
int i = 0; i < numBodies; i++)
1419#ifdef BT_ADDITIONAL_DEBUG
1421 for (
int i = 0; i < numConstraints; i++)
1426 if (!
constraint->getRigidBodyA().isStaticOrKinematicObject())
1429 for (
int b = 0; b < numBodies; b++)
1431 if (&
constraint->getRigidBodyA() == bodies[b])
1439 if (!
constraint->getRigidBodyB().isStaticOrKinematicObject())
1442 for (
int b = 0; b < numBodies; b++)
1444 if (&
constraint->getRigidBodyB() == bodies[b])
1457 if (!
manifoldPtr[i]->getBody0()->isStaticOrKinematicObject())
1460 for (
int b = 0; b < numBodies; b++)
1470 if (!
manifoldPtr[i]->getBody1()->isStaticOrKinematicObject())
1473 for (
int b = 0; b < numBodies; b++)
1582 for (
int j = 0;
j < numConstraints;
j++)
1699 BT_PROFILE(
"solveGroupCacheFriendlySplitImpulseIterations");
1720#ifdef VERBOSE_RESIDUAL_PRINTF
1732 BT_PROFILE(
"solveGroupCacheFriendlyIterations");
1747#ifdef VERBOSE_RESIDUAL_PRINTF
1803 constr->setEnabled(
false);
@ BT_CONTACT_FLAG_LATERAL_FRICTION_INITIALIZED
@ BT_CONTACT_FLAG_HAS_CONTACT_ERP
@ BT_CONTACT_FLAG_HAS_CONTACT_CFM
@ BT_CONTACT_FLAG_CONTACT_STIFFNESS_DAMPING
@ BT_CONTACT_FLAG_FRICTION_ANCHOR
const T & btMax(const T &a, const T &b)
btScalar dot(const btQuaternion &q1, const btQuaternion &q2)
Calculate the dot product between two quaternions.
@ BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY
@ BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT
BT_ENABLE_GYROPSCOPIC_FORCE flags is enabled by default in Bullet 2.83 and onwards.
@ BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
btScalar btSqrt(btScalar y)
btScalar btFabs(btScalar x)
static btScalar gResolveSingleConstraintRowGeneric_scalar_reference(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &c)
This is the scalar reference implementation of solving a single constraint row, the innerloop of the ...
static btScalar gResolveSingleConstraintRowLowerLimit_scalar_reference(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &c)
static btScalar gResolveSplitPenetrationImpulse_sse2(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &c)
int gNumSplitImpulseRecoveries
static btScalar gResolveSplitPenetrationImpulse_scalar_reference(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &c)
btScalar(* btSingleConstraintRowSolver)(btSolverBody &, btSolverBody &, const btSolverConstraint &)
static T sum(const btAlignedObjectArray< T > &items)
#define btSimdScalar
Until we get other contributions, only use SIMD on Windows, when using Visual Studio 2008 or later,...
void btPlaneSpace1(const T &n, T &p, T &q)
void resizeNoInitialize(int newsize)
resize changes the number of elements in the array.
int size() const
return the number of elements in the array
void resize(int newsize, const T &fillData=T())
T & expandNonInitializing()
T & expand(const T &fillValue=T())
btCollisionObject can be used to manage collision detection objects.
bool isStaticOrKinematicObject() const
int getInternalType() const
reserved for Bullet internal usage
int getWorldArrayIndex() const
void setCompanionId(int id)
bool isKinematicObject() const
@ CF_ANISOTROPIC_ROLLING_FRICTION
@ CF_ANISOTROPIC_FRICTION
int getCompanionId() const
static int getCpuFeatures()
The btDispatcher interface class can be used in combination with broadphase to dispatch calculations ...
The btIDebugDraw interface class allows hooking up a debug renderer to visually debug simulations.
ManifoldContactPoint collects and maintains persistent contactpoints.
btPersistentManifold is a contact point cache, it stays persistent as long as objects are overlapping...
The btRigidBody is the main class for rigid body objects.
btScalar getInvMass() const
btVector3 computeGyroscopicImpulseImplicit_World(btScalar dt) const
perform implicit force computation in world space
btVector3 computeGyroscopicImpulseImplicit_Body(btScalar step) const
perform implicit force computation in body space (inertial frame)
static const btRigidBody * upcast(const btCollisionObject *colObj)
to keep collision detection and dynamics separate we don't store a rigidbody pointer but a rigidbody ...
const btMatrix3x3 & getInvInertiaTensorWorld() const
btVector3 computeGyroscopicForceExplicit(btScalar maxGyroscopicForce) const
explicit version is best avoided, it gains energy
btSingleConstraintRowSolver getScalarConstraintRowSolverLowerLimit()
Various implementations of solving a single constraint row using an inequality (lower limit) constrai...
void initSolverBody(btSolverBody *solverBody, btCollisionObject *collisionObject, btScalar timeStep)
btSingleConstraintRowSolver getSSE2ConstraintRowSolverGeneric()
btConstraintArray m_tmpSolverContactConstraintPool
int m_maxOverrideNumSolverIterations
virtual void convertBodies(btCollisionObject **bodies, int numBodies, const btContactSolverInfo &infoGlobal)
btSolverConstraint & addFrictionConstraint(const btVector3 &normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint &cp, const btVector3 &rel_pos1, const btVector3 &rel_pos2, btCollisionObject *colObj0, btCollisionObject *colObj1, btScalar relaxation, const btContactSolverInfo &infoGlobal, btScalar desiredVelocity=0., btScalar cfmSlip=0.)
void writeBackJoints(int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
btConstraintArray m_tmpSolverContactFrictionConstraintPool
virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject **bodies, int numBodies, const btContactSolverInfo &infoGlobal)
btAlignedObjectArray< int > m_orderFrictionConstraintPool
virtual void convertJoints(btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal)
virtual ~btSequentialImpulseConstraintSolver()
btSolverAnalyticsData m_analyticsData
void convertJoint(btSolverConstraint *currentConstraintRow, btTypedConstraint *constraint, const btTypedConstraint::btConstraintInfo1 &info1, int solverBodyIdA, int solverBodyIdB, const btContactSolverInfo &infoGlobal)
virtual btScalar solveGroup(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifold, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &info, btIDebugDraw *debugDrawer, btDispatcher *dispatcher)
btSequentialImpulseConstraintSolver Sequentially applies impulses
btSolverConstraint & addTorsionalFrictionConstraint(const btVector3 &normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint &cp, btScalar torsionalFriction, const btVector3 &rel_pos1, const btVector3 &rel_pos2, btCollisionObject *colObj0, btCollisionObject *colObj1, btScalar relaxation, btScalar desiredVelocity=0, btScalar cfmSlip=0.f)
virtual btScalar solveGroupCacheFriendlyIterations(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer)
virtual void solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer)
unsigned long m_btSeed2
m_btSeed2 is used for re-arranging the constraint rows. improves convergence/quality of friction
virtual void reset()
clear internal cached data and reset random seed
virtual void convertContacts(btPersistentManifold **manifoldPtr, int numManifolds, const btContactSolverInfo &infoGlobal)
btScalar resolveSingleConstraintRowLowerLimit(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
void setupSolverFunctions(bool useSimd)
static void applyAnisotropicFriction(btCollisionObject *colObj, btVector3 &frictionDirection, int frictionMode)
btSingleConstraintRowSolver getSSE2ConstraintRowSolverLowerLimit()
btScalar resolveSingleConstraintRowGeneric(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
void setupTorsionalFrictionConstraint(btSolverConstraint &solverConstraint, const btVector3 &normalAxis, int solverBodyIdA, int solverBodyIdB, btManifoldPoint &cp, btScalar combinedTorsionalFriction, const btVector3 &rel_pos1, const btVector3 &rel_pos2, btCollisionObject *colObj0, btCollisionObject *colObj1, btScalar relaxation, btScalar desiredVelocity=0., btScalar cfmSlip=0.)
btScalar m_leastSquaresResidual
void convertContact(btPersistentManifold *manifold, const btContactSolverInfo &infoGlobal)
btAlignedObjectArray< btSolverBody > m_tmpSolverBodyPool
btSingleConstraintRowSolver m_resolveSingleConstraintRowLowerLimit
btSingleConstraintRowSolver getScalarConstraintRowSolverGeneric()
Various implementations of solving a single constraint row using a generic equality constraint,...
btSingleConstraintRowSolver m_resolveSplitPenetrationImpulse
btAlignedObjectArray< btTypedConstraint::btConstraintInfo1 > m_tmpConstraintSizesPool
btAlignedObjectArray< int > m_orderTmpConstraintPool
btAlignedObjectArray< int > m_orderNonContactConstraintPool
btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverGeneric()
void writeBackBodies(int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
btAlignedObjectArray< int > m_kinematicBodyUniqueIdToSolverBodyTable
virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer)
void setupFrictionConstraint(btSolverConstraint &solverConstraint, const btVector3 &normalAxis, int solverBodyIdA, int solverBodyIdB, btManifoldPoint &cp, const btVector3 &rel_pos1, const btVector3 &rel_pos2, btCollisionObject *colObj0, btCollisionObject *colObj1, btScalar relaxation, const btContactSolverInfo &infoGlobal, btScalar desiredVelocity=0., btScalar cfmSlip=0.)
btConstraintArray m_tmpSolverNonContactConstraintPool
btSingleConstraintRowSolver m_resolveSingleConstraintRowGeneric
btSequentialImpulseConstraintSolver()
btConstraintArray m_tmpSolverContactRollingFrictionConstraintPool
void setFrictionConstraintImpulse(btSolverConstraint &solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint &cp, const btContactSolverInfo &infoGlobal)
btScalar resolveSingleConstraintRowLowerLimitSIMD(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
int getOrInitSolverBody(btCollisionObject &body, btScalar timeStep)
btScalar restitutionCurve(btScalar rel_vel, btScalar restitution, btScalar velocityThreshold)
btScalar resolveSingleConstraintRowGenericSIMD(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverLowerLimit()
void writeBackContacts(int iBegin, int iEnd, const btContactSolverInfo &infoGlobal)
virtual btScalar solveSingleIteration(int iteration, btCollisionObject **bodies, int numBodies, btPersistentManifold **manifoldPtr, int numManifolds, btTypedConstraint **constraints, int numConstraints, const btContactSolverInfo &infoGlobal, btIDebugDraw *debugDrawer)
btScalar resolveSplitPenetrationImpulse(btSolverBody &bodyA, btSolverBody &bodyB, const btSolverConstraint &contactConstraint)
void setupContactConstraint(btSolverConstraint &solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint &cp, const btContactSolverInfo &infoGlobal, btScalar &relaxation, const btVector3 &rel_pos1, const btVector3 &rel_pos2)
TypedConstraint is the baseclass for Bullet constraints and vehicles.
virtual void buildJacobian()
internal method used by the constraint solver, don't use them directly
btVector3 can be used to represent 3D points and vectors.
btVector3 cross(const btVector3 &v) const
Return the cross product between this and another vector.
btScalar dot(const btVector3 &v) const
Return the dot product.
btVector3 m_appliedForceBodyA
int m_numContactManifolds
double m_remainingLeastSquaresResidual
The btSolverBody is an internal datastructure for the constraint solver. Only necessary data is packe...
1D constraint along a normal axis between bodyA and bodyB. It can be combined to solve contact and fr...
btVector3 m_contactNormal2
btVector3 m_relpos1CrossNormal
btVector3 m_angularComponentB
btSimdScalar m_appliedImpulse
btScalar m_rhsPenetration
btVector3 m_angularComponentA
btSimdScalar m_appliedPushImpulse
btVector3 m_relpos2CrossNormal
btVector3 m_contactNormal1