summaryrefslogtreecommitdiff
path: root/thirdparty/bullet/BulletDynamics/Featherstone
diff options
context:
space:
mode:
Diffstat (limited to 'thirdparty/bullet/BulletDynamics/Featherstone')
-rw-r--r--thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.cpp15
-rw-r--r--thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.h45
-rw-r--r--thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp86
-rw-r--r--thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h5
-rw-r--r--thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp37
-rw-r--r--thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h2
-rw-r--r--thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h4
-rw-r--r--thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp12
-rw-r--r--thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h2
9 files changed, 170 insertions, 38 deletions
diff --git a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.cpp b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.cpp
index 53fc48d4b9..3e210d7520 100644
--- a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.cpp
+++ b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.cpp
@@ -106,6 +106,7 @@ btMultiBody::btMultiBody(int n_links,
m_fixedBase(fixedBase),
m_awake(true),
m_canSleep(canSleep),
+ m_canWakeup(true),
m_sleepTimer(0),
m_userObjectPointer(0),
m_userIndex2(-1),
@@ -343,6 +344,7 @@ void btMultiBody::finalizeMultiDof()
m_deltaV.resize(6 + m_dofCount);
m_realBuf.resize(6 + m_dofCount + m_dofCount * m_dofCount + 6 + m_dofCount); //m_dofCount for joint-space vels + m_dofCount^2 for "D" matrices + delta-pos vector (6 base "vels" + joint "vels")
m_vectorBuf.resize(2 * m_dofCount); //two 3-vectors (i.e. one six-vector) for each system dof ("h" matrices)
+ m_matrixBuf.resize(m_links.size() + 1);
for (int i = 0; i < m_vectorBuf.size(); i++)
{
m_vectorBuf[i].setValue(0, 0, 0);
@@ -350,9 +352,9 @@ void btMultiBody::finalizeMultiDof()
updateLinksDofOffsets();
}
-int btMultiBody::getParent(int i) const
+int btMultiBody::getParent(int link_num) const
{
- return m_links[i].m_parent;
+ return m_links[link_num].m_parent;
}
btScalar btMultiBody::getLinkMass(int i) const
@@ -1882,6 +1884,8 @@ void btMultiBody::checkMotionAndSleepIfRequired(btScalar timestep)
return;
}
+
+
// motion is computed as omega^2 + v^2 + (sum of squares of joint velocities)
btScalar motion = 0;
{
@@ -1900,8 +1904,11 @@ void btMultiBody::checkMotionAndSleepIfRequired(btScalar timestep)
else
{
m_sleepTimer = 0;
- if (!m_awake)
- wakeUp();
+ if (m_canWakeup)
+ {
+ if (!m_awake)
+ wakeUp();
+ }
}
}
diff --git a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.h b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.h
index e5c0f1806b..c0b0d003be 100644
--- a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.h
+++ b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBody.h
@@ -65,7 +65,7 @@ public:
virtual ~btMultiBody();
//note: fixed link collision with parent is always disabled
- void setupFixed(int linkIndex,
+ void setupFixed(int i, //linkIndex
btScalar mass,
const btVector3 &inertia,
int parent,
@@ -83,7 +83,7 @@ public:
const btVector3 &thisPivotToThisComOffset,
bool disableParentCollision);
- void setupRevolute(int linkIndex, // 0 to num_links-1
+ void setupRevolute(int i, // 0 to num_links-1
btScalar mass,
const btVector3 &inertia,
int parentIndex,
@@ -93,7 +93,7 @@ public:
const btVector3 &thisPivotToThisComOffset, // vector from joint axis to my COM, in MY frame
bool disableParentCollision = false);
- void setupSpherical(int linkIndex, // 0 to num_links-1
+ void setupSpherical(int i, // linkIndex, 0 to num_links-1
btScalar mass,
const btVector3 &inertia,
int parent,
@@ -182,7 +182,10 @@ public:
// get/set pos/vel/rot/omega for the base link
//
- const btVector3 &getBasePos() const { return m_basePos; } // in world frame
+ const btVector3 &getBasePos() const
+ {
+ return m_basePos;
+ } // in world frame
const btVector3 getBaseVel() const
{
return btVector3(m_realBuf[3], m_realBuf[4], m_realBuf[5]);
@@ -274,15 +277,15 @@ public:
//
// transform vectors in local frame of link i to world frame (or vice versa)
//
- btVector3 localPosToWorld(int i, const btVector3 &vec) const;
- btVector3 localDirToWorld(int i, const btVector3 &vec) const;
- btVector3 worldPosToLocal(int i, const btVector3 &vec) const;
- btVector3 worldDirToLocal(int i, const btVector3 &vec) const;
+ btVector3 localPosToWorld(int i, const btVector3 &local_pos) const;
+ btVector3 localDirToWorld(int i, const btVector3 &local_dir) const;
+ btVector3 worldPosToLocal(int i, const btVector3 &world_pos) const;
+ btVector3 worldDirToLocal(int i, const btVector3 &world_dir) const;
//
// transform a frame in local coordinate to a frame in world coordinate
//
- btMatrix3x3 localFrameToWorld(int i, const btMatrix3x3 &mat) const;
+ btMatrix3x3 localFrameToWorld(int i, const btMatrix3x3 &local_frame) const;
//
// calculate kinetic energy and angular momentum
@@ -451,7 +454,10 @@ public:
//
void setCanSleep(bool canSleep)
{
- m_canSleep = canSleep;
+ if (m_canWakeup)
+ {
+ m_canSleep = canSleep;
+ }
}
bool getCanSleep() const
@@ -459,6 +465,15 @@ public:
return m_canSleep;
}
+ bool getCanWakeup() const
+ {
+ return m_canWakeup;
+ }
+
+ void setCanWakeup(bool canWakeup)
+ {
+ m_canWakeup = canWakeup;
+ }
bool isAwake() const { return m_awake; }
void wakeUp();
void goToSleep();
@@ -469,6 +484,11 @@ public:
return m_fixedBase;
}
+ void setFixedBase(bool fixedBase)
+ {
+ m_fixedBase = fixedBase;
+ }
+
int getCompanionId() const
{
return m_companionId;
@@ -556,11 +576,11 @@ public:
{
return m_internalNeedsJointFeedback;
}
- void forwardKinematics(btAlignedObjectArray<btQuaternion> & scratch_q, btAlignedObjectArray<btVector3> & scratch_m);
+ void forwardKinematics(btAlignedObjectArray<btQuaternion>& world_to_local, btAlignedObjectArray<btVector3> & local_origin);
void compTreeLinkVelocities(btVector3 * omega, btVector3 * vel) const;
- void updateCollisionObjectWorldTransforms(btAlignedObjectArray<btQuaternion> & scratch_q, btAlignedObjectArray<btVector3> & scratch_m);
+ void updateCollisionObjectWorldTransforms(btAlignedObjectArray<btQuaternion> & world_to_local, btAlignedObjectArray<btVector3> & local_origin);
virtual int calculateSerializeBufferSize() const;
@@ -688,6 +708,7 @@ private:
// Sleep parameters.
bool m_awake;
bool m_canSleep;
+ bool m_canWakeup;
btScalar m_sleepTimer;
void *m_userObjectPointer;
diff --git a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp
index e97bd71cc4..23e163f0e8 100644
--- a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp
+++ b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp
@@ -70,6 +70,30 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl
//solve featherstone frictional contact
if (infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS && ((infoGlobal.m_solverMode & SOLVER_DISABLE_IMPLICIT_CONE_FRICTION) == 0))
{
+ for (int j1 = 0; j1 < this->m_multiBodySpinningFrictionContactConstraints.size(); j1++)
+ {
+ if (iteration < infoGlobal.m_numIterations)
+ {
+ int index = j1;
+
+ btMultiBodySolverConstraint& frictionConstraint = m_multiBodySpinningFrictionContactConstraints[index];
+ btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse;
+ //adjust friction limits here
+ if (totalImpulse > btScalar(0))
+ {
+ frictionConstraint.m_lowerLimit = -(frictionConstraint.m_friction * totalImpulse);
+ frictionConstraint.m_upperLimit = frictionConstraint.m_friction * totalImpulse;
+ btScalar residual = resolveSingleConstraintRowGeneric(frictionConstraint);
+ leastSquaredResidual = btMax(leastSquaredResidual, residual * residual);
+
+ if (frictionConstraint.m_multiBodyA)
+ frictionConstraint.m_multiBodyA->setPosUpdated(false);
+ if (frictionConstraint.m_multiBodyB)
+ frictionConstraint.m_multiBodyB->setPosUpdated(false);
+ }
+ }
+ }
+
for (int j1 = 0; j1 < this->m_multiBodyTorsionalFrictionContactConstraints.size(); j1++)
{
if (iteration < infoGlobal.m_numIterations)
@@ -78,18 +102,29 @@ btScalar btMultiBodyConstraintSolver::solveSingleIteration(int iteration, btColl
btMultiBodySolverConstraint& frictionConstraint = m_multiBodyTorsionalFrictionContactConstraints[index];
btScalar totalImpulse = m_multiBodyNormalContactConstraints[frictionConstraint.m_frictionIndex].m_appliedImpulse;
+ j1++;
+ int index2 = j1;
+ btMultiBodySolverConstraint& frictionConstraintB = m_multiBodyTorsionalFrictionContactConstraints[index2];
//adjust friction limits here
- if (totalImpulse > btScalar(0))
+ if (totalImpulse > btScalar(0) && frictionConstraint.m_frictionIndex == frictionConstraintB.m_frictionIndex)
{
frictionConstraint.m_lowerLimit = -(frictionConstraint.m_friction * totalImpulse);
frictionConstraint.m_upperLimit = frictionConstraint.m_friction * totalImpulse;
- btScalar residual = resolveSingleConstraintRowGeneric(frictionConstraint);
+ frictionConstraintB.m_lowerLimit = -(frictionConstraintB.m_friction * totalImpulse);
+ frictionConstraintB.m_upperLimit = frictionConstraintB.m_friction * totalImpulse;
+
+ btScalar residual = resolveConeFrictionConstraintRows(frictionConstraint, frictionConstraintB);
leastSquaredResidual = btMax(leastSquaredResidual, residual * residual);
if (frictionConstraint.m_multiBodyA)
frictionConstraint.m_multiBodyA->setPosUpdated(false);
if (frictionConstraint.m_multiBodyB)
frictionConstraint.m_multiBodyB->setPosUpdated(false);
+
+ if (frictionConstraintB.m_multiBodyA)
+ frictionConstraintB.m_multiBodyA->setPosUpdated(false);
+ if (frictionConstraintB.m_multiBodyB)
+ frictionConstraintB.m_multiBodyB->setPosUpdated(false);
}
}
}
@@ -164,6 +199,7 @@ btScalar btMultiBodyConstraintSolver::solveGroupCacheFriendlySetup(btCollisionOb
m_multiBodyNormalContactConstraints.resize(0);
m_multiBodyFrictionContactConstraints.resize(0);
m_multiBodyTorsionalFrictionContactConstraints.resize(0);
+ m_multiBodySpinningFrictionContactConstraints.resize(0);
m_data.m_jacobians.resize(0);
m_data.m_deltaVelocitiesUnitImpulse.resize(0);
@@ -1169,6 +1205,43 @@ btMultiBodySolverConstraint& btMultiBodyConstraintSolver::addMultiBodyTorsionalF
return solverConstraint;
}
+btMultiBodySolverConstraint& btMultiBodyConstraintSolver::addMultiBodySpinningFrictionConstraint(const btVector3& normalAxis, btPersistentManifold* manifold, int frictionIndex, btManifoldPoint& cp,
+ btScalar combinedTorsionalFriction,
+ btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip)
+{
+ BT_PROFILE("addMultiBodyRollingFrictionConstraint");
+
+ btMultiBodySolverConstraint& solverConstraint = m_multiBodySpinningFrictionContactConstraints.expandNonInitializing();
+ solverConstraint.m_orgConstraint = 0;
+ solverConstraint.m_orgDofIndex = -1;
+
+ solverConstraint.m_frictionIndex = frictionIndex;
+ bool isFriction = true;
+
+ const btMultiBodyLinkCollider* fcA = btMultiBodyLinkCollider::upcast(manifold->getBody0());
+ const btMultiBodyLinkCollider* fcB = btMultiBodyLinkCollider::upcast(manifold->getBody1());
+
+ btMultiBody* mbA = fcA ? fcA->m_multiBody : 0;
+ btMultiBody* mbB = fcB ? fcB->m_multiBody : 0;
+
+ int solverBodyIdA = mbA ? -1 : getOrInitSolverBody(*colObj0, infoGlobal.m_timeStep);
+ int solverBodyIdB = mbB ? -1 : getOrInitSolverBody(*colObj1, infoGlobal.m_timeStep);
+
+ solverConstraint.m_solverBodyIdA = solverBodyIdA;
+ solverConstraint.m_solverBodyIdB = solverBodyIdB;
+ solverConstraint.m_multiBodyA = mbA;
+ if (mbA)
+ solverConstraint.m_linkA = fcA->m_link;
+
+ solverConstraint.m_multiBodyB = mbB;
+ if (mbB)
+ solverConstraint.m_linkB = fcB->m_link;
+
+ solverConstraint.m_originalContactPoint = &cp;
+
+ setupMultiBodyTorsionalFrictionConstraint(solverConstraint, normalAxis, cp, combinedTorsionalFriction, infoGlobal, relaxation, isFriction, desiredVelocity, cfmSlip);
+ return solverConstraint;
+}
void btMultiBodyConstraintSolver::convertMultiBodyContact(btPersistentManifold* manifold, const btContactSolverInfo& infoGlobal)
{
const btMultiBodyLinkCollider* fcA = btMultiBodyLinkCollider::upcast(manifold->getBody0());
@@ -1258,7 +1331,7 @@ void btMultiBodyConstraintSolver::convertMultiBodyContact(btPersistentManifold*
{
if (cp.m_combinedSpinningFriction > 0)
{
- addMultiBodyTorsionalFrictionConstraint(cp.m_normalWorldOnB, manifold, frictionIndex, cp, cp.m_combinedSpinningFriction, colObj0, colObj1, relaxation, infoGlobal);
+ addMultiBodySpinningFrictionConstraint(cp.m_normalWorldOnB, manifold, frictionIndex, cp, cp.m_combinedSpinningFriction, colObj0, colObj1, relaxation, infoGlobal);
}
if (cp.m_combinedRollingFriction > 0)
{
@@ -1267,11 +1340,8 @@ void btMultiBodyConstraintSolver::convertMultiBodyContact(btPersistentManifold*
applyAnisotropicFriction(colObj0, cp.m_lateralFrictionDir2, btCollisionObject::CF_ANISOTROPIC_ROLLING_FRICTION);
applyAnisotropicFriction(colObj1, cp.m_lateralFrictionDir2, btCollisionObject::CF_ANISOTROPIC_ROLLING_FRICTION);
- if (cp.m_lateralFrictionDir1.length() > 0.001)
- addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir1, manifold, frictionIndex, cp, cp.m_combinedRollingFriction, colObj0, colObj1, relaxation, infoGlobal);
-
- if (cp.m_lateralFrictionDir2.length() > 0.001)
- addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir2, manifold, frictionIndex, cp, cp.m_combinedRollingFriction, colObj0, colObj1, relaxation, infoGlobal);
+ addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir1, manifold, frictionIndex, cp, cp.m_combinedRollingFriction, colObj0, colObj1, relaxation, infoGlobal);
+ addMultiBodyTorsionalFrictionConstraint(cp.m_lateralFrictionDir2, manifold, frictionIndex, cp, cp.m_combinedRollingFriction, colObj0, colObj1, relaxation, infoGlobal);
}
rollingFriction--;
}
diff --git a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h
index f39f2879fc..abf5718839 100644
--- a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h
+++ b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h
@@ -34,6 +34,7 @@ protected:
btMultiBodyConstraintArray m_multiBodyNormalContactConstraints;
btMultiBodyConstraintArray m_multiBodyFrictionContactConstraints;
btMultiBodyConstraintArray m_multiBodyTorsionalFrictionContactConstraints;
+ btMultiBodyConstraintArray m_multiBodySpinningFrictionContactConstraints;
btMultiBodyJacobianData m_data;
@@ -54,6 +55,10 @@ protected:
btScalar combinedTorsionalFriction,
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity = 0, btScalar cfmSlip = 0);
+ btMultiBodySolverConstraint& addMultiBodySpinningFrictionConstraint(const btVector3& normalAxis, btPersistentManifold* manifold, int frictionIndex, btManifoldPoint& cp,
+ btScalar combinedTorsionalFriction,
+ btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity = 0, btScalar cfmSlip = 0);
+
void setupMultiBodyJointLimitConstraint(btMultiBodySolverConstraint & constraintRow,
btScalar * jacA, btScalar * jacB,
btScalar penetration, btScalar combinedFrictionCoeff, btScalar combinedRestitutionCoeff,
diff --git a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp
index 1557987bc3..1131e5378c 100644
--- a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp
+++ b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp
@@ -207,6 +207,7 @@ public:
}
};
+
struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::IslandCallback
{
btContactSolverInfo* m_solverInfo;
@@ -224,6 +225,8 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
btAlignedObjectArray<btTypedConstraint*> m_constraints;
btAlignedObjectArray<btMultiBodyConstraint*> m_multiBodyConstraints;
+ btAlignedObjectArray<btSolverAnalyticsData> m_islandAnalyticsData;
+
MultiBodyInplaceSolverIslandCallback(btMultiBodyConstraintSolver* solver,
btDispatcher* dispatcher)
: m_solverInfo(NULL),
@@ -235,7 +238,7 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
{
}
- MultiBodyInplaceSolverIslandCallback& operator=(MultiBodyInplaceSolverIslandCallback& other)
+ MultiBodyInplaceSolverIslandCallback& operator=(const MultiBodyInplaceSolverIslandCallback& other)
{
btAssert(0);
(void)other;
@@ -244,6 +247,7 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
SIMD_FORCE_INLINE void setup(btContactSolverInfo* solverInfo, btTypedConstraint** sortedConstraints, int numConstraints, btMultiBodyConstraint** sortedMultiBodyConstraints, int numMultiBodyConstraints, btIDebugDraw* debugDrawer)
{
+ m_islandAnalyticsData.clear();
btAssert(solverInfo);
m_solverInfo = solverInfo;
@@ -270,6 +274,11 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
{
///we don't split islands, so all constraints/contact manifolds/bodies are passed into the solver regardless the island id
m_solver->solveMultiBodyGroup(bodies, numBodies, manifolds, numManifolds, m_sortedConstraints, m_numConstraints, &m_multiBodySortedConstraints[0], m_numConstraints, *m_solverInfo, m_debugDrawer, m_dispatcher);
+ if (m_solverInfo->m_reportSolverAnalytics&1)
+ {
+ m_solver->m_analyticsData.m_islandId = islandId;
+ m_islandAnalyticsData.push_back(m_solver->m_analyticsData);
+ }
}
else
{
@@ -335,7 +344,7 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
if ((m_multiBodyConstraints.size() + m_constraints.size() + m_manifolds.size()) > m_solverInfo->m_minimumSolverBatchSize)
{
- processConstraints();
+ processConstraints(islandId);
}
else
{
@@ -344,7 +353,7 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
}
}
}
- void processConstraints()
+ void processConstraints(int islandId=-1)
{
btCollisionObject** bodies = m_bodies.size() ? &m_bodies[0] : 0;
btPersistentManifold** manifold = m_manifolds.size() ? &m_manifolds[0] : 0;
@@ -354,6 +363,11 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
//printf("mb contacts = %d, mb constraints = %d\n", mbContacts, m_multiBodyConstraints.size());
m_solver->solveMultiBodyGroup(bodies, m_bodies.size(), manifold, m_manifolds.size(), constraints, m_constraints.size(), multiBodyConstraints, m_multiBodyConstraints.size(), *m_solverInfo, m_debugDrawer, m_dispatcher);
+ if (m_bodies.size() && (m_solverInfo->m_reportSolverAnalytics&1))
+ {
+ m_solver->m_analyticsData.m_islandId = islandId;
+ m_islandAnalyticsData.push_back(m_solver->m_analyticsData);
+ }
m_bodies.resize(0);
m_manifolds.resize(0);
m_constraints.resize(0);
@@ -361,6 +375,11 @@ struct MultiBodyInplaceSolverIslandCallback : public btSimulationIslandManager::
}
};
+void btMultiBodyDynamicsWorld::getAnalyticsData(btAlignedObjectArray<btSolverAnalyticsData>& islandAnalyticsData) const
+{
+ islandAnalyticsData = m_solverMultiBodyIslandCallback->m_islandAnalyticsData;
+}
+
btMultiBodyDynamicsWorld::btMultiBodyDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration)
: btDiscreteDynamicsWorld(dispatcher, pairCache, constraintSolver, collisionConfiguration),
m_multiBodyConstraintSolver(constraintSolver)
@@ -717,13 +736,17 @@ void btMultiBodyDynamicsWorld::solveConstraints(btContactSolverInfo& solverInfo)
m_scratch_v.resize(bod->getNumLinks() + 1);
m_scratch_m.resize(bod->getNumLinks() + 1);
+ if (bod->internalNeedsJointFeedback())
{
if (!bod->isUsingRK4Integration())
{
- bool isConstraintPass = true;
- bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(solverInfo.m_timeStep, m_scratch_r, m_scratch_v, m_scratch_m, isConstraintPass,
- getSolverInfo().m_jointFeedbackInWorldSpace,
- getSolverInfo().m_jointFeedbackInJointFrame);
+ if (bod->internalNeedsJointFeedback())
+ {
+ bool isConstraintPass = true;
+ bod->computeAccelerationsArticulatedBodyAlgorithmMultiDof(solverInfo.m_timeStep, m_scratch_r, m_scratch_v, m_scratch_m, isConstraintPass,
+ getSolverInfo().m_jointFeedbackInWorldSpace,
+ getSolverInfo().m_jointFeedbackInJointFrame);
+ }
}
}
}
diff --git a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h
index 641238f3bb..e36c2f7aad 100644
--- a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h
+++ b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h
@@ -109,5 +109,7 @@ public:
virtual void serialize(btSerializer* serializer);
virtual void setMultiBodyConstraintSolver(btMultiBodyConstraintSolver* solver);
virtual void setConstraintSolver(btConstraintSolver* solver);
+ virtual void getAnalyticsData(btAlignedObjectArray<struct btSolverAnalyticsData>& m_islandAnalyticsData) const;
+
};
#endif //BT_MULTIBODY_DYNAMICS_WORLD_H
diff --git a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h
index f91c001f12..bc909990c2 100644
--- a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h
+++ b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h
@@ -36,6 +36,10 @@ public:
btMultiBody* m_multiBody;
int m_link;
+ virtual ~btMultiBodyLinkCollider()
+ {
+
+ }
btMultiBodyLinkCollider(btMultiBody* multiBody, int link)
: m_multiBody(multiBody),
m_link(link)
diff --git a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp
index 338e8af0ab..f2186a93e9 100644
--- a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp
+++ b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp
@@ -22,9 +22,9 @@ subject to the following restrictions:
#define DIRECTLY_UPDATE_VELOCITY_DURING_SOLVER_ITERATIONS
-static bool interleaveContactAndFriction = false;
+static bool interleaveContactAndFriction1 = false;
-struct btJointNode
+struct btJointNode1
{
int jointIndex; // pointer to enclosing dxJoint object
int otherBodyIndex; // *other* body this joint is connected to
@@ -241,7 +241,7 @@ void btMultiBodyMLCPConstraintSolver::createMLCPFast(const btContactSolverInfo&
void btMultiBodyMLCPConstraintSolver::createMLCPFastRigidBody(const btContactSolverInfo& infoGlobal)
{
- int numContactRows = interleaveContactAndFriction ? 3 : 1;
+ int numContactRows = interleaveContactAndFriction1 ? 3 : 1;
int numConstraintRows = m_allConstraintPtrArray.size();
@@ -301,7 +301,7 @@ void btMultiBodyMLCPConstraintSolver::createMLCPFastRigidBody(const btContactSol
BT_PROFILE("bodyJointNodeArray.resize");
bodyJointNodeArray.resize(numBodies, -1);
}
- btAlignedObjectArray<btJointNode> jointNodeArray;
+ btAlignedObjectArray<btJointNode1> jointNodeArray;
{
BT_PROFILE("jointNodeArray.reserve");
jointNodeArray.reserve(2 * m_allConstraintPtrArray.size());
@@ -729,7 +729,7 @@ btScalar btMultiBodyMLCPConstraintSolver::solveGroupCacheFriendlySetup(
int firstContactConstraintOffset = dindex;
// The btSequentialImpulseConstraintSolver moves all friction constraints at the very end, we can also interleave them instead
- if (interleaveContactAndFriction)
+ if (interleaveContactAndFriction1)
{
for (int i = 0; i < m_tmpSolverContactConstraintPool.size(); i++)
{
@@ -785,7 +785,7 @@ btScalar btMultiBodyMLCPConstraintSolver::solveGroupCacheFriendlySetup(
firstContactConstraintOffset = dindex;
// The btSequentialImpulseConstraintSolver moves all friction constraints at the very end, we can also interleave them instead
- if (interleaveContactAndFriction)
+ if (interleaveContactAndFriction1)
{
for (int i = 0; i < m_multiBodyNormalContactConstraints.size(); ++i)
{
diff --git a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h
index 6be36ba142..77fdb86bb9 100644
--- a/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h
+++ b/thirdparty/bullet/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h
@@ -156,7 +156,7 @@ protected:
btTypedConstraint** constraints,
int numConstraints,
const btContactSolverInfo& infoGlobal,
- btIDebugDraw* debugDrawer) BT_OVERRIDE;
+ btIDebugDraw* debugDrawer) ;
public:
BT_DECLARE_ALIGNED_ALLOCATOR()