more refactoring, removed PhysicsInterface, cleaned up demos to make use of btDynamicsWorld derived classes.
removed two cached optimizations, type in btTransform and cached inverse transform (todo: test performance impact) committed fixes that make the code adhere to 'who creates it, also destroys it'
This commit is contained in:
@@ -25,8 +25,7 @@ btCollisionObject::btCollisionObject()
|
||||
m_ccdSweptShereRadius(0.f),
|
||||
m_ccdSquareMotionTreshold(0.f)
|
||||
{
|
||||
m_cachedInvertedWorldTransform.setIdentity();
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -41,8 +41,6 @@ struct btCollisionObject
|
||||
//it can be either previous or future (predicted) transform
|
||||
btTransform m_interpolationWorldTransform;
|
||||
|
||||
btTransform m_cachedInvertedWorldTransform;
|
||||
|
||||
enum CollisionFlags
|
||||
{
|
||||
isStatic = 1,
|
||||
|
||||
@@ -123,7 +123,6 @@ void btCollisionWorld::performDiscreteCollisionDetection()
|
||||
btVector3 aabbMin,aabbMax;
|
||||
for (size_t i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
m_collisionObjects[i]->m_cachedInvertedWorldTransform = m_collisionObjects[i]->m_worldTransform.inverse();
|
||||
m_collisionObjects[i]->m_collisionShape->getAabb(m_collisionObjects[i]->m_worldTransform,aabbMin,aabbMax);
|
||||
m_broadphasePairCache->setAabb(m_collisionObjects[i]->m_broadphaseHandle,aabbMin,aabbMax);
|
||||
}
|
||||
|
||||
@@ -133,7 +133,7 @@ public:
|
||||
|
||||
struct LocalRayResult
|
||||
{
|
||||
LocalRayResult(const btCollisionObject* collisionObject,
|
||||
LocalRayResult(btCollisionObject* collisionObject,
|
||||
LocalShapeInfo* localShapeInfo,
|
||||
const btVector3& hitNormalLocal,
|
||||
float hitFraction)
|
||||
@@ -144,7 +144,7 @@ public:
|
||||
{
|
||||
}
|
||||
|
||||
const btCollisionObject* m_collisionObject;
|
||||
btCollisionObject* m_collisionObject;
|
||||
LocalShapeInfo* m_localShapeInfo;
|
||||
const btVector3& m_hitNormalLocal;
|
||||
float m_hitFraction;
|
||||
@@ -167,7 +167,7 @@ public:
|
||||
:m_closestHitFraction(1.f)
|
||||
{
|
||||
}
|
||||
virtual float AddSingleResult(const LocalRayResult& rayResult) = 0;
|
||||
virtual float AddSingleResult(LocalRayResult& rayResult) = 0;
|
||||
};
|
||||
|
||||
struct ClosestRayResultCallback : public RayResultCallback
|
||||
@@ -184,9 +184,9 @@ public:
|
||||
|
||||
btVector3 m_hitNormalWorld;
|
||||
btVector3 m_hitPointWorld;
|
||||
const btCollisionObject* m_collisionObject;
|
||||
btCollisionObject* m_collisionObject;
|
||||
|
||||
virtual float AddSingleResult(const LocalRayResult& rayResult)
|
||||
virtual float AddSingleResult(LocalRayResult& rayResult)
|
||||
{
|
||||
|
||||
//caller already does the filter on the m_closestHitFraction
|
||||
|
||||
@@ -217,8 +217,9 @@ float btConvexConcaveCollisionAlgorithm::calculateTimeOfImpact(btBroadphaseProxy
|
||||
//btVector3 to = convexbody->m_interpolationWorldTransform.getOrigin();
|
||||
//todo: only do if the motion exceeds the 'radius'
|
||||
|
||||
btTransform convexFromLocal = triBody->m_cachedInvertedWorldTransform * convexbody->m_worldTransform;
|
||||
btTransform convexToLocal = triBody->m_cachedInvertedWorldTransform * convexbody->m_interpolationWorldTransform;
|
||||
btTransform worldToLocalTrimesh = triBody->m_worldTransform.inverse();
|
||||
btTransform convexFromLocal = worldToLocalTrimesh * convexbody->m_worldTransform;
|
||||
btTransform convexToLocal = worldToLocalTrimesh * convexbody->m_interpolationWorldTransform;
|
||||
|
||||
struct LocalTriangleSphereCastCallback : public btTriangleCallback
|
||||
{
|
||||
|
||||
@@ -57,8 +57,8 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b
|
||||
return;
|
||||
|
||||
|
||||
btTransform transAInv = m_body0->m_cachedInvertedWorldTransform;
|
||||
btTransform transBInv= m_body1->m_cachedInvertedWorldTransform;
|
||||
btTransform transAInv = m_body0->m_worldTransform.inverse();
|
||||
btTransform transBInv= m_body1->m_worldTransform.inverse();
|
||||
|
||||
//transAInv = m_body0->m_worldTransform.inverse();
|
||||
//transBInv= m_body1->m_worldTransform.inverse();
|
||||
|
||||
@@ -148,14 +148,12 @@ btVector3 btConvexTriangleMeshShape::localGetSupportingVertex(const btVector3& v
|
||||
int btConvexTriangleMeshShape::getNumVertices() const
|
||||
{
|
||||
//cache this?
|
||||
assert(0);
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
int btConvexTriangleMeshShape::getNumEdges() const
|
||||
{
|
||||
assert(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
@@ -13,6 +13,9 @@ subject to the following restrictions:
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
|
||||
#ifndef BT_TRIANGLE_INDEX_VERTEX_ARRAY_H
|
||||
#define BT_TRIANGLE_INDEX_VERTEX_ARRAY_H
|
||||
|
||||
#include "btStridingMeshInterface.h"
|
||||
#include <vector>
|
||||
|
||||
@@ -76,3 +79,4 @@ public:
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_TRIANGLE_INDEX_VERTEX_ARRAY_H
|
||||
|
||||
@@ -16,6 +16,7 @@ subject to the following restrictions:
|
||||
|
||||
#include "btDiscreteDynamicsWorld.h"
|
||||
|
||||
|
||||
//collision detection
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btSimpleBroadphase.h"
|
||||
@@ -32,12 +33,14 @@ subject to the following restrictions:
|
||||
#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
|
||||
#include "BulletDynamics/Vehicle/btVehicleRaycaster.h"
|
||||
#include "BulletDynamics/Vehicle/btWheelInfo.h"
|
||||
#include "LinearMath/btIDebugDraw.h"
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
btDiscreteDynamicsWorld::btDiscreteDynamicsWorld()
|
||||
:btDynamicsWorld(),
|
||||
m_constraintSolver(new btSequentialImpulseConstraintSolver)
|
||||
m_constraintSolver(new btSequentialImpulseConstraintSolver),
|
||||
m_debugDrawer(0)
|
||||
{
|
||||
m_islandManager = new btSimulationIslandManager();
|
||||
m_ownsIslandManager = true;
|
||||
@@ -47,11 +50,12 @@ m_constraintSolver(new btSequentialImpulseConstraintSolver)
|
||||
|
||||
btDiscreteDynamicsWorld::btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver)
|
||||
:btDynamicsWorld(dispatcher,pairCache),
|
||||
m_constraintSolver(constraintSolver)
|
||||
m_constraintSolver(constraintSolver? constraintSolver: new btSequentialImpulseConstraintSolver),
|
||||
m_debugDrawer(0)
|
||||
{
|
||||
m_islandManager = new btSimulationIslandManager();
|
||||
m_ownsIslandManager = true;
|
||||
m_ownsConstraintSolver = false;
|
||||
m_ownsConstraintSolver = (constraintSolver==0);
|
||||
}
|
||||
|
||||
|
||||
@@ -114,10 +118,9 @@ void btDiscreteDynamicsWorld::updateActivationState(float timeStep)
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
|
||||
body->updateDeactivation(timeStep);
|
||||
|
||||
if (body->wantsSleeping())
|
||||
@@ -190,8 +193,8 @@ void btDiscreteDynamicsWorld::solveContactConstraints(btContactSolverInfo& solve
|
||||
|
||||
};
|
||||
|
||||
btIDebugDraw* debugDraw = 0;
|
||||
InplaceSolverIslandCallback solverCallback( solverInfo, m_constraintSolver, debugDraw);
|
||||
|
||||
InplaceSolverIslandCallback solverCallback( solverInfo, m_constraintSolver, m_debugDrawer);
|
||||
|
||||
|
||||
/// solve all the contact points and contact friction
|
||||
@@ -277,23 +280,60 @@ void btDiscreteDynamicsWorld::calculateSimulationIslands()
|
||||
Profiler::endBlock("IslandUnionFind");
|
||||
#endif //USE_QUICKPROF
|
||||
|
||||
}
|
||||
|
||||
static void DrawAabb(btIDebugDraw* debugDrawer,const btVector3& from,const btVector3& to,const btVector3& color)
|
||||
{
|
||||
btVector3 halfExtents = (to-from)* 0.5f;
|
||||
btVector3 center = (to+from) *0.5f;
|
||||
int i,j;
|
||||
|
||||
btVector3 edgecoord(1.f,1.f,1.f),pa,pb;
|
||||
for (i=0;i<4;i++)
|
||||
{
|
||||
for (j=0;j<3;j++)
|
||||
{
|
||||
pa = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
|
||||
edgecoord[2]*halfExtents[2]);
|
||||
pa+=center;
|
||||
|
||||
int othercoord = j%3;
|
||||
edgecoord[othercoord]*=-1.f;
|
||||
pb = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
|
||||
edgecoord[2]*halfExtents[2]);
|
||||
pb+=center;
|
||||
|
||||
debugDrawer->drawLine(pa,pb,color);
|
||||
}
|
||||
edgecoord = btVector3(-1.f,-1.f,-1.f);
|
||||
if (i<3)
|
||||
edgecoord[i]*=-1.f;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
void btDiscreteDynamicsWorld::updateAabbs()
|
||||
{
|
||||
btVector3 colorvec(1,0,0);
|
||||
btTransform predictedTrans;
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
// if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
btPoint3 minAabb,maxAabb;
|
||||
colObj->m_collisionShape->getAabb(colObj->m_worldTransform, minAabb,maxAabb);
|
||||
btSimpleBroadphase* bp = (btSimpleBroadphase*)m_broadphasePairCache;
|
||||
bp->setAabb(body->m_broadphaseHandle,minAabb,maxAabb);
|
||||
if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawAabb))
|
||||
{
|
||||
DrawAabb(m_debugDrawer,minAabb,maxAabb,colorvec);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -305,9 +345,9 @@ void btDiscreteDynamicsWorld::integrateTransforms(float timeStep)
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
body->predictIntegratedTransform(timeStep, predictedTrans);
|
||||
@@ -324,10 +364,9 @@ void btDiscreteDynamicsWorld::predictUnconstraintMotion(float timeStep)
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
body->m_cachedInvertedWorldTransform = body->m_worldTransform.inverse();
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
body->applyForces( timeStep);
|
||||
|
||||
@@ -25,6 +25,7 @@ class btSimulationIslandManager;
|
||||
class btTypedConstraint;
|
||||
struct btContactSolverInfo;
|
||||
class btRaycastVehicle;
|
||||
class btIDebugDraw;
|
||||
|
||||
#include <vector>
|
||||
|
||||
@@ -40,6 +41,8 @@ protected:
|
||||
|
||||
std::vector<btTypedConstraint*> m_constraints;
|
||||
|
||||
btIDebugDraw* m_debugDrawer;
|
||||
|
||||
bool m_ownsIslandManager;
|
||||
bool m_ownsConstraintSolver;
|
||||
|
||||
@@ -49,8 +52,6 @@ protected:
|
||||
|
||||
void integrateTransforms(float timeStep);
|
||||
|
||||
void updateAabbs();
|
||||
|
||||
void calculateSimulationIslands();
|
||||
|
||||
void solveNoncontactConstraints(btContactSolverInfo& solverInfo);
|
||||
@@ -65,7 +66,7 @@ public:
|
||||
|
||||
|
||||
///this btDiscreteDynamicsWorld constructor gets created objects from the user, and will not delete those
|
||||
btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver);
|
||||
btDiscreteDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver=0);
|
||||
|
||||
///this btDiscreteDynamicsWorld will create and own dispatcher, pairCache and constraintSolver, and deletes it in the destructor.
|
||||
btDiscreteDynamicsWorld();
|
||||
@@ -74,6 +75,8 @@ public:
|
||||
|
||||
virtual void stepSimulation( float timeStep);
|
||||
|
||||
virtual void updateAabbs();
|
||||
|
||||
void addConstraint(btTypedConstraint* constraint);
|
||||
|
||||
void removeConstraint(btTypedConstraint* constraint);
|
||||
@@ -97,6 +100,16 @@ public:
|
||||
return this;
|
||||
}
|
||||
|
||||
virtual void setDebugDrawer(btIDebugDraw* debugDrawer)
|
||||
{
|
||||
m_debugDrawer = debugDrawer;
|
||||
}
|
||||
|
||||
virtual btIDebugDraw* getDebugDrawer()
|
||||
{
|
||||
return m_debugDrawer;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_DISCRETE_DYNAMICS_WORLD_H
|
||||
|
||||
@@ -40,11 +40,16 @@ class btDynamicsWorld : public btCollisionWorld
|
||||
///stepSimulation proceeds the simulation over timeStep units
|
||||
virtual void stepSimulation( float timeStep) = 0;
|
||||
|
||||
virtual void updateAabbs() = 0;
|
||||
|
||||
virtual void addConstraint(btTypedConstraint* constraint) {};
|
||||
|
||||
virtual void removeConstraint(btTypedConstraint* constraint) {};
|
||||
|
||||
|
||||
virtual void setDebugDrawer(btIDebugDraw* debugDrawer) = 0;
|
||||
|
||||
virtual btIDebugDraw* getDebugDrawer() = 0;
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_DYNAMICS_WORLD_H
|
||||
|
||||
@@ -48,6 +48,9 @@ btRigidBody::btRigidBody( const btMassProps& massProps,btScalar linearDamping,bt
|
||||
|
||||
m_debugBodyId = uniqueId++;
|
||||
|
||||
//m_internalOwner is to allow upcasting from collision object to rigid body
|
||||
m_internalOwner = this;
|
||||
|
||||
setMassProps(massProps.m_mass, massProps.m_inertiaLocal);
|
||||
setDamping(linearDamping, angularDamping);
|
||||
m_worldTransform.setIdentity();
|
||||
|
||||
@@ -65,6 +65,16 @@ public:
|
||||
|
||||
void proceedToTransform(const btTransform& newTrans);
|
||||
|
||||
///to keep collision detection and dynamics separate we don't store a rigidbody pointer
|
||||
///but a rigidbody is derived from btCollisionObject, so we can safely perform an upcast
|
||||
static const btRigidBody* upcast(const btCollisionObject* colObj)
|
||||
{
|
||||
return (const btRigidBody*)colObj->m_internalOwner;
|
||||
}
|
||||
static btRigidBody* upcast(btCollisionObject* colObj)
|
||||
{
|
||||
return (btRigidBody*)colObj->m_internalOwner;
|
||||
}
|
||||
|
||||
/// continuous collision detection needs prediction
|
||||
void predictIntegratedTransform(btScalar step, btTransform& predictedTransform) const;
|
||||
|
||||
@@ -24,14 +24,16 @@ subject to the following restrictions:
|
||||
|
||||
btSimpleDynamicsWorld::btSimpleDynamicsWorld()
|
||||
:m_constraintSolver(new btSequentialImpulseConstraintSolver),
|
||||
m_ownsConstraintSolver(true)
|
||||
m_ownsConstraintSolver(true),
|
||||
m_debugDrawer(0)
|
||||
{
|
||||
}
|
||||
|
||||
btSimpleDynamicsWorld::btSimpleDynamicsWorld(btDispatcher* dispatcher,btOverlappingPairCache* pairCache,btConstraintSolver* constraintSolver)
|
||||
:btDynamicsWorld(dispatcher,pairCache),
|
||||
m_constraintSolver(constraintSolver),
|
||||
m_ownsConstraintSolver(false)
|
||||
m_ownsConstraintSolver(false),
|
||||
m_debugDrawer(0)
|
||||
{
|
||||
|
||||
}
|
||||
@@ -56,8 +58,8 @@ void btSimpleDynamicsWorld::stepSimulation(float timeStep)
|
||||
int numManifolds = m_dispatcher1->getNumManifolds();
|
||||
btContactSolverInfo infoGlobal;
|
||||
infoGlobal.m_timeStep = timeStep;
|
||||
btIDebugDraw* debugDrawer=0;
|
||||
m_constraintSolver->solveGroup(manifoldPtr, numManifolds,infoGlobal,debugDrawer);
|
||||
|
||||
m_constraintSolver->solveGroup(manifoldPtr, numManifolds,infoGlobal,m_debugDrawer);
|
||||
|
||||
///integrate transforms
|
||||
integrateTransforms(timeStep);
|
||||
@@ -74,9 +76,9 @@ void btSimpleDynamicsWorld::updateAabbs()
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
btPoint3 minAabb,maxAabb;
|
||||
@@ -94,9 +96,9 @@ void btSimpleDynamicsWorld::integrateTransforms(float timeStep)
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
body->predictIntegratedTransform(timeStep, predictedTrans);
|
||||
@@ -113,10 +115,9 @@ void btSimpleDynamicsWorld::predictUnconstraintMotion(float timeStep)
|
||||
for (int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
if (colObj->m_internalOwner)
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
{
|
||||
btRigidBody* body = (btRigidBody*)colObj->m_internalOwner;
|
||||
body->m_cachedInvertedWorldTransform = body->m_worldTransform.inverse();
|
||||
if (body->IsActive() && (!body->IsStatic()))
|
||||
{
|
||||
body->applyForces( timeStep);
|
||||
|
||||
@@ -35,12 +35,13 @@ protected:
|
||||
|
||||
bool m_ownsConstraintSolver;
|
||||
|
||||
btIDebugDraw* m_debugDrawer;
|
||||
|
||||
void predictUnconstraintMotion(float timeStep);
|
||||
|
||||
void integrateTransforms(float timeStep);
|
||||
|
||||
void updateAabbs();
|
||||
|
||||
|
||||
public:
|
||||
|
||||
|
||||
@@ -54,6 +55,17 @@ public:
|
||||
|
||||
virtual void stepSimulation( float timeStep);
|
||||
|
||||
virtual void setDebugDrawer(btIDebugDraw* debugDrawer)
|
||||
{
|
||||
m_debugDrawer = debugDrawer;
|
||||
};
|
||||
|
||||
virtual btIDebugDraw* getDebugDrawer()
|
||||
{
|
||||
return m_debugDrawer;
|
||||
}
|
||||
|
||||
virtual void updateAabbs();
|
||||
};
|
||||
|
||||
#endif //BT_SIMPLE_DYNAMICS_WORLD_H
|
||||
|
||||
@@ -41,37 +41,26 @@ public:
|
||||
explicit SIMD_FORCE_INLINE btTransform(const btQuaternion& q,
|
||||
const btVector3& c = btVector3(btScalar(0), btScalar(0), btScalar(0)))
|
||||
: m_basis(q),
|
||||
m_origin(c),
|
||||
m_type(RIGID)
|
||||
m_origin(c)
|
||||
{}
|
||||
|
||||
explicit SIMD_FORCE_INLINE btTransform(const btMatrix3x3& b,
|
||||
const btVector3& c = btVector3(btScalar(0), btScalar(0), btScalar(0)),
|
||||
unsigned int type = AFFINE)
|
||||
: m_basis(b),
|
||||
m_origin(c),
|
||||
m_type(type)
|
||||
m_origin(c)
|
||||
{}
|
||||
|
||||
|
||||
SIMD_FORCE_INLINE void mult(const btTransform& t1, const btTransform& t2) {
|
||||
m_basis = t1.m_basis * t2.m_basis;
|
||||
m_origin = t1(t2.m_origin);
|
||||
m_type = t1.m_type | t2.m_type;
|
||||
}
|
||||
|
||||
void multInverseLeft(const btTransform& t1, const btTransform& t2) {
|
||||
btVector3 v = t2.m_origin - t1.m_origin;
|
||||
if (t1.m_type & SCALING) {
|
||||
btMatrix3x3 inv = t1.m_basis.inverse();
|
||||
m_basis = inv * t2.m_basis;
|
||||
m_origin = inv * v;
|
||||
}
|
||||
else {
|
||||
m_basis = btMultTransposeLeft(t1.m_basis, t2.m_basis);
|
||||
m_origin = v * t1.m_basis;
|
||||
}
|
||||
m_type = t1.m_type | t2.m_type;
|
||||
m_basis = btMultTransposeLeft(t1.m_basis, t2.m_basis);
|
||||
m_origin = v * t1.m_basis;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE btVector3 operator()(const btVector3& x) const
|
||||
@@ -102,7 +91,6 @@ public:
|
||||
{
|
||||
m_basis.setValue(m);
|
||||
m_origin.setValue(&m[12]);
|
||||
m_type = AFFINE;
|
||||
}
|
||||
|
||||
|
||||
@@ -126,7 +114,6 @@ public:
|
||||
SIMD_FORCE_INLINE void setOrigin(const btVector3& origin)
|
||||
{
|
||||
m_origin = origin;
|
||||
m_type |= TRANSLATION;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE btVector3 invXform(const btVector3& inVec) const;
|
||||
@@ -136,50 +123,36 @@ public:
|
||||
SIMD_FORCE_INLINE void setBasis(const btMatrix3x3& basis)
|
||||
{
|
||||
m_basis = basis;
|
||||
m_type |= LINEAR;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void setRotation(const btQuaternion& q)
|
||||
{
|
||||
m_basis.setRotation(q);
|
||||
m_type = (m_type & ~LINEAR) | ROTATION;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE void scale(const btVector3& scaling)
|
||||
{
|
||||
m_basis = m_basis.scaled(scaling);
|
||||
m_type |= SCALING;
|
||||
}
|
||||
|
||||
void setIdentity()
|
||||
{
|
||||
m_basis.setIdentity();
|
||||
m_origin.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
|
||||
m_type = 0x0;
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE bool isIdentity() const { return m_type == 0x0; }
|
||||
|
||||
|
||||
btTransform& operator*=(const btTransform& t)
|
||||
{
|
||||
m_origin += m_basis * t.m_origin;
|
||||
m_basis *= t.m_basis;
|
||||
m_type |= t.m_type;
|
||||
return *this;
|
||||
}
|
||||
|
||||
btTransform inverse() const
|
||||
{
|
||||
if (m_type)
|
||||
{
|
||||
btMatrix3x3 inv = (m_type & SCALING) ?
|
||||
m_basis.inverse() :
|
||||
m_basis.transpose();
|
||||
|
||||
return btTransform(inv, inv * -m_origin, m_type);
|
||||
}
|
||||
|
||||
return *this;
|
||||
btMatrix3x3 inv = m_basis.transpose();
|
||||
return btTransform(inv, inv * -m_origin);
|
||||
}
|
||||
|
||||
btTransform inverseTimes(const btTransform& t) const;
|
||||
@@ -190,7 +163,6 @@ private:
|
||||
|
||||
btMatrix3x3 m_basis;
|
||||
btVector3 m_origin;
|
||||
unsigned int m_type;
|
||||
};
|
||||
|
||||
|
||||
@@ -205,25 +177,15 @@ SIMD_FORCE_INLINE btTransform
|
||||
btTransform::inverseTimes(const btTransform& t) const
|
||||
{
|
||||
btVector3 v = t.getOrigin() - m_origin;
|
||||
if (m_type & SCALING)
|
||||
{
|
||||
btMatrix3x3 inv = m_basis.inverse();
|
||||
return btTransform(inv * t.getBasis(), inv * v,
|
||||
m_type | t.m_type);
|
||||
}
|
||||
else
|
||||
{
|
||||
return btTransform(m_basis.transposeTimes(t.m_basis),
|
||||
v * m_basis, m_type | t.m_type);
|
||||
}
|
||||
v * m_basis);
|
||||
}
|
||||
|
||||
SIMD_FORCE_INLINE btTransform
|
||||
btTransform::operator*(const btTransform& t) const
|
||||
{
|
||||
return btTransform(m_basis * t.m_basis,
|
||||
(*this)(t.m_origin),
|
||||
m_type | t.m_type);
|
||||
(*this)(t.m_origin));
|
||||
}
|
||||
|
||||
|
||||
|
||||
@@ -24,6 +24,8 @@ subject to the following restrictions:
|
||||
#include "BulletDynamics/Dynamics/btRigidBody.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btHingeConstraint.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h"
|
||||
|
||||
#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h"
|
||||
///Vehicle simulation, with wheel contact simulated by raycasts
|
||||
#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
|
||||
|
||||
Reference in New Issue
Block a user