Welcome to mirror list, hosted at ThFree Co, Russian Federation.

git.blender.org/blender.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
path: root/extern
diff options
context:
space:
mode:
authorErwin Coumans <blender@erwincoumans.com>2009-03-09 07:21:28 +0300
committerErwin Coumans <blender@erwincoumans.com>2009-03-09 07:21:28 +0300
commitabb338ddf9dea9a26ca1092b3f7fda86b32bbd16 (patch)
tree215d6b18fccc2705c4b2566f0dba3b11433bc6d5 /extern
parente4ce0d629e021bcc1b910a1f49c251a17501cff6 (diff)
upgrade to latest Bullet trunk, fix related to vehicle anti-roll, added constraint visualization.
This commit doesn't add new functionality, but more updates are planned before Blender 2.49 release.
Diffstat (limited to 'extern')
-rw-r--r--extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp36
-rw-r--r--extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h5
-rw-r--r--extern/bullet2/src/BulletDynamics/ConstraintSolver/btSolverBody.h6
-rw-r--r--extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h1
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btActionInterface.h39
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btContinuousDynamicsWorld.cpp3
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp102
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h39
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h23
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp3
-rw-r--r--extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h36
-rw-r--r--extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp39
-rw-r--r--extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h43
-rw-r--r--extern/bullet2/src/LinearMath/btConvexHull.cpp8
14 files changed, 222 insertions, 161 deletions
diff --git a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp
index 6928bdb966b..685a812d427 100644
--- a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp
+++ b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp
@@ -76,8 +76,8 @@ void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD(
__m128 upperMinApplied = _mm_sub_ps(upperLimit1,cpAppliedImp);
deltaImpulse = _mm_or_ps( _mm_and_ps(resultUpperLess, deltaImpulse), _mm_andnot_ps(resultUpperLess, upperMinApplied) );
c.m_appliedImpulse = _mm_or_ps( _mm_and_ps(resultUpperLess, c.m_appliedImpulse), _mm_andnot_ps(resultUpperLess, upperLimit1) );
- __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal.mVec128,_mm_set1_ps(body1.m_invMass));
- __m128 linearComponentB = _mm_mul_ps((c.m_contactNormal).mVec128,_mm_set1_ps(body2.m_invMass));
+ __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal.mVec128,body1.m_invMass.mVec128);
+ __m128 linearComponentB = _mm_mul_ps((c.m_contactNormal).mVec128,body2.m_invMass.mVec128);
__m128 impulseMagnitude = deltaImpulse;
body1.m_deltaLinearVelocity.mVec128 = _mm_add_ps(body1.m_deltaLinearVelocity.mVec128,_mm_mul_ps(linearComponentA,impulseMagnitude));
body1.m_deltaAngularVelocity.mVec128 = _mm_add_ps(body1.m_deltaAngularVelocity.mVec128 ,_mm_mul_ps(c.m_angularComponentA.mVec128,impulseMagnitude));
@@ -114,9 +114,7 @@ void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD(
{
c.m_appliedImpulse = sum;
}
- if (body1.m_invMass)
body1.applyImpulse(c.m_contactNormal*body1.m_invMass,c.m_angularComponentA,deltaImpulse);
- if (body2.m_invMass)
body2.applyImpulse(-c.m_contactNormal*body2.m_invMass,c.m_angularComponentB,deltaImpulse);
}
@@ -138,8 +136,8 @@ void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD(
__m128 lowMinApplied = _mm_sub_ps(lowerLimit1,cpAppliedImp);
deltaImpulse = _mm_or_ps( _mm_and_ps(resultLowerLess, lowMinApplied), _mm_andnot_ps(resultLowerLess, deltaImpulse) );
c.m_appliedImpulse = _mm_or_ps( _mm_and_ps(resultLowerLess, lowerLimit1), _mm_andnot_ps(resultLowerLess, sum) );
- __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal.mVec128,_mm_set1_ps(body1.m_invMass));
- __m128 linearComponentB = _mm_mul_ps((c.m_contactNormal).mVec128,_mm_set1_ps(body2.m_invMass));
+ __m128 linearComponentA = _mm_mul_ps(c.m_contactNormal.mVec128,body1.m_invMass.mVec128);
+ __m128 linearComponentB = _mm_mul_ps((c.m_contactNormal).mVec128,body2.m_invMass.mVec128);
__m128 impulseMagnitude = deltaImpulse;
body1.m_deltaLinearVelocity.mVec128 = _mm_add_ps(body1.m_deltaLinearVelocity.mVec128,_mm_mul_ps(linearComponentA,impulseMagnitude));
body1.m_deltaAngularVelocity.mVec128 = _mm_add_ps(body1.m_deltaAngularVelocity.mVec128 ,_mm_mul_ps(c.m_angularComponentA.mVec128,impulseMagnitude));
@@ -169,10 +167,8 @@ void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD(
{
c.m_appliedImpulse = sum;
}
- if (body1.m_invMass)
- body1.applyImpulse(c.m_contactNormal*body1.m_invMass,c.m_angularComponentA,deltaImpulse);
- if (body2.m_invMass)
- body2.applyImpulse(-c.m_contactNormal*body2.m_invMass,c.m_angularComponentB,deltaImpulse);
+ body1.applyImpulse(c.m_contactNormal*body1.m_invMass,c.m_angularComponentA,deltaImpulse);
+ body2.applyImpulse(-c.m_contactNormal*body2.m_invMass,c.m_angularComponentB,deltaImpulse);
}
@@ -224,14 +220,14 @@ void btSequentialImpulseConstraintSolver::initSolverBody(btSolverBody* solverBod
if (rb)
{
- solverBody->m_invMass = rb->getInvMass();
+ solverBody->m_invMass = btVector3(rb->getInvMass(),rb->getInvMass(),rb->getInvMass())*rb->getLinearFactor();
solverBody->m_originalBody = rb;
solverBody->m_angularFactor = rb->getAngularFactor();
} else
{
- solverBody->m_invMass = 0.f;
+ solverBody->m_invMass.setValue(0,0,0);
solverBody->m_originalBody = 0;
- solverBody->m_angularFactor = 1.f;
+ solverBody->m_angularFactor.setValue(1,1,1);
}
}
@@ -394,6 +390,10 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
solverBodyIdB = getOrInitSolverBody(*colObj1);
}
+ ///avoid collision response between two static objects
+ if (!solverBodyIdA && !solverBodyIdB)
+ return;
+
btVector3 rel_pos1;
btVector3 rel_pos2;
btScalar relaxation;
@@ -490,13 +490,13 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
///warm starting (or zero if disabled)
- if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING)
+ if (0)//infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING)
{
solverConstraint.m_appliedImpulse = cp.m_appliedImpulse * infoGlobal.m_warmstartingFactor;
if (rb0)
- m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdA].applyImpulse(solverConstraint.m_contactNormal*rb0->getInvMass(),solverConstraint.m_angularComponentA,solverConstraint.m_appliedImpulse);
+ m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdA].applyImpulse(solverConstraint.m_contactNormal*rb0->getInvMass()*rb0->getLinearFactor(),solverConstraint.m_angularComponentA,solverConstraint.m_appliedImpulse);
if (rb1)
- m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdB].applyImpulse(solverConstraint.m_contactNormal*rb1->getInvMass(),-solverConstraint.m_angularComponentB,-solverConstraint.m_appliedImpulse);
+ m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdB].applyImpulse(solverConstraint.m_contactNormal*rb1->getInvMass()*rb1->getLinearFactor(),-solverConstraint.m_angularComponentB,-solverConstraint.m_appliedImpulse);
} else
{
solverConstraint.m_appliedImpulse = 0.f;
@@ -583,9 +583,9 @@ void btSequentialImpulseConstraintSolver::convertContact(btPersistentManifold* m
{
frictionConstraint1.m_appliedImpulse = cp.m_appliedImpulseLateral1 * infoGlobal.m_warmstartingFactor;
if (rb0)
- m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdA].applyImpulse(frictionConstraint1.m_contactNormal*rb0->getInvMass(),frictionConstraint1.m_angularComponentA,frictionConstraint1.m_appliedImpulse);
+ m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdA].applyImpulse(frictionConstraint1.m_contactNormal*rb0->getInvMass()*rb0->getLinearFactor(),frictionConstraint1.m_angularComponentA,frictionConstraint1.m_appliedImpulse);
if (rb1)
- m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdB].applyImpulse(frictionConstraint1.m_contactNormal*rb1->getInvMass(),-frictionConstraint1.m_angularComponentB,-frictionConstraint1.m_appliedImpulse);
+ m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdB].applyImpulse(frictionConstraint1.m_contactNormal*rb1->getInvMass()*rb1->getLinearFactor(),-frictionConstraint1.m_angularComponentB,-frictionConstraint1.m_appliedImpulse);
} else
{
frictionConstraint1.m_appliedImpulse = 0.f;
diff --git a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h
index 467e37bb91f..90e7fc8354d 100644
--- a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h
+++ b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h
@@ -24,10 +24,7 @@ class btIDebugDraw;
-///The btSequentialImpulseConstraintSolver uses a Propagation Method and Sequentially applies impulses
-///The approach is the 3D version of Erin Catto's GDC 2006 tutorial. See http://www.gphysics.com
-///Although Sequential Impulse is more intuitive, it is mathematically equivalent to Projected Successive Overrelaxation (iterative LCP)
-///Applies impulses for combined restitution and penetration recovery and to simulate friction
+///The btSequentialImpulseConstraintSolver is a fast SIMD implementation of the Projected Gauss Seidel (iterative LCP) method.
class btSequentialImpulseConstraintSolver : public btConstraintSolver
{
protected:
diff --git a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSolverBody.h b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSolverBody.h
index 98c9876ae46..6b728959162 100644
--- a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSolverBody.h
+++ b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btSolverBody.h
@@ -110,8 +110,8 @@ ATTRIBUTE_ALIGNED16 (struct) btSolverBody
BT_DECLARE_ALIGNED_ALLOCATOR();
btVector3 m_deltaLinearVelocity;
btVector3 m_deltaAngularVelocity;
- btScalar m_angularFactor;
- btScalar m_invMass;
+ btVector3 m_angularFactor;
+ btVector3 m_invMass;
btScalar m_friction;
btRigidBody* m_originalBody;
btVector3 m_pushVelocity;
@@ -162,7 +162,7 @@ ATTRIBUTE_ALIGNED16 (struct) btSolverBody
void writebackVelocity(btScalar timeStep=0)
{
- if (m_invMass)
+ if (m_originalBody)
{
m_originalBody->setLinearVelocity(m_originalBody->getLinearVelocity()+m_deltaLinearVelocity);
m_originalBody->setAngularVelocity(m_originalBody->getAngularVelocity()+m_deltaAngularVelocity);
diff --git a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h
index 78a770231b3..14cbe831b40 100644
--- a/extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h
+++ b/extern/bullet2/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h
@@ -30,7 +30,6 @@ enum btTypedConstraintType
HINGE_CONSTRAINT_TYPE,
CONETWIST_CONSTRAINT_TYPE,
D6_CONSTRAINT_TYPE,
- VEHICLE_CONSTRAINT_TYPE,
SLIDER_CONSTRAINT_TYPE
};
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btActionInterface.h b/extern/bullet2/src/BulletDynamics/Dynamics/btActionInterface.h
new file mode 100644
index 00000000000..8348795ef70
--- /dev/null
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btActionInterface.h
@@ -0,0 +1,39 @@
+/*
+Bullet Continuous Collision Detection and Physics Library
+Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
+
+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.
+*/
+
+#ifndef _BT_ACTION_INTERFACE_H
+#define _BT_ACTION_INTERFACE_H
+
+class btIDebugDraw;
+class btCollisionWorld;
+
+#include "LinearMath/btScalar.h"
+
+///Basic interface to allow actions such as vehicles and characters to be updated inside a btDynamicsWorld
+class btActionInterface
+{
+ public:
+
+ virtual ~btActionInterface()
+ {
+ }
+
+ virtual void updateAction( btCollisionWorld* collisionWorld, btScalar deltaTimeStep)=0;
+
+ virtual void debugDraw(btIDebugDraw* debugDrawer) = 0;
+
+};
+
+#endif //_BT_ACTION_INTERFACE_H \ No newline at end of file
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btContinuousDynamicsWorld.cpp b/extern/bullet2/src/BulletDynamics/Dynamics/btContinuousDynamicsWorld.cpp
index 19443adc723..fa0d63d74a1 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btContinuousDynamicsWorld.cpp
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btContinuousDynamicsWorld.cpp
@@ -90,8 +90,7 @@ void btContinuousDynamicsWorld::internalSingleStepSimulation( btScalar timeStep)
integrateTransforms(timeStep * toi);
///update vehicle simulation
- updateVehicles(timeStep);
-
+ updateActions(timeStep);
updateActivationState( timeStep );
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp b/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp
index ec803df06f7..ea2e0ad2a2b 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp
@@ -51,17 +51,7 @@ subject to the following restrictions:
#include "LinearMath/btIDebugDraw.h"
-
-//vehicle
-#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
-#include "BulletDynamics/Vehicle/btVehicleRaycaster.h"
-#include "BulletDynamics/Vehicle/btWheelInfo.h"
-#ifdef USE_CHARACTER
-//character
-#include "BulletDynamics/Character/btCharacterControllerInterface.h"
-#endif //USE_CHARACTER
-
-#include "LinearMath/btIDebugDraw.h"
+#include "BulletDynamics/Dynamics/btActionInterface.h"
#include "LinearMath/btQuickprof.h"
#include "LinearMath/btMotionState.h"
@@ -214,32 +204,11 @@ void btDiscreteDynamicsWorld::debugDrawWorld()
}
- for ( i=0;i<this->m_vehicles.size();i++)
+ if (getDebugDrawer() && getDebugDrawer()->getDebugMode())
{
- for (int v=0;v<m_vehicles[i]->getNumWheels();v++)
+ for (i=0;i<m_actions.size();i++)
{
- btVector3 wheelColor(0,255,255);
- if (m_vehicles[i]->getWheelInfo(v).m_raycastInfo.m_isInContact)
- {
- wheelColor.setValue(0,0,255);
- } else
- {
- wheelColor.setValue(255,0,255);
- }
-
- btVector3 wheelPosWS = m_vehicles[i]->getWheelInfo(v).m_worldTransform.getOrigin();
-
- btVector3 axle = btVector3(
- m_vehicles[i]->getWheelInfo(v).m_worldTransform.getBasis()[0][m_vehicles[i]->getRightAxis()],
- m_vehicles[i]->getWheelInfo(v).m_worldTransform.getBasis()[1][m_vehicles[i]->getRightAxis()],
- m_vehicles[i]->getWheelInfo(v).m_worldTransform.getBasis()[2][m_vehicles[i]->getRightAxis()]);
-
-
- //m_vehicles[i]->getWheelInfo(v).m_raycastInfo.m_wheelAxleWS
- //debug wheels (cylinders)
- m_debugDrawer->drawLine(wheelPosWS,wheelPosWS+axle,wheelColor);
- m_debugDrawer->drawLine(wheelPosWS,m_vehicles[i]->getWheelInfo(v).m_raycastInfo.m_contactPointWS,wheelColor);
-
+ m_actions[i]->debugDraw(m_debugDrawer);
}
}
}
@@ -311,7 +280,7 @@ void btDiscreteDynamicsWorld::synchronizeMotionStates()
synchronizeSingleMotionState(body);
}
}
-
+/*
if (getDebugDrawer() && getDebugDrawer()->getDebugMode() & btIDebugDraw::DBG_DrawWireframe)
{
for ( int i=0;i<this->m_vehicles.size();i++)
@@ -323,6 +292,8 @@ void btDiscreteDynamicsWorld::synchronizeMotionStates()
}
}
}
+ */
+
}
@@ -428,10 +399,8 @@ void btDiscreteDynamicsWorld::internalSingleStepSimulation(btScalar timeStep)
integrateTransforms(timeStep);
///update vehicle simulation
- updateVehicles(timeStep);
+ updateActions(timeStep);
- updateCharacters(timeStep);
-
updateActivationState( timeStep );
if(0 != m_internalTickCallback) {
@@ -495,31 +464,15 @@ void btDiscreteDynamicsWorld::addRigidBody(btRigidBody* body, short group, short
}
-void btDiscreteDynamicsWorld::updateVehicles(btScalar timeStep)
-{
- BT_PROFILE("updateVehicles");
-
- for ( int i=0;i<m_vehicles.size();i++)
- {
- btRaycastVehicle* vehicle = m_vehicles[i];
- vehicle->updateVehicle( timeStep);
- }
-}
-
-void btDiscreteDynamicsWorld::updateCharacters(btScalar timeStep)
+void btDiscreteDynamicsWorld::updateActions(btScalar timeStep)
{
-#ifdef USE_CHARACTER
- BT_PROFILE("updateCharacters");
+ BT_PROFILE("updateActions");
- for ( int i=0;i<m_characters.size();i++)
+ for ( int i=0;i<m_actions.size();i++)
{
- btCharacterControllerInterface* character = m_characters[i];
- character->preStep (this);
- character->playerStep (this,timeStep);
+ m_actions[i]->updateAction( this, timeStep);
}
-#endif //USE_CHARACTER
}
-
void btDiscreteDynamicsWorld::updateActivationState(btScalar timeStep)
@@ -576,28 +529,35 @@ void btDiscreteDynamicsWorld::removeConstraint(btTypedConstraint* constraint)
constraint->getRigidBodyB().removeConstraintRef(constraint);
}
-void btDiscreteDynamicsWorld::addVehicle(btRaycastVehicle* vehicle)
+void btDiscreteDynamicsWorld::addAction(btActionInterface* action)
+{
+ m_actions.push_back(action);
+}
+
+void btDiscreteDynamicsWorld::removeAction(btActionInterface* action)
+{
+ m_actions.remove(action);
+}
+
+
+void btDiscreteDynamicsWorld::addVehicle(btActionInterface* vehicle)
{
- m_vehicles.push_back(vehicle);
+ addAction(vehicle);
}
-void btDiscreteDynamicsWorld::removeVehicle(btRaycastVehicle* vehicle)
+void btDiscreteDynamicsWorld::removeVehicle(btActionInterface* vehicle)
{
- m_vehicles.remove(vehicle);
+ removeAction(vehicle);
}
-void btDiscreteDynamicsWorld::addCharacter(btCharacterControllerInterface* character)
+void btDiscreteDynamicsWorld::addCharacter(btActionInterface* character)
{
-#ifdef USE_CHARACTER
- m_characters.push_back(character);
-#endif //USE_CHARACTER
+ addAction(character);
}
-void btDiscreteDynamicsWorld::removeCharacter(btCharacterControllerInterface* character)
+void btDiscreteDynamicsWorld::removeCharacter(btActionInterface* character)
{
-#ifdef USE_CHARACTER
- m_characters.remove(character);
-#endif //USE_CHARACTER
+ removeAction(character);
}
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h b/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h
index 34d4e6b353f..4662cf5052a 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h
@@ -23,10 +23,8 @@ class btOverlappingPairCache;
class btConstraintSolver;
class btSimulationIslandManager;
class btTypedConstraint;
+class btActionInterface;
-
-class btRaycastVehicle;
-class btCharacterControllerInterface;
class btIDebugDraw;
#include "LinearMath/btAlignedObjectArray.h"
@@ -52,12 +50,8 @@ protected:
bool m_ownsIslandManager;
bool m_ownsConstraintSolver;
+ btAlignedObjectArray<btActionInterface*> m_actions;
- btAlignedObjectArray<btRaycastVehicle*> m_vehicles;
-
- btAlignedObjectArray<btCharacterControllerInterface*> m_characters;
-
-
int m_profileTimings;
virtual void predictUnconstraintMotion(btScalar timeStep);
@@ -70,9 +64,7 @@ protected:
void updateActivationState(btScalar timeStep);
- void updateVehicles(btScalar timeStep);
-
- void updateCharacters(btScalar timeStep);
+ void updateActions(btScalar timeStep);
void startProfiling(btScalar timeStep);
@@ -105,15 +97,10 @@ public:
virtual void removeConstraint(btTypedConstraint* constraint);
- virtual void addVehicle(btRaycastVehicle* vehicle);
+ virtual void addAction(btActionInterface*);
- virtual void removeVehicle(btRaycastVehicle* vehicle);
+ virtual void removeAction(btActionInterface*);
- virtual void addCharacter(btCharacterControllerInterface* character);
-
- virtual void removeCharacter(btCharacterControllerInterface* character);
-
-
btSimulationIslandManager* getSimulationIslandManager()
{
return m_islandManager;
@@ -130,6 +117,7 @@ public:
}
virtual void setGravity(const btVector3& gravity);
+
virtual btVector3 getGravity () const;
virtual void addRigidBody(btRigidBody* body);
@@ -171,6 +159,21 @@ public:
(void) numTasks;
}
+ ///obsolete, use updateActions instead
+ virtual void updateVehicles(btScalar timeStep)
+ {
+ updateActions(timeStep);
+ }
+
+ ///obsolete, use addAction instead
+ virtual void addVehicle(btActionInterface* vehicle);
+ ///obsolete, use removeAction instead
+ virtual void removeVehicle(btActionInterface* vehicle);
+ ///obsolete, use addAction instead
+ virtual void addCharacter(btActionInterface* character);
+ ///obsolete, use removeAction instead
+ virtual void removeCharacter(btActionInterface* character);
+
};
#endif //BT_DISCRETE_DYNAMICS_WORLD_H
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h b/extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h
index 2d90e212f7a..ecf7a2f0c64 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btDynamicsWorld.h
@@ -20,10 +20,10 @@ subject to the following restrictions:
#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
class btTypedConstraint;
-class btRaycastVehicle;
+class btActionInterface;
class btConstraintSolver;
class btDynamicsWorld;
-class btCharacterControllerInterface;
+
/// Type for the callback for each tick
typedef void (*btInternalTickCallback)(btDynamicsWorld *world, btScalar timeStep);
@@ -72,14 +72,9 @@ public:
virtual void removeConstraint(btTypedConstraint* constraint) {(void)constraint;}
- virtual void addVehicle(btRaycastVehicle* vehicle) {(void)vehicle;}
-
- virtual void removeVehicle(btRaycastVehicle* vehicle) {(void)vehicle;}
-
- virtual void addCharacter(btCharacterControllerInterface* character) {(void)character;}
-
- virtual void removeCharacter(btCharacterControllerInterface* character) {(void)character;}
+ virtual void addAction(btActionInterface* action) = 0;
+ virtual void removeAction(btActionInterface* action) = 0;
//once a rigidbody is added to the dynamics world, it will get this gravity assigned
//existing rigidbodies in the world get gravity assigned too, during this method
@@ -129,6 +124,16 @@ public:
}
+ ///obsolete, use addAction instead.
+ virtual void addVehicle(btActionInterface* vehicle) {(void)vehicle;}
+ ///obsolete, use removeAction instead
+ virtual void removeVehicle(btActionInterface* vehicle) {(void)vehicle;}
+ ///obsolete, use addAction instead.
+ virtual void addCharacter(btActionInterface* character) {(void)character;}
+ ///obsolete, use removeAction instead
+ virtual void removeCharacter(btActionInterface* character) {(void)character;}
+
+
};
#endif //BT_DYNAMICS_WORLD_H
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp b/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp
index a2b8a7dade4..a4d8e1d77f6 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.cpp
@@ -44,7 +44,8 @@ void btRigidBody::setupRigidBody(const btRigidBody::btRigidBodyConstructionInfo&
m_linearVelocity.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
m_angularVelocity.setValue(btScalar(0.),btScalar(0.),btScalar(0.));
- m_angularFactor = btScalar(1.);
+ m_angularFactor.setValue(1,1,1);
+ m_linearFactor.setValue(1,1,1);
m_gravity.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
m_gravity_acceleration.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
m_totalForce.setValue(btScalar(0.0), btScalar(0.0), btScalar(0.0));
diff --git a/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h b/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h
index ec570cab875..da1fcb78611 100644
--- a/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h
+++ b/extern/bullet2/src/BulletDynamics/Dynamics/btRigidBody.h
@@ -45,7 +45,8 @@ class btRigidBody : public btCollisionObject
btVector3 m_linearVelocity;
btVector3 m_angularVelocity;
btScalar m_inverseMass;
- btScalar m_angularFactor;
+ btVector3 m_angularFactor;
+ btVector3 m_linearFactor;
btVector3 m_gravity;
btVector3 m_gravity_acceleration;
@@ -219,6 +220,14 @@ public:
void setMassProps(btScalar mass, const btVector3& inertia);
+ const btVector3& getLinearFactor() const
+ {
+ return m_linearFactor;
+ }
+ void setLinearFactor(const btVector3& linearFactor)
+ {
+ m_linearFactor = linearFactor;
+ }
btScalar getInvMass() const { return m_inverseMass; }
const btMatrix3x3& getInvInertiaTensorWorld() const {
return m_invInertiaTensorWorld;
@@ -230,7 +239,7 @@ public:
void applyCentralForce(const btVector3& force)
{
- m_totalForce += force;
+ m_totalForce += force*m_linearFactor;
}
const btVector3& getTotalForce()
@@ -261,23 +270,23 @@ public:
void applyTorque(const btVector3& torque)
{
- m_totalTorque += torque;
+ m_totalTorque += torque*m_angularFactor;
}
void applyForce(const btVector3& force, const btVector3& rel_pos)
{
applyCentralForce(force);
- applyTorque(rel_pos.cross(force)*m_angularFactor);
+ applyTorque(rel_pos.cross(force*m_linearFactor));
}
void applyCentralImpulse(const btVector3& impulse)
{
- m_linearVelocity += impulse * m_inverseMass;
+ m_linearVelocity += impulse *m_linearFactor * m_inverseMass;
}
void applyTorqueImpulse(const btVector3& torque)
{
- m_angularVelocity += m_invInertiaTensorWorld * torque;
+ m_angularVelocity += m_invInertiaTensorWorld * torque * m_angularFactor;
}
void applyImpulse(const btVector3& impulse, const btVector3& rel_pos)
@@ -287,7 +296,7 @@ public:
applyCentralImpulse(impulse);
if (m_angularFactor)
{
- applyTorqueImpulse(rel_pos.cross(impulse)*m_angularFactor);
+ applyTorqueImpulse(rel_pos.cross(impulse*m_linearFactor));
}
}
}
@@ -297,10 +306,10 @@ public:
{
if (m_inverseMass != btScalar(0.))
{
- m_linearVelocity += linearComponent*impulseMagnitude;
+ m_linearVelocity += linearComponent*m_linearFactor*impulseMagnitude;
if (m_angularFactor)
{
- m_angularVelocity += angularComponent*impulseMagnitude*m_angularFactor;
+ m_angularVelocity += angularComponent*m_angularFactor*impulseMagnitude;
}
}
}
@@ -450,11 +459,16 @@ public:
int m_contactSolverType;
int m_frictionSolverType;
- void setAngularFactor(btScalar angFac)
+ void setAngularFactor(const btVector3& angFac)
{
m_angularFactor = angFac;
}
- btScalar getAngularFactor() const
+
+ void setAngularFactor(btScalar angFac)
+ {
+ m_angularFactor.setValue(angFac,angFac,angFac);
+ }
+ const btVector3& getAngularFactor() const
{
return m_angularFactor;
}
diff --git a/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp b/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp
index 4982e673053..031fcb5b447 100644
--- a/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp
+++ b/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp
@@ -19,15 +19,13 @@
#include "btVehicleRaycaster.h"
#include "btWheelInfo.h"
#include "LinearMath/btMinMax.h"
-
-
+#include "LinearMath/btIDebugDraw.h"
#include "BulletDynamics/ConstraintSolver/btContactConstraint.h"
static btRigidBody s_fixedObject( 0,0,0);
btRaycastVehicle::btRaycastVehicle(const btVehicleTuning& tuning,btRigidBody* chassis, btVehicleRaycaster* raycaster )
-: btTypedConstraint(VEHICLE_CONSTRAINT_TYPE),
-m_vehicleRaycaster(raycaster),
+:m_vehicleRaycaster(raycaster),
m_pitchControl(btScalar(0.))
{
m_chassisBody = chassis;
@@ -691,7 +689,7 @@ void btRaycastVehicle::updateFriction(btScalar timeStep)
btVector3 sideImp = m_axle[wheel] * m_sideImpulse[wheel];
- rel_pos[m_indexForwardAxis] *= wheelInfo.m_rollInfluence;
+ rel_pos[m_indexUpAxis] *= wheelInfo.m_rollInfluence;
m_chassisBody->applyImpulse(sideImp,rel_pos);
//apply friction impulse on the ground
@@ -704,6 +702,36 @@ void btRaycastVehicle::updateFriction(btScalar timeStep)
}
+
+void btRaycastVehicle::debugDraw(btIDebugDraw* debugDrawer)
+{
+
+ for (int v=0;v<this->getNumWheels();v++)
+ {
+ btVector3 wheelColor(0,255,255);
+ if (getWheelInfo(v).m_raycastInfo.m_isInContact)
+ {
+ wheelColor.setValue(0,0,255);
+ } else
+ {
+ wheelColor.setValue(255,0,255);
+ }
+
+ btVector3 wheelPosWS = getWheelInfo(v).m_worldTransform.getOrigin();
+
+ btVector3 axle = btVector3(
+ getWheelInfo(v).m_worldTransform.getBasis()[0][getRightAxis()],
+ getWheelInfo(v).m_worldTransform.getBasis()[1][getRightAxis()],
+ getWheelInfo(v).m_worldTransform.getBasis()[2][getRightAxis()]);
+
+ //debug wheels (cylinders)
+ debugDrawer->drawLine(wheelPosWS,wheelPosWS+axle,wheelColor);
+ debugDrawer->drawLine(wheelPosWS,getWheelInfo(v).m_raycastInfo.m_contactPointWS,wheelColor);
+
+ }
+}
+
+
void* btDefaultVehicleRaycaster::castRay(const btVector3& from,const btVector3& to, btVehicleRaycasterResult& result)
{
// RayResultCallback& resultCallback;
@@ -727,3 +755,4 @@ void* btDefaultVehicleRaycaster::castRay(const btVector3& from,const btVector3&
}
return 0;
}
+
diff --git a/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h b/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h
index bfe0d7df2fb..d5a299c606f 100644
--- a/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h
+++ b/extern/bullet2/src/BulletDynamics/Vehicle/btRaycastVehicle.h
@@ -17,11 +17,12 @@
class btDynamicsWorld;
#include "LinearMath/btAlignedObjectArray.h"
#include "btWheelInfo.h"
+#include "BulletDynamics/Dynamics/btActionInterface.h"
class btVehicleTuning;
///rayCast vehicle, very special constraint that turn a rigidbody into a vehicle.
-class btRaycastVehicle : public btTypedConstraint
+class btRaycastVehicle : public btActionInterface
{
btAlignedObjectArray<btVector3> m_forwardWS;
@@ -29,6 +30,11 @@ class btRaycastVehicle : public btTypedConstraint
btAlignedObjectArray<btScalar> m_forwardImpulse;
btAlignedObjectArray<btScalar> m_sideImpulse;
+ int m_userConstraintType;
+
+ int m_userConstraintId;
+
+
public:
class btVehicleTuning
{
@@ -73,13 +79,24 @@ public:
virtual ~btRaycastVehicle() ;
-
+
+ ///btActionInterface interface
+ virtual void updateAction( btCollisionWorld* collisionWorld, btScalar step)
+ {
+ updateVehicle(step);
+ }
+
+
+ ///btActionInterface interface
+ void debugDraw(btIDebugDraw* debugDrawer);
+
const btTransform& getChassisWorldTransform() const;
btScalar rayCast(btWheelInfo& wheel);
virtual void updateVehicle(btScalar step);
-
+
+
void resetSuspension();
btScalar getSteeringValue(int wheel) const;
@@ -175,26 +192,24 @@ public:
m_indexForwardAxis = forwardIndex;
}
- virtual void buildJacobian()
+ int getUserConstraintType() const
{
- //not yet
+ return m_userConstraintType ;
}
- virtual void getInfo1 (btConstraintInfo1* info)
+ void setUserConstraintType(int userConstraintType)
{
- info->m_numConstraintRows = 0;
- info->nub = 0;
- }
+ m_userConstraintType = userConstraintType;
+ };
- virtual void getInfo2 (btConstraintInfo2* info)
+ void setUserConstraintId(int uid)
{
- btAssert(0);
+ m_userConstraintId = uid;
}
- virtual void solveConstraintObsolete(btSolverBody& bodyA,btSolverBody& bodyB,btScalar timeStep)
+ int getUserConstraintId() const
{
- (void)timeStep;
- //not yet
+ return m_userConstraintId;
}
diff --git a/extern/bullet2/src/LinearMath/btConvexHull.cpp b/extern/bullet2/src/LinearMath/btConvexHull.cpp
index 16ababca522..419c752a1d9 100644
--- a/extern/bullet2/src/LinearMath/btConvexHull.cpp
+++ b/extern/bullet2/src/LinearMath/btConvexHull.cpp
@@ -262,8 +262,8 @@ int maxdirsterid(const T *p,int count,const T &dir,btAlignedObjectArray<int> &al
int ma=-1;
for(btScalar x = btScalar(0.0) ; x<= btScalar(360.0) ; x+= btScalar(45.0))
{
- btScalar s = sinf(SIMD_RADS_PER_DEG*(x));
- btScalar c = cosf(SIMD_RADS_PER_DEG*(x));
+ btScalar s = btSin(SIMD_RADS_PER_DEG*(x));
+ btScalar c = btCos(SIMD_RADS_PER_DEG*(x));
int mb = maxdirfiltered(p,count,dir+(u*s+v*c)*btScalar(0.025),allow);
if(ma==m && mb==m)
{
@@ -275,8 +275,8 @@ int maxdirsterid(const T *p,int count,const T &dir,btAlignedObjectArray<int> &al
int mc = ma;
for(btScalar xx = x-btScalar(40.0) ; xx <= x ; xx+= btScalar(5.0))
{
- btScalar s = sinf(SIMD_RADS_PER_DEG*(xx));
- btScalar c = cosf(SIMD_RADS_PER_DEG*(xx));
+ btScalar s = btSin(SIMD_RADS_PER_DEG*(xx));
+ btScalar c = btCos(SIMD_RADS_PER_DEG*(xx));
int md = maxdirfiltered(p,count,dir+(u*s+v*c)*btScalar(0.025),allow);
if(mc==m && md==m)
{