fix padding in btSolverConstraint, see Issue 650

fix some warnings
This commit is contained in:
erwin.coumans
2012-09-08 19:21:14 +00:00
parent 9065f59229
commit b69c6ac3f5
47 changed files with 127 additions and 118 deletions

View File

@@ -354,7 +354,7 @@ void b2CollidePolygons(btManifoldResult* manifold,
btVector3 v11 = vertices1[edge1];
btVector3 v12 = edge1 + 1 < count1 ? vertices1[edge1+1] : vertices1[0];
btVector3 dv = v12 - v11;
//btVector3 dv = v12 - v11;
btVector3 sideNormal = b2Mul(xf1.getBasis(), v12 - v11);
sideNormal.normalize();
btVector3 frontNormal = btCrossS(sideNormal, 1.0f);

View File

@@ -314,8 +314,8 @@ void btConvexConvexAlgorithm ::processCollision (const btCollisionObjectWrapper*
{
btCapsuleShape* capsuleA = (btCapsuleShape*) min0;
btCapsuleShape* capsuleB = (btCapsuleShape*) min1;
btVector3 localScalingA = capsuleA->getLocalScaling();
btVector3 localScalingB = capsuleB->getLocalScaling();
// btVector3 localScalingA = capsuleA->getLocalScaling();
// btVector3 localScalingB = capsuleB->getLocalScaling();
btScalar threshold = m_manifoldPtr->getContactBreakingThreshold();

View File

@@ -482,7 +482,7 @@ void btAdjustInternalEdgeContacts(btManifoldPoint& cp, const btCollisionObjectWr
tri_shape->getVertex(1,v1);
tri_shape->getVertex(2,v2);
btVector3 center = (v0+v1+v2)*btScalar(1./3.);
//btVector3 center = (v0+v1+v2)*btScalar(1./3.);
btVector3 red(1,0,0), green(0,1,0),blue(0,0,1),white(1,1,1),black(0,0,0);
btVector3 tri_normal;

View File

@@ -44,7 +44,7 @@ btVector3 btConvexPointCloudShape::localGetSupportingVertexWithoutMargin(const b
if( m_numPoints > 0 )
{
// Here we take advantage of dot(a*b, c) = dot( a, b*c) to do less work. Note this transformation is true mathematically, not numerically.
btVector3 scaled = vec * m_localScaling;
// btVector3 scaled = vec * m_localScaling;
int index = (int) vec.maxDot( &m_unscaledPoints[0], m_numPoints, maxDot); //FIXME: may violate encapsulation of m_unscaledPoints
return getScaledPoint(index);
}

View File

@@ -242,7 +242,7 @@ const char* btStridingMeshInterface::serialize(void* dataBuffer, btSerializer* s
int gfxindex;
// btVector3 triangle[3];
btVector3 meshScaling = getScaling();
// btVector3 meshScaling = getScaling();
///if the number of parts is big, the performance might drop due to the innerloop switch on indextype
for (part=0;part<graphicssubparts ;part++,memPtr++)

View File

@@ -44,9 +44,9 @@ class btManifoldPoint
public:
btManifoldPoint()
:m_userPersistentData(0),
m_appliedImpulse(0.f),
m_lateralFrictionInitialized(false),
m_appliedImpulseLateral1(0.f),
m_appliedImpulse(0.f),
m_appliedImpulseLateral1(0.f),
m_appliedImpulseLateral2(0.f),
m_contactMotion1(0.f),
m_contactMotion2(0.f),
@@ -66,9 +66,9 @@ class btManifoldPoint
m_combinedFriction(btScalar(0.)),
m_combinedRestitution(btScalar(0.)),
m_userPersistentData(0),
m_appliedImpulse(0.f),
m_lateralFrictionInitialized(false),
m_appliedImpulseLateral1(0.f),
m_appliedImpulse(0.f),
m_appliedImpulseLateral1(0.f),
m_appliedImpulseLateral2(0.f),
m_contactMotion1(0.f),
m_contactMotion2(0.f),

View File

@@ -400,9 +400,9 @@ void btPolyhedralContactClipping::clipHullAgainstHull(const btVector3& separatin
{
btVector3 separatingNormal = separatingNormal1.normalized();
const btVector3 c0 = transA * hullA.m_localCenter;
const btVector3 c1 = transB * hullB.m_localCenter;
const btVector3 DeltaC2 = c0 - c1;
// const btVector3 c0 = transA * hullA.m_localCenter;
// const btVector3 c1 = transB * hullB.m_localCenter;
//const btVector3 DeltaC2 = c0 - c1;
int closestFaceB=-1;

View File

@@ -506,7 +506,7 @@ void btConeTwistConstraint::solveConstraintObsolete(btSolverBody& bodyA,btSolver
m_accTwistLimitImpulse = btMax(m_accTwistLimitImpulse + impulseMag, btScalar(0.0) );
impulseMag = m_accTwistLimitImpulse - temp;
btVector3 impulse = m_twistAxis * impulseMag;
// btVector3 impulse = m_twistAxis * impulseMag;
bodyA.internalApplyImpulse(btVector3(0,0,0), m_rbA.getInvInertiaTensorWorld()*m_twistAxis,impulseMag);
bodyB.internalApplyImpulse(btVector3(0,0,0), m_rbB.getInvInertiaTensorWorld()*m_twistAxis,-impulseMag);
@@ -828,12 +828,11 @@ void btConeTwistConstraint::computeConeLimitInfo(const btQuaternion& qCone,
{
vSwingAxis = btVector3(qCone.x(), qCone.y(), qCone.z());
vSwingAxis.normalize();
if (fabs(vSwingAxis.x()) > SIMD_EPSILON)
{
// non-zero twist?! this should never happen.
int wtf = 0; wtf = wtf;
}
#if 0
// non-zero twist?! this should never happen.
btAssert(fabs(vSwingAxis.x()) <= SIMD_EPSILON));
#endif
// Compute limit for given swing. tricky:
// Given a swing axis, we're looking for the intersection with the bounding cone ellipse.
// (Since we're dealing with angles, this ellipse is embedded on the surface of a sphere.)
@@ -877,8 +876,10 @@ void btConeTwistConstraint::computeConeLimitInfo(const btQuaternion& qCone,
else if (swingAngle < 0)
{
// this should never happen!
int wtf = 0; wtf = wtf;
}
#if 0
btAssert(0);
#endif
}
}
btVector3 btConeTwistConstraint::GetPointForAngle(btScalar fAngleInRadians, btScalar fLength) const
@@ -929,7 +930,9 @@ void btConeTwistConstraint::computeTwistLimitInfo(const btQuaternion& qTwist,
if (twistAngle < 0)
{
// this should never happen
int wtf = 0; wtf = wtf;
#if 0
btAssert(0);
#endif
}
vTwistAxis = btVector3(qMinTwist.x(), qMinTwist.y(), qMinTwist.z());
@@ -976,10 +979,10 @@ void btConeTwistConstraint::setMotorTarget(const btQuaternion &q)
{
btTransform trACur = m_rbA.getCenterOfMassTransform();
btTransform trBCur = m_rbB.getCenterOfMassTransform();
btTransform trABCur = trBCur.inverse() * trACur;
btQuaternion qABCur = trABCur.getRotation();
btTransform trConstraintCur = (trBCur * m_rbBFrame).inverse() * (trACur * m_rbAFrame);
btQuaternion qConstraintCur = trConstraintCur.getRotation();
// btTransform trABCur = trBCur.inverse() * trACur;
// btQuaternion qABCur = trABCur.getRotation();
// btTransform trConstraintCur = (trBCur * m_rbBFrame).inverse() * (trACur * m_rbAFrame);
//btQuaternion qConstraintCur = trConstraintCur.getRotation();
btQuaternion qConstraint = m_rbBFrame.getRotation().inverse() * q * m_rbAFrame.getRotation();
setMotorTargetInConstraintSpace(qConstraint);

View File

@@ -144,6 +144,7 @@ public:
virtual void solveConstraintObsolete(btSolverBody& bodyA,btSolverBody& bodyB,btScalar timeStep);
void updateRHS(btScalar timeStep);

View File

@@ -118,7 +118,7 @@ void btGeneric6DofSpringConstraint::internalUpdateSprings(btConstraintInfo2* inf
{
// it is assumed that calculateTransforms() have been called before this call
int i;
btVector3 relVel = m_rbB.getLinearVelocity() - m_rbA.getLinearVelocity();
//btVector3 relVel = m_rbB.getLinearVelocity() - m_rbA.getLinearVelocity();
for(i = 0; i < 3; i++)
{
if(m_springEnabled[i])

View File

@@ -702,8 +702,8 @@ void btHingeConstraint::getInfo2InternalUsingFrameOffset(btConstraintInfo2* info
btTransform trA = transA*m_rbAFrame;
btTransform trB = transB*m_rbBFrame;
// pivot point
btVector3 pivotAInW = trA.getOrigin();
btVector3 pivotBInW = trB.getOrigin();
// btVector3 pivotAInW = trA.getOrigin();
// btVector3 pivotBInW = trB.getOrigin();
#if 1
// difference between frames in WCS
btVector3 ofs = trB.getOrigin() - trA.getOrigin();

View File

@@ -124,7 +124,7 @@ void btPoint2PointConstraint::getInfo2NonVirtual (btConstraintInfo2* info, const
btVector3 a2 = body1_trans.getBasis()*getPivotInB();
{
btVector3 a2n = -a2;
// btVector3 a2n = -a2;
btVector3* angular0 = (btVector3*)(info->m_J2angularAxis);
btVector3* angular1 = (btVector3*)(info->m_J2angularAxis+info->rowskip);
btVector3* angular2 = (btVector3*)(info->m_J2angularAxis+2*info->rowskip);

View File

@@ -677,8 +677,8 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
int solverBodyIdA = getOrInitSolverBody(*colObj0);
int solverBodyIdB = getOrInitSolverBody(*colObj1);
btRigidBody* bodyA = btRigidBody::upcast(colObj0);
btRigidBody* bodyB = btRigidBody::upcast(colObj1);
// btRigidBody* bodyA = btRigidBody::upcast(colObj0);
// btRigidBody* bodyB = btRigidBody::upcast(colObj1);
btSolverBody* solverBodyA = &m_tmpSolverBodyPool[solverBodyIdA];
btSolverBody* solverBodyB = &m_tmpSolverBodyPool[solverBodyIdB];
@@ -686,7 +686,7 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
///avoid collision response between two static objects
if (!solverBodyA || !solverBodyA->m_originalBody && (!solverBodyB || !solverBodyB->m_originalBody))
if (!solverBodyA || (!solverBodyA->m_originalBody && (!solverBodyB || !solverBodyB->m_originalBody)))
return;
for (int j=0;j<manifold->getNumContacts();j++)
@@ -704,8 +704,8 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
int frictionIndex = m_tmpSolverContactConstraintPool.size();
btSolverConstraint& solverConstraint = m_tmpSolverContactConstraintPool.expandNonInitializing();
btRigidBody* rb0 = btRigidBody::upcast(colObj0);
btRigidBody* rb1 = btRigidBody::upcast(colObj1);
// btRigidBody* rb0 = btRigidBody::upcast(colObj0);
// btRigidBody* rb1 = btRigidBody::upcast(colObj1);
solverConstraint.m_solverBodyIdA = solverBodyIdA;
solverConstraint.m_solverBodyIdB = solverBodyIdB;
@@ -908,7 +908,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
info2.m_J2angularAxis = currentConstraintRow->m_relpos2CrossNormal;
info2.rowskip = sizeof(btSolverConstraint)/sizeof(btScalar);//check this
///the size of btSolverConstraint needs be a multiple of btScalar
btAssert(info2.rowskip*sizeof(btScalar)== sizeof(btSolverConstraint));
btAssert(info2.rowskip*sizeof(btScalar)== sizeof(btSolverConstraint));
info2.m_constraintError = &currentConstraintRow->m_rhs;
currentConstraintRow->m_cfm = infoGlobal.m_globalCfm;
info2.m_damping = infoGlobal.m_damping;
@@ -997,7 +997,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
}
}
btContactSolverInfo info = infoGlobal;
// btContactSolverInfo info = infoGlobal;
int numNonContactPool = m_tmpSolverNonContactConstraintPool.size();

View File

@@ -275,7 +275,7 @@ ATTRIBUTE_ALIGNED64 (struct) btSolverBody
btTransform newTransform;
if (m_pushVelocity[0]!=0.f || m_pushVelocity[1]!=0 || m_pushVelocity[2]!=0 || m_turnVelocity[0]!=0.f || m_turnVelocity[1]!=0 || m_turnVelocity[2]!=0)
{
btQuaternion orn = m_worldTransform.getRotation();
// btQuaternion orn = m_worldTransform.getRotation();
btTransformUtil::integrateTransform(m_worldTransform,m_pushVelocity,m_turnVelocity*splitImpulseTurnErp,timeStep,newTransform);
m_worldTransform = newTransform;
}

View File

@@ -27,7 +27,7 @@ class btRigidBody;
///1D constraint along a normal axis between bodyA and bodyB. It can be combined to solve contact and friction constraints.
ATTRIBUTE_ALIGNED64 (struct) btSolverConstraint
ATTRIBUTE_ALIGNED16 (struct) btSolverConstraint
{
BT_DECLARE_ALIGNED_ALLOCATOR();
@@ -42,41 +42,27 @@ ATTRIBUTE_ALIGNED64 (struct) btSolverConstraint
mutable btSimdScalar m_appliedPushImpulse;
mutable btSimdScalar m_appliedImpulse;
btScalar m_friction;
btScalar m_jacDiagABInv;
union
{
int m_numConsecutiveRowsPerKernel;
btScalar m_unusedPadding0;
};
int m_overrideNumSolverIterations;
union
{
int m_frictionIndex;
btScalar m_unusedPadding1;
};
btScalar m_rhs;
btScalar m_cfm;
int m_solverBodyIdA;
int m_solverBodyIdB;
union
btScalar m_lowerLimit;
btScalar m_upperLimit;
btScalar m_rhsPenetration;
union
{
void* m_originalContactPoint;
btScalar m_unusedPadding4;
};
btScalar m_rhs;
btScalar m_cfm;
btScalar m_lowerLimit;
btScalar m_upperLimit;
btScalar m_rhsPenetration;
int m_overrideNumSolverIterations;
int m_frictionIndex;
int m_solverBodyIdA;
int m_solverBodyIdB;
enum btSolverConstraintType
{
BT_SOLVER_CONTACT_1D = 0,

View File

@@ -203,13 +203,14 @@ struct InplaceSolverIslandCallback : public btSimulationIslandManager::IslandCal
btDiscreteDynamicsWorld::btDiscreteDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration)
:btDynamicsWorld(dispatcher,pairCache,collisionConfiguration),
m_sortedConstraints (),
m_solverIslandCallback ( NULL ),
m_constraintSolver(constraintSolver),
m_gravity(0,-10,0),
m_localTime(0),
m_synchronizeAllMotionStates(false),
m_profileTimings(0),
m_sortedConstraints (),
m_solverIslandCallback ( NULL )
m_profileTimings(0)
{
if (!m_constraintSolver)
{

View File

@@ -793,7 +793,7 @@ void btOpenCLSoftBodySolver::optimize( btAlignedObjectArray< btSoftBody * > &sof
int firstLink = getLinkData().getNumLinks();
int numLinks = softBody->m_links.size();
int maxLinks = numLinks;
// int maxLinks = numLinks;
// Allocate space for the links
getLinkData().createLinks( numLinks );

View File

@@ -460,8 +460,8 @@ void btSoftBody::addAeroForceToNode(const btVector3& windVelocity,int nodeInde
const btScalar dt = m_sst.sdt;
const btScalar kLF = m_cfg.kLF;
const btScalar kDG = m_cfg.kDG;
const btScalar kPR = m_cfg.kPR;
const btScalar kVC = m_cfg.kVC;
//const btScalar kPR = m_cfg.kPR;
//const btScalar kVC = m_cfg.kVC;
const bool as_lift = kLF>0;
const bool as_drag = kDG>0;
const bool as_aero = as_lift || as_drag;

View File

@@ -563,7 +563,7 @@ int HullLibrary::calchullgen(btVector3 *verts,int verts_count, int vlimit)
vlimit-=4;
while(vlimit >0 && ((te=extrudable(epsilon)) != 0))
{
int3 ti=*te;
//int3 ti=*te;
int v=te->vmax;
btAssert(v != -1);
btAssert(!isextreme[v]); // wtf we've already done this vertex