fix an issue with btMultiBodyConstraint, automatically 'finalizeMultiDof' to pre-allocate jacobian data
enable joint limit for slider/prismatic joint in btMultiBody version of URDF loader
This commit is contained in:
@@ -3,7 +3,7 @@
|
||||
#include "btMultiBodyPoint2Point.h" //for testing (BTMBP2PCONSTRAINT_BLOCK_ANGULAR_MOTION_TEST macro)
|
||||
|
||||
|
||||
|
||||
|
||||
btMultiBodyConstraint::btMultiBodyConstraint(btMultiBody* bodyA,btMultiBody* bodyB,int linkA, int linkB, int numRows, bool isUnilateral)
|
||||
:m_bodyA(bodyA),
|
||||
m_bodyB(bodyB),
|
||||
@@ -13,14 +13,15 @@ btMultiBodyConstraint::btMultiBodyConstraint(btMultiBody* bodyA,btMultiBody* bod
|
||||
m_jacSizeA(0),
|
||||
m_jacSizeBoth(0),
|
||||
m_isUnilateral(isUnilateral),
|
||||
m_maxAppliedImpulse(100)
|
||||
m_maxAppliedImpulse(100),
|
||||
m_numDofsFinalized(-1)
|
||||
{
|
||||
finalizeMultiDof();
|
||||
|
||||
}
|
||||
|
||||
void btMultiBodyConstraint::finalizeMultiDof()
|
||||
void btMultiBodyConstraint::updateJacobianSizes()
|
||||
{
|
||||
if(m_bodyA)
|
||||
if(m_bodyA)
|
||||
{
|
||||
if(m_bodyA->isMultiDof())
|
||||
m_jacSizeA = (6 + m_bodyA->getNumDofs());
|
||||
@@ -37,7 +38,12 @@ void btMultiBodyConstraint::finalizeMultiDof()
|
||||
}
|
||||
else
|
||||
m_jacSizeBoth = m_jacSizeA;
|
||||
|
||||
}
|
||||
|
||||
void btMultiBodyConstraint::allocateJacobiansMultiDof()
|
||||
{
|
||||
updateJacobianSizes();
|
||||
|
||||
m_posOffset = ((1 + m_jacSizeBoth)*m_numRows);
|
||||
m_data.resize((2 + m_jacSizeBoth) * m_numRows);
|
||||
}
|
||||
@@ -48,25 +54,27 @@ btMultiBodyConstraint::~btMultiBodyConstraint()
|
||||
|
||||
void btMultiBodyConstraint::applyDeltaVee(btMultiBodyJacobianData& data, btScalar* delta_vee, btScalar impulse, int velocityIndex, int ndof)
|
||||
{
|
||||
for (int i = 0; i < ndof; ++i)
|
||||
for (int i = 0; i < ndof; ++i)
|
||||
data.m_deltaVelocities[velocityIndex+i] += delta_vee[i] * impulse;
|
||||
}
|
||||
|
||||
btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstraint& solverConstraint,
|
||||
btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstraint& solverConstraint,
|
||||
btMultiBodyJacobianData& data,
|
||||
btScalar* jacOrgA, btScalar* jacOrgB,
|
||||
const btVector3& contactNormalOnB,
|
||||
const btVector3& posAworld, const btVector3& posBworld,
|
||||
const btVector3& posAworld, const btVector3& posBworld,
|
||||
btScalar posError,
|
||||
const btContactSolverInfo& infoGlobal,
|
||||
btScalar lowerLimit, btScalar upperLimit,
|
||||
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;
|
||||
solverConstraint.m_linkB = m_linkB;
|
||||
|
||||
btMultiBody* multiBodyA = solverConstraint.m_multiBodyA;
|
||||
btMultiBody* multiBodyB = solverConstraint.m_multiBodyB;
|
||||
@@ -181,13 +189,13 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr
|
||||
}
|
||||
else if(rb1)
|
||||
{
|
||||
btVector3 torqueAxis1 = rel_pos2.cross(contactNormalOnB);
|
||||
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;
|
||||
@@ -233,7 +241,7 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr
|
||||
vec = ( -solverConstraint.m_angularComponentB).cross(rel_pos2);
|
||||
denom1 = rb1->getInvMass() + contactNormalOnB.dot(vec);
|
||||
}
|
||||
|
||||
|
||||
//
|
||||
btScalar d = denom0+denom1;
|
||||
if (d>SIMD_EPSILON)
|
||||
@@ -244,10 +252,10 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr
|
||||
{
|
||||
//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;
|
||||
|
||||
@@ -260,7 +268,7 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr
|
||||
{
|
||||
ndofA = (multiBodyA->isMultiDof() ? multiBodyA->getNumDofs() : multiBodyA->getNumLinks()) + 6;
|
||||
btScalar* jacA = &data.m_jacobians[solverConstraint.m_jacAindex];
|
||||
for (int i = 0; i < ndofA ; ++i)
|
||||
for (int i = 0; i < ndofA ; ++i)
|
||||
rel_vel += multiBodyA->getVelocityVector()[i] * jacA[i];
|
||||
}
|
||||
else if(rb0)
|
||||
@@ -271,7 +279,7 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr
|
||||
{
|
||||
ndofB = (multiBodyB->isMultiDof() ? multiBodyB->getNumDofs() : multiBodyB->getNumLinks()) + 6;
|
||||
btScalar* jacB = &data.m_jacobians[solverConstraint.m_jacBindex];
|
||||
for (int i = 0; i < ndofB ; ++i)
|
||||
for (int i = 0; i < ndofB ; ++i)
|
||||
rel_vel += multiBodyB->getVelocityVector()[i] * jacB[i];
|
||||
|
||||
}
|
||||
@@ -321,11 +329,11 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr
|
||||
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))
|
||||
|
||||
@@ -4,8 +4,8 @@ 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,
|
||||
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.
|
||||
@@ -54,7 +54,7 @@ protected:
|
||||
int m_posOffset;
|
||||
|
||||
bool m_isUnilateral;
|
||||
|
||||
int m_numDofsFinalized;
|
||||
btScalar m_maxAppliedImpulse;
|
||||
|
||||
|
||||
@@ -66,11 +66,11 @@ protected:
|
||||
|
||||
void applyDeltaVee(btMultiBodyJacobianData& data, btScalar* delta_vee, btScalar impulse, int velocityIndex, int ndof);
|
||||
|
||||
btScalar fillMultiBodyConstraint(btMultiBodySolverConstraint& solverConstraint,
|
||||
btScalar fillMultiBodyConstraint(btMultiBodySolverConstraint& solverConstraint,
|
||||
btMultiBodyJacobianData& data,
|
||||
btScalar* jacOrgA, btScalar* jacOrgB,
|
||||
const btVector3& contactNormalOnB,
|
||||
const btVector3& posAworld, const btVector3& posBworld,
|
||||
const btVector3& posAworld, const btVector3& posBworld,
|
||||
btScalar posError,
|
||||
const btContactSolverInfo& infoGlobal,
|
||||
btScalar lowerLimit, btScalar upperLimit,
|
||||
@@ -82,11 +82,14 @@ public:
|
||||
btMultiBodyConstraint(btMultiBody* bodyA,btMultiBody* bodyB,int linkA, int linkB, int numRows, bool isUnilateral);
|
||||
virtual ~btMultiBodyConstraint();
|
||||
|
||||
void finalizeMultiDof();
|
||||
void updateJacobianSizes();
|
||||
void allocateJacobiansMultiDof();
|
||||
|
||||
virtual void finalizeMultiDof()=0;
|
||||
|
||||
virtual int getIslandIdA() const =0;
|
||||
virtual int getIslandIdB() const =0;
|
||||
|
||||
|
||||
virtual void createConstraintRows(btMultiBodyConstraintArray& constraintRows,
|
||||
btMultiBodyJacobianData& data,
|
||||
const btContactSolverInfo& infoGlobal)=0;
|
||||
@@ -108,17 +111,17 @@ public:
|
||||
// current constraint position
|
||||
// constraint is pos >= 0 for unilateral, or pos = 0 for bilateral
|
||||
// NOTE: ignored position for friction rows.
|
||||
btScalar getPosition(int row) const
|
||||
{
|
||||
return m_data[m_posOffset + row];
|
||||
btScalar getPosition(int row) const
|
||||
{
|
||||
return m_data[m_posOffset + row];
|
||||
}
|
||||
|
||||
void setPosition(int row, btScalar pos)
|
||||
{
|
||||
m_data[m_posOffset + row] = pos;
|
||||
void setPosition(int row, btScalar pos)
|
||||
{
|
||||
m_data[m_posOffset + row] = pos;
|
||||
}
|
||||
|
||||
|
||||
|
||||
bool isUnilateral() const
|
||||
{
|
||||
return m_isUnilateral;
|
||||
@@ -127,21 +130,21 @@ public:
|
||||
// jacobian blocks.
|
||||
// each of size 6 + num_links. (jacobian2 is null if no body2.)
|
||||
// format: 3 'omega' coefficients, 3 'v' coefficients, then the 'qdot' coefficients.
|
||||
btScalar* jacobianA(int row)
|
||||
{
|
||||
return &m_data[m_numRows + row * m_jacSizeBoth];
|
||||
btScalar* jacobianA(int row)
|
||||
{
|
||||
return &m_data[m_numRows + row * m_jacSizeBoth];
|
||||
}
|
||||
const btScalar* jacobianA(int row) const
|
||||
{
|
||||
return &m_data[m_numRows + (row * m_jacSizeBoth)];
|
||||
const btScalar* jacobianA(int row) const
|
||||
{
|
||||
return &m_data[m_numRows + (row * m_jacSizeBoth)];
|
||||
}
|
||||
btScalar* jacobianB(int row)
|
||||
{
|
||||
return &m_data[m_numRows + (row * m_jacSizeBoth) + m_jacSizeA];
|
||||
btScalar* jacobianB(int row)
|
||||
{
|
||||
return &m_data[m_numRows + (row * m_jacSizeBoth) + m_jacSizeA];
|
||||
}
|
||||
const btScalar* jacobianB(int row) const
|
||||
{
|
||||
return &m_data[m_numRows + (row * m_jacSizeBoth) + m_jacSizeA];
|
||||
const btScalar* jacobianB(int row) const
|
||||
{
|
||||
return &m_data[m_numRows + (row * m_jacSizeBoth) + m_jacSizeA];
|
||||
}
|
||||
|
||||
btScalar getMaxAppliedImpulse() const
|
||||
@@ -152,7 +155,7 @@ public:
|
||||
{
|
||||
m_maxAppliedImpulse = maxImp;
|
||||
}
|
||||
|
||||
|
||||
virtual void debugDraw(class btIDebugDraw* drawer)=0;
|
||||
|
||||
};
|
||||
|
||||
@@ -4,8 +4,8 @@ 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,
|
||||
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.
|
||||
@@ -38,11 +38,11 @@ protected:
|
||||
virtual void calculateSimulationIslands();
|
||||
virtual void updateActivationState(btScalar timeStep);
|
||||
virtual void solveConstraints(btContactSolverInfo& solverInfo);
|
||||
|
||||
|
||||
public:
|
||||
|
||||
btMultiBodyDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btMultiBodyConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration);
|
||||
|
||||
|
||||
virtual ~btMultiBodyDynamicsWorld ();
|
||||
|
||||
virtual void addMultiBody(btMultiBody* body, short group= btBroadphaseProxy::DefaultFilter, short mask=btBroadphaseProxy::AllFilter);
|
||||
@@ -51,12 +51,27 @@ public:
|
||||
|
||||
virtual void addMultiBodyConstraint( btMultiBodyConstraint* constraint);
|
||||
|
||||
virtual int getNumMultiBodyConstraints() const
|
||||
{
|
||||
return m_multiBodyConstraints.size();
|
||||
}
|
||||
|
||||
virtual btMultiBodyConstraint* getMultiBodyConstraint( int constraintIndex)
|
||||
{
|
||||
return m_multiBodyConstraints[constraintIndex];
|
||||
}
|
||||
|
||||
virtual const btMultiBodyConstraint* getMultiBodyConstraint( int constraintIndex) const
|
||||
{
|
||||
return m_multiBodyConstraints[constraintIndex];
|
||||
}
|
||||
|
||||
virtual void removeMultiBodyConstraint( btMultiBodyConstraint* constraint);
|
||||
|
||||
virtual void integrateTransforms(btScalar timeStep);
|
||||
|
||||
virtual void debugDrawWorld();
|
||||
|
||||
|
||||
virtual void debugDrawMultiBodyConstraint(btMultiBodyConstraint* constraint);
|
||||
};
|
||||
#endif //BT_MULTIBODY_DYNAMICS_WORLD_H
|
||||
|
||||
@@ -4,8 +4,8 @@ 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,
|
||||
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.
|
||||
@@ -26,14 +26,18 @@ btMultiBodyJointLimitConstraint::btMultiBodyJointLimitConstraint(btMultiBody* bo
|
||||
:btMultiBodyConstraint(body,body,link,link,2,true),
|
||||
m_lowerBound(lower),
|
||||
m_upperBound(upper)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void btMultiBodyJointLimitConstraint::finalizeMultiDof()
|
||||
{
|
||||
// the data.m_jacobians never change, so may as well
|
||||
// initialize them here
|
||||
|
||||
// note: we rely on the fact that data.m_jacobians are
|
||||
// always initialized to zero by the Constraint ctor
|
||||
|
||||
unsigned int offset = 6 + (body->isMultiDof() ? body->getLink(link).m_dofOffset : link);
|
||||
allocateJacobiansMultiDof();
|
||||
|
||||
unsigned int offset = 6 + (m_bodyA->isMultiDof() ? m_bodyA->getLink(m_linkA).m_dofOffset : m_linkA);
|
||||
|
||||
// row 0: the lower bound
|
||||
jacobianA(0)[offset] = 1;
|
||||
@@ -41,7 +45,10 @@ btMultiBodyJointLimitConstraint::btMultiBodyJointLimitConstraint(btMultiBody* bo
|
||||
//jacobianA(1)[offset] = -1;
|
||||
|
||||
jacobianB(1)[offset] = -1;
|
||||
|
||||
m_numDofsFinalized = m_jacSizeBoth;
|
||||
}
|
||||
|
||||
btMultiBodyJointLimitConstraint::~btMultiBodyJointLimitConstraint()
|
||||
{
|
||||
}
|
||||
@@ -87,7 +94,13 @@ void btMultiBodyJointLimitConstraint::createConstraintRows(btMultiBodyConstraint
|
||||
{
|
||||
// only positions need to be updated -- data.m_jacobians and force
|
||||
// directions were set in the ctor and never change.
|
||||
|
||||
|
||||
if (m_numDofsFinalized != m_jacSizeBoth)
|
||||
{
|
||||
finalizeMultiDof();
|
||||
}
|
||||
|
||||
|
||||
// row 0: the lower bound
|
||||
setPosition(0, m_bodyA->getJointPos(m_linkA) - m_lowerBound); //multidof: this is joint-type dependent
|
||||
|
||||
@@ -101,7 +114,7 @@ void btMultiBodyJointLimitConstraint::createConstraintRows(btMultiBodyConstraint
|
||||
constraintRow.m_multiBodyB = m_bodyB;
|
||||
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 penetration = getPosition(row);
|
||||
@@ -139,7 +152,7 @@ void btMultiBodyJointLimitConstraint::createConstraintRows(btMultiBodyConstraint
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -4,8 +4,8 @@ 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,
|
||||
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.
|
||||
@@ -30,6 +30,8 @@ public:
|
||||
btMultiBodyJointLimitConstraint(btMultiBody* body, int link, btScalar lower, btScalar upper);
|
||||
virtual ~btMultiBodyJointLimitConstraint();
|
||||
|
||||
virtual void finalizeMultiDof();
|
||||
|
||||
virtual int getIslandIdA() const;
|
||||
virtual int getIslandIdB() const;
|
||||
|
||||
@@ -41,7 +43,7 @@ public:
|
||||
{
|
||||
//todo(erwincoumans)
|
||||
}
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_MULTIBODY_JOINT_LIMIT_CONSTRAINT_H
|
||||
|
||||
@@ -4,8 +4,8 @@ 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,
|
||||
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.
|
||||
@@ -23,44 +23,41 @@ subject to the following restrictions:
|
||||
|
||||
btMultiBodyJointMotor::btMultiBodyJointMotor(btMultiBody* body, int link, btScalar desiredVelocity, btScalar maxMotorImpulse)
|
||||
:btMultiBodyConstraint(body,body,link,link,1,true),
|
||||
m_desiredVelocity(desiredVelocity)
|
||||
m_desiredVelocity(desiredVelocity)
|
||||
{
|
||||
int linkDoF = 0;
|
||||
|
||||
|
||||
m_maxAppliedImpulse = maxMotorImpulse;
|
||||
// the data.m_jacobians never change, so may as well
|
||||
// initialize them here
|
||||
|
||||
// note: we rely on the fact that data.m_jacobians are
|
||||
// always initialized to zero by the Constraint ctor
|
||||
|
||||
unsigned int offset = 6 + (body->isMultiDof() ? body->getLink(link).m_dofOffset + linkDoF : link);
|
||||
|
||||
// row 0: the lower bound
|
||||
// row 0: the lower bound
|
||||
jacobianA(0)[offset] = 1;
|
||||
}
|
||||
|
||||
void btMultiBodyJointMotor::finalizeMultiDof()
|
||||
{
|
||||
allocateJacobiansMultiDof();
|
||||
// note: we rely on the fact that data.m_jacobians are
|
||||
// always initialized to zero by the Constraint ctor
|
||||
int linkDoF = 0;
|
||||
unsigned int offset = 6 + (m_bodyA->isMultiDof() ? m_bodyA->getLink(m_linkA).m_dofOffset + linkDoF : m_linkA);
|
||||
|
||||
// row 0: the lower bound
|
||||
// row 0: the lower bound
|
||||
jacobianA(0)[offset] = 1;
|
||||
|
||||
m_numDofsFinalized = m_jacSizeBoth;
|
||||
}
|
||||
|
||||
btMultiBodyJointMotor::btMultiBodyJointMotor(btMultiBody* body, int link, int linkDoF, btScalar desiredVelocity, btScalar maxMotorImpulse)
|
||||
//:btMultiBodyConstraint(body,0,link,-1,1,true),
|
||||
:btMultiBodyConstraint(body,body,link,link,1,true),
|
||||
m_desiredVelocity(desiredVelocity)
|
||||
m_desiredVelocity(desiredVelocity)
|
||||
{
|
||||
btAssert(linkDoF < body->getLink(link).m_dofCount);
|
||||
|
||||
m_maxAppliedImpulse = maxMotorImpulse;
|
||||
// the data.m_jacobians never change, so may as well
|
||||
// initialize them here
|
||||
|
||||
// note: we rely on the fact that data.m_jacobians are
|
||||
// always initialized to zero by the Constraint ctor
|
||||
|
||||
unsigned int offset = 6 + (body->isMultiDof() ? body->getLink(link).m_dofOffset + linkDoF : link);
|
||||
|
||||
// row 0: the lower bound
|
||||
// row 0: the lower bound
|
||||
jacobianA(0)[offset] = 1;
|
||||
}
|
||||
btMultiBodyJointMotor::~btMultiBodyJointMotor()
|
||||
{
|
||||
@@ -101,18 +98,26 @@ void btMultiBodyJointMotor::createConstraintRows(btMultiBodyConstraintArray& con
|
||||
{
|
||||
// only positions need to be updated -- data.m_jacobians and force
|
||||
// directions were set in the ctor and never change.
|
||||
|
||||
|
||||
|
||||
if (m_numDofsFinalized != m_jacSizeBoth)
|
||||
{
|
||||
finalizeMultiDof();
|
||||
}
|
||||
|
||||
//don't crash
|
||||
if (m_numDofsFinalized != m_jacSizeBoth)
|
||||
return;
|
||||
|
||||
const btScalar posError = 0;
|
||||
const btVector3 dummy(0, 0, 0);
|
||||
|
||||
for (int row=0;row<getNumRows();row++)
|
||||
{
|
||||
btMultiBodySolverConstraint& constraintRow = constraintRows.expandNonInitializing();
|
||||
|
||||
|
||||
|
||||
|
||||
fillMultiBodyConstraint(constraintRow,data,jacobianA(row),jacobianB(row),dummy,dummy,dummy,posError,infoGlobal,-m_maxAppliedImpulse,m_maxAppliedImpulse,1,false,m_desiredVelocity);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -4,8 +4,8 @@ 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,
|
||||
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.
|
||||
@@ -25,7 +25,7 @@ class btMultiBodyJointMotor : public btMultiBodyConstraint
|
||||
{
|
||||
protected:
|
||||
|
||||
|
||||
|
||||
btScalar m_desiredVelocity;
|
||||
|
||||
public:
|
||||
@@ -33,6 +33,7 @@ public:
|
||||
btMultiBodyJointMotor(btMultiBody* body, int link, btScalar desiredVelocity, btScalar maxMotorImpulse);
|
||||
btMultiBodyJointMotor(btMultiBody* body, int link, int linkDoF, btScalar desiredVelocity, btScalar maxMotorImpulse);
|
||||
virtual ~btMultiBodyJointMotor();
|
||||
virtual void finalizeMultiDof();
|
||||
|
||||
virtual int getIslandIdA() const;
|
||||
virtual int getIslandIdB() const;
|
||||
@@ -40,7 +41,7 @@ public:
|
||||
virtual void createConstraintRows(btMultiBodyConstraintArray& constraintRows,
|
||||
btMultiBodyJacobianData& data,
|
||||
const btContactSolverInfo& infoGlobal);
|
||||
|
||||
|
||||
virtual void setVelocityTarget(btScalar velTarget)
|
||||
{
|
||||
m_desiredVelocity = velTarget;
|
||||
|
||||
@@ -43,7 +43,12 @@ btMultiBodyPoint2Point::btMultiBodyPoint2Point(btMultiBody* bodyA, int linkA, bt
|
||||
m_pivotInB(pivotInB)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
void btMultiBodyPoint2Point::finalizeMultiDof()
|
||||
{
|
||||
//not implemented yet
|
||||
btAssert(0);
|
||||
}
|
||||
|
||||
btMultiBodyPoint2Point::~btMultiBodyPoint2Point()
|
||||
{
|
||||
|
||||
@@ -4,8 +4,8 @@ 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,
|
||||
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.
|
||||
@@ -30,7 +30,7 @@ protected:
|
||||
btRigidBody* m_rigidBodyB;
|
||||
btVector3 m_pivotInA;
|
||||
btVector3 m_pivotInB;
|
||||
|
||||
|
||||
|
||||
public:
|
||||
|
||||
@@ -39,6 +39,8 @@ public:
|
||||
|
||||
virtual ~btMultiBodyPoint2Point();
|
||||
|
||||
virtual void finalizeMultiDof();
|
||||
|
||||
virtual int getIslandIdA() const;
|
||||
virtual int getIslandIdB() const;
|
||||
|
||||
@@ -57,7 +59,7 @@ public:
|
||||
}
|
||||
|
||||
virtual void debugDraw(class btIDebugDraw* drawer);
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_MULTIBODY_POINT2POINT_H
|
||||
|
||||
Reference in New Issue
Block a user