mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
Fixed constraint for btMultiBody and btRigidBody.
This commit is contained in:
parent
e982b2b5dd
commit
9c4cfde3d6
@ -10,6 +10,7 @@
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
|
||||
|
||||
#include "../OpenGLWindow/GLInstancingRenderer.h"
|
||||
#include "BulletCollision/CollisionShapes/btShapeHull.h"
|
||||
@ -134,7 +135,8 @@ void MultiDofDemo::initPhysics()
|
||||
bool spherical = true; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals
|
||||
bool multibodyOnly = false;
|
||||
bool canSleep = true;
|
||||
bool selfCollide = false;
|
||||
bool selfCollide = false;
|
||||
bool multibodyConstraint = true;
|
||||
btVector3 linkHalfExtents(0.05, 0.37, 0.1);
|
||||
btVector3 baseHalfExtents(0.05, 0.37, 0.1);
|
||||
|
||||
@ -236,7 +238,18 @@ void MultiDofDemo::initPhysics()
|
||||
|
||||
m_dynamicsWorld->addRigidBody(body);//,1,1+2);
|
||||
|
||||
|
||||
if (multibodyConstraint) {
|
||||
btVector3 pointInA = -linkHalfExtents;
|
||||
btVector3 pointInB = halfExtents;
|
||||
btMatrix3x3 frameInA;
|
||||
btMatrix3x3 frameInB;
|
||||
frameInA.setIdentity();
|
||||
frameInB.setIdentity();
|
||||
btMultiBodyFixedConstraint* p2p = new btMultiBodyFixedConstraint(mbC,numLinks-1,body,pointInA,pointInB,frameInA,frameInB);
|
||||
//btMultiBodyFixedConstraint* p2p = new btMultiBodyFixedConstraint(mbC,numLinks-1,mbC,numLinks-4,pointInA,pointInA,frameInA,frameInB);
|
||||
p2p->setMaxAppliedImpulse(2.0);
|
||||
m_dynamicsWorld->addMultiBodyConstraint(p2p);
|
||||
}
|
||||
}
|
||||
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
|
@ -32,6 +32,7 @@ SET(BulletDynamics_SRCS
|
||||
Featherstone/btMultiBodyJointLimitConstraint.cpp
|
||||
Featherstone/btMultiBodyConstraint.cpp
|
||||
Featherstone/btMultiBodyPoint2Point.cpp
|
||||
Featherstone/btMultiBodyFixedConstraint.cpp
|
||||
Featherstone/btMultiBodyJointMotor.cpp
|
||||
MLCPSolvers/btDantzigLCP.cpp
|
||||
MLCPSolvers/btMLCPSolver.cpp
|
||||
@ -89,6 +90,7 @@ SET(Featherstone_HDRS
|
||||
Featherstone/btMultiBodyJointLimitConstraint.h
|
||||
Featherstone/btMultiBodyConstraint.h
|
||||
Featherstone/btMultiBodyPoint2Point.h
|
||||
Featherstone/btMultiBodyFixedConstraint.h
|
||||
Featherstone/btMultiBodyJointMotor.h
|
||||
)
|
||||
|
||||
|
@ -319,14 +319,6 @@ protected:
|
||||
const btTransform& transA,const btTransform& transB,const btVector3& linVelA,const btVector3& linVelB,const btVector3& angVelA,const btVector3& angVelB,
|
||||
btConstraintInfo2* info, int row, btVector3& ax1, int rotational, int rotAllowed = false);
|
||||
|
||||
static btScalar btGetMatrixElem(const btMatrix3x3& mat, int index);
|
||||
static bool matrixToEulerXYZ(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerXZY(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerYXZ(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerYZX(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerZXY(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerZYX(const btMatrix3x3& mat,btVector3& xyz);
|
||||
|
||||
public:
|
||||
|
||||
BT_DECLARE_ALIGNED_ALLOCATOR();
|
||||
@ -489,6 +481,14 @@ public:
|
||||
//If no axis is provided, it uses the default axis for this constraint.
|
||||
virtual void setParam(int num, btScalar value, int axis = -1);
|
||||
virtual btScalar getParam(int num, int axis = -1) const;
|
||||
|
||||
static btScalar btGetMatrixElem(const btMatrix3x3& mat, int index);
|
||||
static bool matrixToEulerXYZ(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerXZY(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerYXZ(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerYZX(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerZXY(const btMatrix3x3& mat,btVector3& xyz);
|
||||
static bool matrixToEulerZYX(const btMatrix3x3& mat,btVector3& xyz);
|
||||
};
|
||||
|
||||
|
||||
|
@ -466,6 +466,16 @@ btVector3 btMultiBody::worldDirToLocal(int i, const btVector3 &world_dir) const
|
||||
}
|
||||
}
|
||||
|
||||
btMatrix3x3 btMultiBody::localFrameToWorld(int i, const btMatrix3x3 &local_frame) const
|
||||
{
|
||||
btMatrix3x3 result = local_frame;
|
||||
btVector3 frameInWorld0 = localDirToWorld(i, local_frame.getColumn(0));
|
||||
btVector3 frameInWorld1 = localDirToWorld(i, local_frame.getColumn(1));
|
||||
btVector3 frameInWorld2 = localDirToWorld(i, local_frame.getColumn(2));
|
||||
result.setValue(frameInWorld0[0], frameInWorld1[0], frameInWorld2[0], frameInWorld0[1], frameInWorld1[1], frameInWorld2[1], frameInWorld0[2], frameInWorld1[2], frameInWorld2[2]);
|
||||
return result;
|
||||
}
|
||||
|
||||
void btMultiBody::compTreeLinkVelocities(btVector3 *omega, btVector3 *vel) const
|
||||
{
|
||||
int num_links = getNumLinks();
|
||||
|
@ -272,7 +272,11 @@ public:
|
||||
btVector3 localDirToWorld(int i, const btVector3 &vec) const;
|
||||
btVector3 worldPosToLocal(int i, const btVector3 &vec) const;
|
||||
btVector3 worldDirToLocal(int i, const btVector3 &vec) const;
|
||||
|
||||
|
||||
//
|
||||
// transform a frame in local coordinate to a frame in world coordinate
|
||||
//
|
||||
btMatrix3x3 localFrameToWorld(int i, const btMatrix3x3 &mat) const;
|
||||
|
||||
//
|
||||
// calculate kinetic energy and angular momentum
|
||||
|
@ -53,323 +53,359 @@ void btMultiBodyConstraint::applyDeltaVee(btMultiBodyJacobianData& data, btScala
|
||||
}
|
||||
|
||||
btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstraint& solverConstraint,
|
||||
btMultiBodyJacobianData& data,
|
||||
btScalar* jacOrgA, btScalar* jacOrgB,
|
||||
const btVector3& contactNormalOnB,
|
||||
const btVector3& posAworld, const btVector3& posBworld,
|
||||
btScalar posError,
|
||||
const btContactSolverInfo& infoGlobal,
|
||||
btScalar lowerLimit, btScalar upperLimit,
|
||||
btScalar relaxation,
|
||||
bool isFriction, btScalar desiredVelocity, btScalar cfmSlip)
|
||||
btMultiBodyJacobianData& data,
|
||||
btScalar* jacOrgA, btScalar* jacOrgB,
|
||||
const btVector3& constraintNormalAng,
|
||||
const btVector3& constraintNormalLin,
|
||||
const btVector3& posAworld, const btVector3& posBworld,
|
||||
btScalar posError,
|
||||
const btContactSolverInfo& infoGlobal,
|
||||
btScalar lowerLimit, btScalar upperLimit,
|
||||
bool angConstraint,
|
||||
btScalar relaxation,
|
||||
bool isFriction, btScalar desiredVelocity, btScalar cfmSlip)
|
||||
{
|
||||
|
||||
|
||||
solverConstraint.m_multiBodyA = m_bodyA;
|
||||
solverConstraint.m_multiBodyB = m_bodyB;
|
||||
solverConstraint.m_linkA = m_linkA;
|
||||
solverConstraint.m_linkB = m_linkB;
|
||||
|
||||
btMultiBody* multiBodyA = solverConstraint.m_multiBodyA;
|
||||
btMultiBody* multiBodyB = solverConstraint.m_multiBodyB;
|
||||
|
||||
btSolverBody* bodyA = multiBodyA ? 0 : &data.m_solverBodyPool->at(solverConstraint.m_solverBodyIdA);
|
||||
btSolverBody* bodyB = multiBodyB ? 0 : &data.m_solverBodyPool->at(solverConstraint.m_solverBodyIdB);
|
||||
|
||||
btRigidBody* rb0 = multiBodyA ? 0 : bodyA->m_originalBody;
|
||||
btRigidBody* rb1 = multiBodyB ? 0 : bodyB->m_originalBody;
|
||||
|
||||
btVector3 rel_pos1, rel_pos2; //these two used to be inited to posAworld and posBworld (respectively) but it does not seem necessary
|
||||
if (bodyA)
|
||||
rel_pos1 = posAworld - bodyA->getWorldTransform().getOrigin();
|
||||
if (bodyB)
|
||||
rel_pos2 = posBworld - bodyB->getWorldTransform().getOrigin();
|
||||
|
||||
if (multiBodyA)
|
||||
{
|
||||
if (solverConstraint.m_linkA<0)
|
||||
{
|
||||
rel_pos1 = posAworld - multiBodyA->getBasePos();
|
||||
} else
|
||||
{
|
||||
rel_pos1 = posAworld - multiBodyA->getLink(solverConstraint.m_linkA).m_cachedWorldTransform.getOrigin();
|
||||
}
|
||||
|
||||
const int ndofA = multiBodyA->getNumDofs() + 6;
|
||||
|
||||
solverConstraint.m_deltaVelAindex = multiBodyA->getCompanionId();
|
||||
|
||||
if (solverConstraint.m_deltaVelAindex <0)
|
||||
{
|
||||
solverConstraint.m_deltaVelAindex = data.m_deltaVelocities.size();
|
||||
multiBodyA->setCompanionId(solverConstraint.m_deltaVelAindex);
|
||||
data.m_deltaVelocities.resize(data.m_deltaVelocities.size()+ndofA);
|
||||
} else
|
||||
{
|
||||
btAssert(data.m_deltaVelocities.size() >= solverConstraint.m_deltaVelAindex+ndofA);
|
||||
}
|
||||
|
||||
//determine jacobian of this 1D constraint in terms of multibodyA's degrees of freedom
|
||||
//resize..
|
||||
solverConstraint.m_jacAindex = data.m_jacobians.size();
|
||||
data.m_jacobians.resize(data.m_jacobians.size()+ndofA);
|
||||
//copy/determine
|
||||
if(jacOrgA)
|
||||
{
|
||||
for (int i=0;i<ndofA;i++)
|
||||
data.m_jacobians[solverConstraint.m_jacAindex+i] = jacOrgA[i];
|
||||
}
|
||||
else
|
||||
{
|
||||
btScalar* jac1=&data.m_jacobians[solverConstraint.m_jacAindex];
|
||||
multiBodyA->fillContactJacobianMultiDof(solverConstraint.m_linkA, posAworld, contactNormalOnB, jac1, data.scratch_r, data.scratch_v, data.scratch_m);
|
||||
}
|
||||
|
||||
//determine the velocity response of multibodyA to reaction impulses of this constraint (i.e. A[i,i] for i=1,...n_con: multibody's inverse inertia with respect to this 1D constraint)
|
||||
//resize..
|
||||
data.m_deltaVelocitiesUnitImpulse.resize(data.m_deltaVelocitiesUnitImpulse.size()+ndofA); //=> each constraint row has the constrained tree dofs allocated in m_deltaVelocitiesUnitImpulse
|
||||
btAssert(data.m_jacobians.size() == data.m_deltaVelocitiesUnitImpulse.size());
|
||||
btScalar* delta = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacAindex];
|
||||
//determine..
|
||||
multiBodyA->calcAccelerationDeltasMultiDof(&data.m_jacobians[solverConstraint.m_jacAindex],delta,data.scratch_r, data.scratch_v);
|
||||
|
||||
btVector3 torqueAxis0 = rel_pos1.cross(contactNormalOnB);
|
||||
solverConstraint.m_relpos1CrossNormal = torqueAxis0;
|
||||
solverConstraint.m_contactNormal1 = contactNormalOnB;
|
||||
}
|
||||
else //if(rb0)
|
||||
{
|
||||
btVector3 torqueAxis0 = rel_pos1.cross(contactNormalOnB);
|
||||
solverConstraint.m_angularComponentA = rb0 ? rb0->getInvInertiaTensorWorld()*torqueAxis0*rb0->getAngularFactor() : btVector3(0,0,0);
|
||||
solverConstraint.m_relpos1CrossNormal = torqueAxis0;
|
||||
solverConstraint.m_contactNormal1 = contactNormalOnB;
|
||||
}
|
||||
|
||||
if (multiBodyB)
|
||||
{
|
||||
if (solverConstraint.m_linkB<0)
|
||||
{
|
||||
rel_pos2 = posBworld - multiBodyB->getBasePos();
|
||||
} else
|
||||
{
|
||||
rel_pos2 = posBworld - multiBodyB->getLink(solverConstraint.m_linkB).m_cachedWorldTransform.getOrigin();
|
||||
}
|
||||
|
||||
const int ndofB = multiBodyB->getNumDofs() + 6;
|
||||
|
||||
solverConstraint.m_deltaVelBindex = multiBodyB->getCompanionId();
|
||||
if (solverConstraint.m_deltaVelBindex <0)
|
||||
{
|
||||
solverConstraint.m_deltaVelBindex = data.m_deltaVelocities.size();
|
||||
multiBodyB->setCompanionId(solverConstraint.m_deltaVelBindex);
|
||||
data.m_deltaVelocities.resize(data.m_deltaVelocities.size()+ndofB);
|
||||
}
|
||||
|
||||
//determine jacobian of this 1D constraint in terms of multibodyB's degrees of freedom
|
||||
//resize..
|
||||
solverConstraint.m_jacBindex = data.m_jacobians.size();
|
||||
data.m_jacobians.resize(data.m_jacobians.size()+ndofB);
|
||||
//copy/determine..
|
||||
if(jacOrgB)
|
||||
{
|
||||
for (int i=0;i<ndofB;i++)
|
||||
data.m_jacobians[solverConstraint.m_jacBindex+i] = jacOrgB[i];
|
||||
}
|
||||
else
|
||||
{
|
||||
multiBodyB->fillContactJacobianMultiDof(solverConstraint.m_linkB, posBworld, -contactNormalOnB, &data.m_jacobians[solverConstraint.m_jacBindex], data.scratch_r, data.scratch_v, data.scratch_m);
|
||||
}
|
||||
|
||||
//determine velocity response of multibodyB to reaction impulses of this constraint (i.e. A[i,i] for i=1,...n_con: multibody's inverse inertia with respect to this 1D constraint)
|
||||
//resize..
|
||||
data.m_deltaVelocitiesUnitImpulse.resize(data.m_deltaVelocitiesUnitImpulse.size()+ndofB);
|
||||
btAssert(data.m_jacobians.size() == data.m_deltaVelocitiesUnitImpulse.size());
|
||||
btScalar* delta = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacBindex];
|
||||
//determine..
|
||||
multiBodyB->calcAccelerationDeltasMultiDof(&data.m_jacobians[solverConstraint.m_jacBindex],delta,data.scratch_r, data.scratch_v);
|
||||
|
||||
btVector3 torqueAxis1 = rel_pos2.cross(contactNormalOnB);
|
||||
solverConstraint.m_relpos2CrossNormal = -torqueAxis1;
|
||||
solverConstraint.m_contactNormal2 = -contactNormalOnB;
|
||||
|
||||
}
|
||||
else //if(rb1)
|
||||
{
|
||||
btVector3 torqueAxis1 = rel_pos2.cross(contactNormalOnB);
|
||||
solverConstraint.m_angularComponentB = rb1 ? rb1->getInvInertiaTensorWorld()*-torqueAxis1*rb1->getAngularFactor() : btVector3(0,0,0);
|
||||
solverConstraint.m_relpos2CrossNormal = -torqueAxis1;
|
||||
solverConstraint.m_contactNormal2 = -contactNormalOnB;
|
||||
}
|
||||
{
|
||||
|
||||
btVector3 vec;
|
||||
btScalar denom0 = 0.f;
|
||||
btScalar denom1 = 0.f;
|
||||
btScalar* jacB = 0;
|
||||
btScalar* jacA = 0;
|
||||
btScalar* deltaVelA = 0;
|
||||
btScalar* deltaVelB = 0;
|
||||
int ndofA = 0;
|
||||
//determine the "effective mass" of the constrained multibodyA with respect to this 1D constraint (i.e. 1/A[i,i])
|
||||
if (multiBodyA)
|
||||
{
|
||||
ndofA = multiBodyA->getNumDofs() + 6;
|
||||
jacA = &data.m_jacobians[solverConstraint.m_jacAindex];
|
||||
deltaVelA = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacAindex];
|
||||
for (int i = 0; i < ndofA; ++i)
|
||||
{
|
||||
btScalar j = jacA[i] ;
|
||||
btScalar l = deltaVelA[i];
|
||||
denom0 += j*l;
|
||||
}
|
||||
}
|
||||
else if(rb0)
|
||||
{
|
||||
vec = ( solverConstraint.m_angularComponentA).cross(rel_pos1);
|
||||
denom0 = rb0->getInvMass() + contactNormalOnB.dot(vec);
|
||||
}
|
||||
//
|
||||
if (multiBodyB)
|
||||
{
|
||||
const int ndofB = multiBodyB->getNumDofs() + 6;
|
||||
jacB = &data.m_jacobians[solverConstraint.m_jacBindex];
|
||||
deltaVelB = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacBindex];
|
||||
for (int i = 0; i < ndofB; ++i)
|
||||
{
|
||||
btScalar j = jacB[i] ;
|
||||
btScalar l = deltaVelB[i];
|
||||
denom1 += j*l;
|
||||
}
|
||||
|
||||
}
|
||||
else if(rb1)
|
||||
{
|
||||
vec = ( -solverConstraint.m_angularComponentB).cross(rel_pos2);
|
||||
denom1 = rb1->getInvMass() + contactNormalOnB.dot(vec);
|
||||
}
|
||||
|
||||
//
|
||||
btScalar d = denom0+denom1;
|
||||
if (d>SIMD_EPSILON)
|
||||
{
|
||||
solverConstraint.m_jacDiagABInv = relaxation/(d);
|
||||
}
|
||||
else
|
||||
{
|
||||
//disable the constraint row to handle singularity/redundant constraint
|
||||
solverConstraint.m_jacDiagABInv = 0.f;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//compute rhs and remaining solverConstraint fields
|
||||
btScalar penetration = isFriction? 0 : posError+infoGlobal.m_linearSlop;
|
||||
|
||||
btScalar rel_vel = 0.f;
|
||||
int ndofA = 0;
|
||||
int ndofB = 0;
|
||||
{
|
||||
btVector3 vel1,vel2;
|
||||
if (multiBodyA)
|
||||
{
|
||||
ndofA = multiBodyA->getNumDofs() + 6;
|
||||
btScalar* jacA = &data.m_jacobians[solverConstraint.m_jacAindex];
|
||||
for (int i = 0; i < ndofA ; ++i)
|
||||
rel_vel += multiBodyA->getVelocityVector()[i] * jacA[i];
|
||||
}
|
||||
else if(rb0)
|
||||
{
|
||||
rel_vel += rb0->getVelocityInLocalPoint(rel_pos1).dot(solverConstraint.m_contactNormal1);
|
||||
}
|
||||
if (multiBodyB)
|
||||
{
|
||||
ndofB = multiBodyB->getNumDofs() + 6;
|
||||
btScalar* jacB = &data.m_jacobians[solverConstraint.m_jacBindex];
|
||||
for (int i = 0; i < ndofB ; ++i)
|
||||
rel_vel += multiBodyB->getVelocityVector()[i] * jacB[i];
|
||||
|
||||
}
|
||||
else if(rb1)
|
||||
{
|
||||
rel_vel += rb1->getVelocityInLocalPoint(rel_pos2).dot(solverConstraint.m_contactNormal2);
|
||||
}
|
||||
|
||||
solverConstraint.m_friction = 0.f;//cp.m_combinedFriction;
|
||||
}
|
||||
|
||||
|
||||
///warm starting (or zero if disabled)
|
||||
/*
|
||||
if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING)
|
||||
{
|
||||
solverConstraint.m_appliedImpulse = isFriction ? 0 : cp.m_appliedImpulse * infoGlobal.m_warmstartingFactor;
|
||||
|
||||
if (solverConstraint.m_appliedImpulse)
|
||||
{
|
||||
if (multiBodyA)
|
||||
{
|
||||
btScalar impulse = solverConstraint.m_appliedImpulse;
|
||||
btScalar* deltaV = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacAindex];
|
||||
multiBodyA->applyDeltaVee(deltaV,impulse);
|
||||
applyDeltaVee(data,deltaV,impulse,solverConstraint.m_deltaVelAindex,ndofA);
|
||||
} else
|
||||
{
|
||||
if (rb0)
|
||||
solverConstraint.m_multiBodyA = m_bodyA;
|
||||
solverConstraint.m_multiBodyB = m_bodyB;
|
||||
solverConstraint.m_linkA = m_linkA;
|
||||
solverConstraint.m_linkB = m_linkB;
|
||||
|
||||
btMultiBody* multiBodyA = solverConstraint.m_multiBodyA;
|
||||
btMultiBody* multiBodyB = solverConstraint.m_multiBodyB;
|
||||
|
||||
btSolverBody* bodyA = multiBodyA ? 0 : &data.m_solverBodyPool->at(solverConstraint.m_solverBodyIdA);
|
||||
btSolverBody* bodyB = multiBodyB ? 0 : &data.m_solverBodyPool->at(solverConstraint.m_solverBodyIdB);
|
||||
|
||||
btRigidBody* rb0 = multiBodyA ? 0 : bodyA->m_originalBody;
|
||||
btRigidBody* rb1 = multiBodyB ? 0 : bodyB->m_originalBody;
|
||||
|
||||
btVector3 rel_pos1, rel_pos2; //these two used to be inited to posAworld and posBworld (respectively) but it does not seem necessary
|
||||
if (bodyA)
|
||||
rel_pos1 = posAworld - bodyA->getWorldTransform().getOrigin();
|
||||
if (bodyB)
|
||||
rel_pos2 = posBworld - bodyB->getWorldTransform().getOrigin();
|
||||
|
||||
if (multiBodyA)
|
||||
{
|
||||
if (solverConstraint.m_linkA<0)
|
||||
{
|
||||
rel_pos1 = posAworld - multiBodyA->getBasePos();
|
||||
} else
|
||||
{
|
||||
rel_pos1 = posAworld - multiBodyA->getLink(solverConstraint.m_linkA).m_cachedWorldTransform.getOrigin();
|
||||
}
|
||||
|
||||
const int ndofA = multiBodyA->getNumDofs() + 6;
|
||||
|
||||
solverConstraint.m_deltaVelAindex = multiBodyA->getCompanionId();
|
||||
|
||||
if (solverConstraint.m_deltaVelAindex <0)
|
||||
{
|
||||
solverConstraint.m_deltaVelAindex = data.m_deltaVelocities.size();
|
||||
multiBodyA->setCompanionId(solverConstraint.m_deltaVelAindex);
|
||||
data.m_deltaVelocities.resize(data.m_deltaVelocities.size()+ndofA);
|
||||
} else
|
||||
{
|
||||
btAssert(data.m_deltaVelocities.size() >= solverConstraint.m_deltaVelAindex+ndofA);
|
||||
}
|
||||
|
||||
//determine jacobian of this 1D constraint in terms of multibodyA's degrees of freedom
|
||||
//resize..
|
||||
solverConstraint.m_jacAindex = data.m_jacobians.size();
|
||||
data.m_jacobians.resize(data.m_jacobians.size()+ndofA);
|
||||
//copy/determine
|
||||
if(jacOrgA)
|
||||
{
|
||||
for (int i=0;i<ndofA;i++)
|
||||
data.m_jacobians[solverConstraint.m_jacAindex+i] = jacOrgA[i];
|
||||
}
|
||||
else
|
||||
{
|
||||
btScalar* jac1=&data.m_jacobians[solverConstraint.m_jacAindex];
|
||||
//multiBodyA->fillContactJacobianMultiDof(solverConstraint.m_linkA, posAworld, constraintNormalLin, jac1, data.scratch_r, data.scratch_v, data.scratch_m);
|
||||
multiBodyA->fillConstraintJacobianMultiDof(solverConstraint.m_linkA, posAworld, constraintNormalAng, constraintNormalLin, jac1, data.scratch_r, data.scratch_v, data.scratch_m);
|
||||
}
|
||||
|
||||
//determine the velocity response of multibodyA to reaction impulses of this constraint (i.e. A[i,i] for i=1,...n_con: multibody's inverse inertia with respect to this 1D constraint)
|
||||
//resize..
|
||||
data.m_deltaVelocitiesUnitImpulse.resize(data.m_deltaVelocitiesUnitImpulse.size()+ndofA); //=> each constraint row has the constrained tree dofs allocated in m_deltaVelocitiesUnitImpulse
|
||||
btAssert(data.m_jacobians.size() == data.m_deltaVelocitiesUnitImpulse.size());
|
||||
btScalar* delta = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacAindex];
|
||||
//determine..
|
||||
multiBodyA->calcAccelerationDeltasMultiDof(&data.m_jacobians[solverConstraint.m_jacAindex],delta,data.scratch_r, data.scratch_v);
|
||||
|
||||
btVector3 torqueAxis0;
|
||||
if (angConstraint) {
|
||||
torqueAxis0 = constraintNormalAng;
|
||||
}
|
||||
else {
|
||||
torqueAxis0 = rel_pos1.cross(constraintNormalLin);
|
||||
|
||||
}
|
||||
solverConstraint.m_relpos1CrossNormal = torqueAxis0;
|
||||
solverConstraint.m_contactNormal1 = constraintNormalLin;
|
||||
}
|
||||
else //if(rb0)
|
||||
{
|
||||
btVector3 torqueAxis0;
|
||||
if (angConstraint) {
|
||||
torqueAxis0 = constraintNormalAng;
|
||||
}
|
||||
else {
|
||||
torqueAxis0 = rel_pos1.cross(constraintNormalLin);
|
||||
}
|
||||
solverConstraint.m_angularComponentA = rb0 ? rb0->getInvInertiaTensorWorld()*torqueAxis0*rb0->getAngularFactor() : btVector3(0,0,0);
|
||||
solverConstraint.m_relpos1CrossNormal = torqueAxis0;
|
||||
solverConstraint.m_contactNormal1 = constraintNormalLin;
|
||||
}
|
||||
|
||||
if (multiBodyB)
|
||||
{
|
||||
if (solverConstraint.m_linkB<0)
|
||||
{
|
||||
rel_pos2 = posBworld - multiBodyB->getBasePos();
|
||||
} else
|
||||
{
|
||||
rel_pos2 = posBworld - multiBodyB->getLink(solverConstraint.m_linkB).m_cachedWorldTransform.getOrigin();
|
||||
}
|
||||
|
||||
const int ndofB = multiBodyB->getNumDofs() + 6;
|
||||
|
||||
solverConstraint.m_deltaVelBindex = multiBodyB->getCompanionId();
|
||||
if (solverConstraint.m_deltaVelBindex <0)
|
||||
{
|
||||
solverConstraint.m_deltaVelBindex = data.m_deltaVelocities.size();
|
||||
multiBodyB->setCompanionId(solverConstraint.m_deltaVelBindex);
|
||||
data.m_deltaVelocities.resize(data.m_deltaVelocities.size()+ndofB);
|
||||
}
|
||||
|
||||
//determine jacobian of this 1D constraint in terms of multibodyB's degrees of freedom
|
||||
//resize..
|
||||
solverConstraint.m_jacBindex = data.m_jacobians.size();
|
||||
data.m_jacobians.resize(data.m_jacobians.size()+ndofB);
|
||||
//copy/determine..
|
||||
if(jacOrgB)
|
||||
{
|
||||
for (int i=0;i<ndofB;i++)
|
||||
data.m_jacobians[solverConstraint.m_jacBindex+i] = jacOrgB[i];
|
||||
}
|
||||
else
|
||||
{
|
||||
//multiBodyB->fillContactJacobianMultiDof(solverConstraint.m_linkB, posBworld, -constraintNormalLin, &data.m_jacobians[solverConstraint.m_jacBindex], data.scratch_r, data.scratch_v, data.scratch_m);
|
||||
multiBodyB->fillConstraintJacobianMultiDof(solverConstraint.m_linkB, posBworld, -constraintNormalAng, -constraintNormalLin, &data.m_jacobians[solverConstraint.m_jacBindex], data.scratch_r, data.scratch_v, data.scratch_m);
|
||||
}
|
||||
|
||||
//determine velocity response of multibodyB to reaction impulses of this constraint (i.e. A[i,i] for i=1,...n_con: multibody's inverse inertia with respect to this 1D constraint)
|
||||
//resize..
|
||||
data.m_deltaVelocitiesUnitImpulse.resize(data.m_deltaVelocitiesUnitImpulse.size()+ndofB);
|
||||
btAssert(data.m_jacobians.size() == data.m_deltaVelocitiesUnitImpulse.size());
|
||||
btScalar* delta = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacBindex];
|
||||
//determine..
|
||||
multiBodyB->calcAccelerationDeltasMultiDof(&data.m_jacobians[solverConstraint.m_jacBindex],delta,data.scratch_r, data.scratch_v);
|
||||
|
||||
btVector3 torqueAxis1;
|
||||
if (angConstraint) {
|
||||
torqueAxis1 = constraintNormalAng;
|
||||
}
|
||||
else {
|
||||
torqueAxis1 = rel_pos2.cross(constraintNormalLin);
|
||||
}
|
||||
solverConstraint.m_relpos2CrossNormal = -torqueAxis1;
|
||||
solverConstraint.m_contactNormal2 = -constraintNormalLin;
|
||||
}
|
||||
else //if(rb1)
|
||||
{
|
||||
btVector3 torqueAxis1;
|
||||
if (angConstraint) {
|
||||
torqueAxis1 = constraintNormalAng;
|
||||
}
|
||||
else {
|
||||
torqueAxis1 = rel_pos2.cross(constraintNormalLin);
|
||||
}
|
||||
solverConstraint.m_angularComponentB = rb1 ? rb1->getInvInertiaTensorWorld()*-torqueAxis1*rb1->getAngularFactor() : btVector3(0,0,0);
|
||||
solverConstraint.m_relpos2CrossNormal = -torqueAxis1;
|
||||
solverConstraint.m_contactNormal2 = -constraintNormalLin;
|
||||
}
|
||||
{
|
||||
|
||||
btVector3 vec;
|
||||
btScalar denom0 = 0.f;
|
||||
btScalar denom1 = 0.f;
|
||||
btScalar* jacB = 0;
|
||||
btScalar* jacA = 0;
|
||||
btScalar* deltaVelA = 0;
|
||||
btScalar* deltaVelB = 0;
|
||||
int ndofA = 0;
|
||||
//determine the "effective mass" of the constrained multibodyA with respect to this 1D constraint (i.e. 1/A[i,i])
|
||||
if (multiBodyA)
|
||||
{
|
||||
ndofA = multiBodyA->getNumDofs() + 6;
|
||||
jacA = &data.m_jacobians[solverConstraint.m_jacAindex];
|
||||
deltaVelA = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacAindex];
|
||||
for (int i = 0; i < ndofA; ++i)
|
||||
{
|
||||
btScalar j = jacA[i] ;
|
||||
btScalar l = deltaVelA[i];
|
||||
denom0 += j*l;
|
||||
}
|
||||
}
|
||||
else if(rb0)
|
||||
{
|
||||
vec = ( solverConstraint.m_angularComponentA).cross(rel_pos1);
|
||||
if (angConstraint) {
|
||||
denom0 = rb0->getInvMass() + constraintNormalAng.dot(vec);
|
||||
}
|
||||
else {
|
||||
denom0 = rb0->getInvMass() + constraintNormalLin.dot(vec);
|
||||
}
|
||||
}
|
||||
//
|
||||
if (multiBodyB)
|
||||
{
|
||||
const int ndofB = multiBodyB->getNumDofs() + 6;
|
||||
jacB = &data.m_jacobians[solverConstraint.m_jacBindex];
|
||||
deltaVelB = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacBindex];
|
||||
for (int i = 0; i < ndofB; ++i)
|
||||
{
|
||||
btScalar j = jacB[i] ;
|
||||
btScalar l = deltaVelB[i];
|
||||
denom1 += j*l;
|
||||
}
|
||||
|
||||
}
|
||||
else if(rb1)
|
||||
{
|
||||
vec = ( -solverConstraint.m_angularComponentB).cross(rel_pos2);
|
||||
if (angConstraint) {
|
||||
denom1 = rb1->getInvMass() + constraintNormalAng.dot(vec);
|
||||
}
|
||||
else {
|
||||
denom1 = rb1->getInvMass() + constraintNormalLin.dot(vec);
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
btScalar d = denom0+denom1;
|
||||
if (d>SIMD_EPSILON)
|
||||
{
|
||||
solverConstraint.m_jacDiagABInv = relaxation/(d);
|
||||
}
|
||||
else
|
||||
{
|
||||
//disable the constraint row to handle singularity/redundant constraint
|
||||
solverConstraint.m_jacDiagABInv = 0.f;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//compute rhs and remaining solverConstraint fields
|
||||
btScalar penetration = isFriction? 0 : posError+infoGlobal.m_linearSlop;
|
||||
|
||||
btScalar rel_vel = 0.f;
|
||||
int ndofA = 0;
|
||||
int ndofB = 0;
|
||||
{
|
||||
btVector3 vel1,vel2;
|
||||
if (multiBodyA)
|
||||
{
|
||||
ndofA = multiBodyA->getNumDofs() + 6;
|
||||
btScalar* jacA = &data.m_jacobians[solverConstraint.m_jacAindex];
|
||||
for (int i = 0; i < ndofA ; ++i)
|
||||
rel_vel += multiBodyA->getVelocityVector()[i] * jacA[i];
|
||||
}
|
||||
else if(rb0)
|
||||
{
|
||||
rel_vel += rb0->getVelocityInLocalPoint(rel_pos1).dot(solverConstraint.m_contactNormal1);
|
||||
}
|
||||
if (multiBodyB)
|
||||
{
|
||||
ndofB = multiBodyB->getNumDofs() + 6;
|
||||
btScalar* jacB = &data.m_jacobians[solverConstraint.m_jacBindex];
|
||||
for (int i = 0; i < ndofB ; ++i)
|
||||
rel_vel += multiBodyB->getVelocityVector()[i] * jacB[i];
|
||||
|
||||
}
|
||||
else if(rb1)
|
||||
{
|
||||
rel_vel += rb1->getVelocityInLocalPoint(rel_pos2).dot(solverConstraint.m_contactNormal2);
|
||||
}
|
||||
|
||||
solverConstraint.m_friction = 0.f;//cp.m_combinedFriction;
|
||||
}
|
||||
|
||||
|
||||
///warm starting (or zero if disabled)
|
||||
/*
|
||||
if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING)
|
||||
{
|
||||
solverConstraint.m_appliedImpulse = isFriction ? 0 : cp.m_appliedImpulse * infoGlobal.m_warmstartingFactor;
|
||||
|
||||
if (solverConstraint.m_appliedImpulse)
|
||||
{
|
||||
if (multiBodyA)
|
||||
{
|
||||
btScalar impulse = solverConstraint.m_appliedImpulse;
|
||||
btScalar* deltaV = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacAindex];
|
||||
multiBodyA->applyDeltaVee(deltaV,impulse);
|
||||
applyDeltaVee(data,deltaV,impulse,solverConstraint.m_deltaVelAindex,ndofA);
|
||||
} else
|
||||
{
|
||||
if (rb0)
|
||||
bodyA->internalApplyImpulse(solverConstraint.m_contactNormal1*bodyA->internalGetInvMass()*rb0->getLinearFactor(),solverConstraint.m_angularComponentA,solverConstraint.m_appliedImpulse);
|
||||
}
|
||||
if (multiBodyB)
|
||||
{
|
||||
btScalar impulse = solverConstraint.m_appliedImpulse;
|
||||
btScalar* deltaV = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacBindex];
|
||||
multiBodyB->applyDeltaVee(deltaV,impulse);
|
||||
applyDeltaVee(data,deltaV,impulse,solverConstraint.m_deltaVelBindex,ndofB);
|
||||
} else
|
||||
{
|
||||
if (rb1)
|
||||
}
|
||||
if (multiBodyB)
|
||||
{
|
||||
btScalar impulse = solverConstraint.m_appliedImpulse;
|
||||
btScalar* deltaV = &data.m_deltaVelocitiesUnitImpulse[solverConstraint.m_jacBindex];
|
||||
multiBodyB->applyDeltaVee(deltaV,impulse);
|
||||
applyDeltaVee(data,deltaV,impulse,solverConstraint.m_deltaVelBindex,ndofB);
|
||||
} else
|
||||
{
|
||||
if (rb1)
|
||||
bodyB->internalApplyImpulse(-solverConstraint.m_contactNormal2*bodyB->internalGetInvMass()*rb1->getLinearFactor(),-solverConstraint.m_angularComponentB,-(btScalar)solverConstraint.m_appliedImpulse);
|
||||
}
|
||||
}
|
||||
} else
|
||||
*/
|
||||
|
||||
solverConstraint.m_appliedImpulse = 0.f;
|
||||
solverConstraint.m_appliedPushImpulse = 0.f;
|
||||
|
||||
{
|
||||
|
||||
btScalar positionalError = 0.f;
|
||||
btScalar velocityError = desiredVelocity - rel_vel;// * damping;
|
||||
|
||||
|
||||
btScalar erp = infoGlobal.m_erp2;
|
||||
if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold))
|
||||
{
|
||||
erp = infoGlobal.m_erp;
|
||||
}
|
||||
|
||||
positionalError = -penetration * erp/infoGlobal.m_timeStep;
|
||||
|
||||
btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv;
|
||||
btScalar velocityImpulse = velocityError *solverConstraint.m_jacDiagABInv;
|
||||
|
||||
if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold))
|
||||
{
|
||||
//combine position and velocity into rhs
|
||||
solverConstraint.m_rhs = penetrationImpulse+velocityImpulse;
|
||||
solverConstraint.m_rhsPenetration = 0.f;
|
||||
|
||||
} else
|
||||
{
|
||||
//split position and velocity into rhs and m_rhsPenetration
|
||||
solverConstraint.m_rhs = velocityImpulse;
|
||||
solverConstraint.m_rhsPenetration = penetrationImpulse;
|
||||
}
|
||||
|
||||
solverConstraint.m_cfm = 0.f;
|
||||
solverConstraint.m_lowerLimit = lowerLimit;
|
||||
solverConstraint.m_upperLimit = upperLimit;
|
||||
}
|
||||
|
||||
return rel_vel;
|
||||
|
||||
}
|
||||
}
|
||||
} else
|
||||
*/
|
||||
|
||||
solverConstraint.m_appliedImpulse = 0.f;
|
||||
solverConstraint.m_appliedPushImpulse = 0.f;
|
||||
|
||||
{
|
||||
|
||||
btScalar positionalError = 0.f;
|
||||
btScalar velocityError = desiredVelocity - rel_vel;// * damping;
|
||||
|
||||
|
||||
btScalar erp = infoGlobal.m_erp2;
|
||||
if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold))
|
||||
{
|
||||
erp = infoGlobal.m_erp;
|
||||
}
|
||||
|
||||
positionalError = -penetration * erp/infoGlobal.m_timeStep;
|
||||
|
||||
btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv;
|
||||
btScalar velocityImpulse = velocityError *solverConstraint.m_jacDiagABInv;
|
||||
|
||||
if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold))
|
||||
{
|
||||
//combine position and velocity into rhs
|
||||
solverConstraint.m_rhs = penetrationImpulse+velocityImpulse;
|
||||
solverConstraint.m_rhsPenetration = 0.f;
|
||||
|
||||
} else
|
||||
{
|
||||
//split position and velocity into rhs and m_rhsPenetration
|
||||
solverConstraint.m_rhs = velocityImpulse;
|
||||
solverConstraint.m_rhsPenetration = penetrationImpulse;
|
||||
}
|
||||
|
||||
solverConstraint.m_cfm = 0.f;
|
||||
solverConstraint.m_lowerLimit = lowerLimit;
|
||||
solverConstraint.m_upperLimit = upperLimit;
|
||||
}
|
||||
|
||||
return rel_vel;
|
||||
|
||||
}
|
||||
|
@ -66,15 +66,19 @@ protected:
|
||||
btAlignedObjectArray<btScalar> m_data;
|
||||
|
||||
void applyDeltaVee(btMultiBodyJacobianData& data, btScalar* delta_vee, btScalar impulse, int velocityIndex, int ndof);
|
||||
|
||||
|
||||
btScalar fillMultiBodyConstraint(btMultiBodySolverConstraint& solverConstraint,
|
||||
btMultiBodyJacobianData& data,
|
||||
btScalar* jacOrgA, btScalar* jacOrgB,
|
||||
const btVector3& contactNormalOnB,
|
||||
btScalar* jacOrgA, btScalar* jacOrgB,
|
||||
const btVector3& constraintNormalAng,
|
||||
|
||||
const btVector3& constraintNormalLin,
|
||||
const btVector3& posAworld, const btVector3& posBworld,
|
||||
btScalar posError,
|
||||
const btContactSolverInfo& infoGlobal,
|
||||
btScalar lowerLimit, btScalar upperLimit,
|
||||
btScalar lowerLimit, btScalar upperLimit,
|
||||
bool angConstraint = false,
|
||||
|
||||
btScalar relaxation = 1.f,
|
||||
bool isFriction = false, btScalar desiredVelocity=0, btScalar cfmSlip=0);
|
||||
|
||||
|
211
src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp
Normal file
211
src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp
Normal file
@ -0,0 +1,211 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2013 Erwin Coumans http://bulletphysics.org
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
///This file was written by Erwin Coumans
|
||||
|
||||
#include "btMultiBodyFixedConstraint.h"
|
||||
#include "btMultiBodyLinkCollider.h"
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.h"
|
||||
#include "LinearMath/btIDebugDraw.h"
|
||||
|
||||
#define BTMBFIXEDCONSTRAINT_DIM 6
|
||||
|
||||
btMultiBodyFixedConstraint::btMultiBodyFixedConstraint(btMultiBody* body, int link, btRigidBody* bodyB, const btVector3& pivotInA, const btVector3& pivotInB, const btMatrix3x3& frameInA, const btMatrix3x3& frameInB)
|
||||
:btMultiBodyConstraint(body,0,link,-1,BTMBFIXEDCONSTRAINT_DIM,false),
|
||||
m_rigidBodyA(0),
|
||||
m_rigidBodyB(bodyB),
|
||||
m_pivotInA(pivotInA),
|
||||
m_pivotInB(pivotInB),
|
||||
m_frameInA(frameInA),
|
||||
m_frameInB(frameInB)
|
||||
{
|
||||
m_data.resize(BTMBFIXEDCONSTRAINT_DIM);//at least store the applied impulses
|
||||
}
|
||||
|
||||
btMultiBodyFixedConstraint::btMultiBodyFixedConstraint(btMultiBody* bodyA, int linkA, btMultiBody* bodyB, int linkB, const btVector3& pivotInA, const btVector3& pivotInB, const btMatrix3x3& frameInA, const btMatrix3x3& frameInB)
|
||||
:btMultiBodyConstraint(bodyA,bodyB,linkA,linkB,BTMBFIXEDCONSTRAINT_DIM,false),
|
||||
m_rigidBodyA(0),
|
||||
m_rigidBodyB(0),
|
||||
m_pivotInA(pivotInA),
|
||||
m_pivotInB(pivotInB),
|
||||
m_frameInA(frameInA),
|
||||
m_frameInB(frameInB)
|
||||
{
|
||||
m_data.resize(BTMBFIXEDCONSTRAINT_DIM);//at least store the applied impulses
|
||||
}
|
||||
|
||||
void btMultiBodyFixedConstraint::finalizeMultiDof()
|
||||
{
|
||||
//not implemented yet
|
||||
btAssert(0);
|
||||
}
|
||||
|
||||
btMultiBodyFixedConstraint::~btMultiBodyFixedConstraint()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
int btMultiBodyFixedConstraint::getIslandIdA() const
|
||||
{
|
||||
if (m_rigidBodyA)
|
||||
return m_rigidBodyA->getIslandTag();
|
||||
|
||||
if (m_bodyA)
|
||||
{
|
||||
btMultiBodyLinkCollider* col = m_bodyA->getBaseCollider();
|
||||
if (col)
|
||||
return col->getIslandTag();
|
||||
for (int i=0;i<m_bodyA->getNumLinks();i++)
|
||||
{
|
||||
if (m_bodyA->getLink(i).m_collider)
|
||||
return m_bodyA->getLink(i).m_collider->getIslandTag();
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
int btMultiBodyFixedConstraint::getIslandIdB() const
|
||||
{
|
||||
if (m_rigidBodyB)
|
||||
return m_rigidBodyB->getIslandTag();
|
||||
if (m_bodyB)
|
||||
{
|
||||
btMultiBodyLinkCollider* col = m_bodyB->getBaseCollider();
|
||||
if (col)
|
||||
return col->getIslandTag();
|
||||
|
||||
for (int i=0;i<m_bodyB->getNumLinks();i++)
|
||||
{
|
||||
col = m_bodyB->getLink(i).m_collider;
|
||||
if (col)
|
||||
return col->getIslandTag();
|
||||
}
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
void btMultiBodyFixedConstraint::createConstraintRows(btMultiBodyConstraintArray& constraintRows, btMultiBodyJacobianData& data, const btContactSolverInfo& infoGlobal)
|
||||
{
|
||||
int numDim = BTMBFIXEDCONSTRAINT_DIM;
|
||||
for (int i=0;i<numDim;i++)
|
||||
{
|
||||
btMultiBodySolverConstraint& constraintRow = constraintRows.expandNonInitializing();
|
||||
constraintRow.m_orgConstraint = this;
|
||||
constraintRow.m_orgDofIndex = i;
|
||||
constraintRow.m_relpos1CrossNormal.setValue(0,0,0);
|
||||
constraintRow.m_contactNormal1.setValue(0,0,0);
|
||||
constraintRow.m_relpos2CrossNormal.setValue(0,0,0);
|
||||
constraintRow.m_contactNormal2.setValue(0,0,0);
|
||||
constraintRow.m_angularComponentA.setValue(0,0,0);
|
||||
constraintRow.m_angularComponentB.setValue(0,0,0);
|
||||
|
||||
constraintRow.m_solverBodyIdA = data.m_fixedBodyId;
|
||||
constraintRow.m_solverBodyIdB = data.m_fixedBodyId;
|
||||
|
||||
// Convert local points back to world
|
||||
btVector3 pivotAworld = m_pivotInA;
|
||||
btMatrix3x3 frameAworld = m_frameInA;
|
||||
if (m_rigidBodyA)
|
||||
{
|
||||
|
||||
constraintRow.m_solverBodyIdA = m_rigidBodyA->getCompanionId();
|
||||
pivotAworld = m_rigidBodyA->getCenterOfMassTransform()*m_pivotInA;
|
||||
frameAworld = frameAworld.transpose()*btMatrix3x3(m_rigidBodyA->getOrientation());
|
||||
|
||||
} else
|
||||
{
|
||||
if (m_bodyA) {
|
||||
pivotAworld = m_bodyA->localPosToWorld(m_linkA, m_pivotInA);
|
||||
frameAworld = m_bodyA->localFrameToWorld(m_linkA, frameAworld);
|
||||
}
|
||||
}
|
||||
btVector3 pivotBworld = m_pivotInB;
|
||||
btMatrix3x3 frameBworld = m_frameInB;
|
||||
if (m_rigidBodyB)
|
||||
{
|
||||
constraintRow.m_solverBodyIdB = m_rigidBodyB->getCompanionId();
|
||||
pivotBworld = m_rigidBodyB->getCenterOfMassTransform()*m_pivotInB;
|
||||
frameBworld = frameBworld.transpose()*btMatrix3x3(m_rigidBodyB->getOrientation());
|
||||
|
||||
} else
|
||||
{
|
||||
if (m_bodyB) {
|
||||
pivotBworld = m_bodyB->localPosToWorld(m_linkB, m_pivotInB);
|
||||
frameBworld = m_bodyB->localFrameToWorld(m_linkB, frameBworld);
|
||||
}
|
||||
}
|
||||
|
||||
btMatrix3x3 relRot = frameAworld.inverse()*frameBworld;
|
||||
btVector3 angleDiff;
|
||||
btGeneric6DofSpring2Constraint::matrixToEulerXYZ(relRot,angleDiff);
|
||||
|
||||
btVector3 constraintNormalLin(0,0,0);
|
||||
btVector3 constraintNormalAng(0,0,0);
|
||||
btScalar posError = 0.0;
|
||||
if (i < 3) {
|
||||
constraintNormalLin[i] = -1;
|
||||
posError = (pivotAworld-pivotBworld).dot(constraintNormalLin);
|
||||
fillMultiBodyConstraint(constraintRow, data, 0, 0, constraintNormalAng,
|
||||
constraintNormalLin, pivotAworld, pivotBworld,
|
||||
posError,
|
||||
infoGlobal,
|
||||
-m_maxAppliedImpulse, m_maxAppliedImpulse
|
||||
);
|
||||
}
|
||||
else { //i>=3
|
||||
constraintNormalAng = frameAworld.getColumn(i%3);
|
||||
posError = angleDiff[i%3];
|
||||
fillMultiBodyConstraint(constraintRow, data, 0, 0, constraintNormalAng,
|
||||
constraintNormalLin, pivotAworld, pivotBworld,
|
||||
posError,
|
||||
infoGlobal,
|
||||
-m_maxAppliedImpulse, m_maxAppliedImpulse, true
|
||||
);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void btMultiBodyFixedConstraint::debugDraw(class btIDebugDraw* drawer)
|
||||
{
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
|
||||
if (m_rigidBodyA)
|
||||
{
|
||||
btVector3 pivot = m_rigidBodyA->getCenterOfMassTransform() * m_pivotInA;
|
||||
tr.setOrigin(pivot);
|
||||
drawer->drawTransform(tr, 0.1);
|
||||
}
|
||||
if (m_bodyA)
|
||||
{
|
||||
btVector3 pivotAworld = m_bodyA->localPosToWorld(m_linkA, m_pivotInA);
|
||||
tr.setOrigin(pivotAworld);
|
||||
drawer->drawTransform(tr, 0.1);
|
||||
}
|
||||
if (m_rigidBodyB)
|
||||
{
|
||||
// that ideally should draw the same frame
|
||||
btVector3 pivot = m_rigidBodyB->getCenterOfMassTransform() * m_pivotInB;
|
||||
tr.setOrigin(pivot);
|
||||
drawer->drawTransform(tr, 0.1);
|
||||
}
|
||||
if (m_bodyB)
|
||||
{
|
||||
btVector3 pivotBworld = m_bodyB->localPosToWorld(m_linkB, m_pivotInB);
|
||||
tr.setOrigin(pivotBworld);
|
||||
drawer->drawTransform(tr, 0.1);
|
||||
}
|
||||
}
|
94
src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h
Normal file
94
src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h
Normal file
@ -0,0 +1,94 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2013 Erwin Coumans http://bulletphysics.org
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
///This file was written by Erwin Coumans
|
||||
|
||||
#ifndef BT_MULTIBODY_FIXED_CONSTRAINT_H
|
||||
#define BT_MULTIBODY_FIXED_CONSTRAINT_H
|
||||
|
||||
#include "btMultiBodyConstraint.h"
|
||||
|
||||
class btMultiBodyFixedConstraint : public btMultiBodyConstraint
|
||||
{
|
||||
protected:
|
||||
|
||||
btRigidBody* m_rigidBodyA;
|
||||
btRigidBody* m_rigidBodyB;
|
||||
btVector3 m_pivotInA;
|
||||
btVector3 m_pivotInB;
|
||||
btMatrix3x3 m_frameInA;
|
||||
btMatrix3x3 m_frameInB;
|
||||
|
||||
public:
|
||||
|
||||
btMultiBodyFixedConstraint(btMultiBody* body, int link, btRigidBody* bodyB, const btVector3& pivotInA, const btVector3& pivotInB, const btMatrix3x3& frameInA, const btMatrix3x3& frameInB);
|
||||
btMultiBodyFixedConstraint(btMultiBody* bodyA, int linkA, btMultiBody* bodyB, int linkB, const btVector3& pivotInA, const btVector3& pivotInB, const btMatrix3x3& frameInA, const btMatrix3x3& frameInB);
|
||||
|
||||
virtual ~btMultiBodyFixedConstraint();
|
||||
|
||||
virtual void finalizeMultiDof();
|
||||
|
||||
virtual int getIslandIdA() const;
|
||||
virtual int getIslandIdB() const;
|
||||
|
||||
virtual void createConstraintRows(btMultiBodyConstraintArray& constraintRows,
|
||||
btMultiBodyJacobianData& data,
|
||||
const btContactSolverInfo& infoGlobal);
|
||||
|
||||
const btVector3& getPivotInA() const
|
||||
{
|
||||
return m_pivotInA;
|
||||
}
|
||||
|
||||
void setPivotInA(const btVector3& pivotInA)
|
||||
{
|
||||
m_pivotInA = pivotInA;
|
||||
}
|
||||
|
||||
const btVector3& getPivotInB() const
|
||||
{
|
||||
return m_pivotInB;
|
||||
}
|
||||
|
||||
void setPivotInB(const btVector3& pivotInB)
|
||||
{
|
||||
m_pivotInB = pivotInB;
|
||||
}
|
||||
|
||||
const btMatrix3x3& getFrameInA() const
|
||||
{
|
||||
return m_frameInA;
|
||||
}
|
||||
|
||||
void setFrameInA(const btMatrix3x3& frameInA)
|
||||
{
|
||||
m_frameInA = frameInA;
|
||||
}
|
||||
|
||||
const btMatrix3x3& getFrameInB() const
|
||||
{
|
||||
return m_frameInB;
|
||||
}
|
||||
|
||||
void setFrameInB(const btMatrix3x3& frameInB)
|
||||
{
|
||||
m_frameInB = frameInB;
|
||||
}
|
||||
|
||||
virtual void debugDraw(class btIDebugDraw* drawer);
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_MULTIBODY_FIXED_CONSTRAINT_H
|
@ -122,7 +122,7 @@ void btMultiBodyJointLimitConstraint::createConstraintRows(btMultiBodyConstraint
|
||||
const btScalar posError = 0; //why assume it's zero?
|
||||
const btVector3 dummy(0, 0, 0);
|
||||
|
||||
btScalar rel_vel = fillMultiBodyConstraint(constraintRow,data,jacobianA(row),jacobianB(row),dummy,dummy,dummy,posError,infoGlobal,0,m_maxAppliedImpulse);
|
||||
btScalar rel_vel = fillMultiBodyConstraint(constraintRow,data,jacobianA(row),jacobianB(row),dummy,dummy,dummy,dummy,posError,infoGlobal,0,m_maxAppliedImpulse);
|
||||
|
||||
{
|
||||
//expect either prismatic or revolute joint type for now
|
||||
|
@ -128,7 +128,7 @@ void btMultiBodyJointMotor::createConstraintRows(btMultiBodyConstraintArray& con
|
||||
btScalar rhs = m_kp * positionStabiliationTerm + currentVelocity+m_kd * velocityError;
|
||||
|
||||
|
||||
fillMultiBodyConstraint(constraintRow,data,jacobianA(row),jacobianB(row),dummy,dummy,dummy,posError,infoGlobal,-m_maxAppliedImpulse,m_maxAppliedImpulse,1,false,rhs);
|
||||
fillMultiBodyConstraint(constraintRow,data,jacobianA(row),jacobianB(row),dummy,dummy,dummy,dummy,posError,infoGlobal,-m_maxAppliedImpulse,m_maxAppliedImpulse,false,1,false,rhs);
|
||||
constraintRow.m_orgConstraint = this;
|
||||
constraintRow.m_orgDofIndex = row;
|
||||
{
|
||||
|
@ -159,7 +159,7 @@ int numDim = BTMBP2PCONSTRAINT_DIM;
|
||||
#ifndef BTMBP2PCONSTRAINT_BLOCK_ANGULAR_MOTION_TEST
|
||||
|
||||
|
||||
fillMultiBodyConstraint(constraintRow, data, 0, 0,
|
||||
fillMultiBodyConstraint(constraintRow, data, 0, 0, btVector3(0,0,0),
|
||||
contactNormalOnB, pivotAworld, pivotBworld, //sucks but let it be this way "for the time being"
|
||||
posError,
|
||||
infoGlobal,
|
||||
|
Loading…
Reference in New Issue
Block a user