Changeset 2430 for code/branches/physics/src/bullet/BulletDynamics
- Timestamp:
- Dec 13, 2008, 11:45:51 PM (16 years ago)
- Location:
- code/branches/physics/src/bullet/BulletDynamics
- Files:
-
- 4 added
- 18 edited
Legend:
- Unmodified
- Added
- Removed
-
code/branches/physics/src/bullet/BulletDynamics/CMakeLists.txt
r2192 r2430 1 ADD_LIBRARY(LibBulletDynamics 2 1 SET(BulletDynamics_SRCS 3 2 ConstraintSolver/btContactConstraint.cpp 4 ConstraintSolver/btContactConstraint.h5 3 ConstraintSolver/btConeTwistConstraint.cpp 6 ConstraintSolver/btConeTwistConstraint.h7 4 ConstraintSolver/btGeneric6DofConstraint.cpp 8 ConstraintSolver/btGeneric6DofConstraint.h9 5 ConstraintSolver/btHingeConstraint.cpp 10 ConstraintSolver/btHingeConstraint.h11 6 ConstraintSolver/btPoint2PointConstraint.cpp 12 ConstraintSolver/btPoint2PointConstraint.h13 7 ConstraintSolver/btSequentialImpulseConstraintSolver.cpp 14 ConstraintSolver/btSequentialImpulseConstraintSolver.h15 8 ConstraintSolver/btSliderConstraint.cpp 16 ConstraintSolver/btSliderConstraint.h17 9 ConstraintSolver/btSolve2LinearConstraint.cpp 18 ConstraintSolver/btSolve2LinearConstraint.h19 10 ConstraintSolver/btTypedConstraint.cpp 20 ConstraintSolver/btTypedConstraint.h21 11 Dynamics/Bullet-C-API.cpp 22 12 Dynamics/btDiscreteDynamicsWorld.cpp 23 Dynamics/btDiscreteDynamicsWorld.h24 13 Dynamics/btSimpleDynamicsWorld.cpp 25 Dynamics/btSimpleDynamicsWorld.h26 14 Dynamics/btRigidBody.cpp 27 Dynamics/btRigidBody.h28 15 Vehicle/btRaycastVehicle.cpp 29 Vehicle/btRaycastVehicle.h30 16 Vehicle/btWheelInfo.cpp 31 Vehicle/btWheelInfo.h17 Character/btKinematicCharacterController.cpp 32 18 ) 19 20 ADD_LIBRARY(BulletDynamics ${BulletDynamics_SRCS}) -
code/branches/physics/src/bullet/BulletDynamics/ConstraintSolver/btConeTwistConstraint.h
r2192 r2430 21 21 #define CONETWISTCONSTRAINT_H 22 22 23 #include " ../../LinearMath/btVector3.h"23 #include "LinearMath/btVector3.h" 24 24 #include "btJacobianEntry.h" 25 25 #include "btTypedConstraint.h" -
code/branches/physics/src/bullet/BulletDynamics/ConstraintSolver/btContactConstraint.cpp
r2192 r2430 426 426 427 427 return btScalar(0.); 428 } ;429 428 } 429 -
code/branches/physics/src/bullet/BulletDynamics/ConstraintSolver/btContactConstraint.h
r2192 r2430 17 17 #define CONTACT_CONSTRAINT_H 18 18 19 // todo: make into a proper class working with the iterative constraint solver19 ///@todo: make into a proper class working with the iterative constraint solver 20 20 21 21 class btRigidBody; -
code/branches/physics/src/bullet/BulletDynamics/ConstraintSolver/btContactSolverInfo.h
r2192 r2430 22 22 SOLVER_FRICTION_SEPARATE = 2, 23 23 SOLVER_USE_WARMSTARTING = 4, 24 SOLVER_CACHE_FRIENDLY = 8 24 SOLVER_USE_FRICTION_WARMSTARTING = 8, 25 SOLVER_CACHE_FRIENDLY = 16 25 26 }; 26 27 … … 45 46 46 47 int m_solverMode; 48 int m_restingContactRestitutionThreshold; 47 49 48 50 … … 69 71 m_linearSlop = btScalar(0.0); 70 72 m_warmstartingFactor=btScalar(0.85); 71 m_solverMode = SOLVER_RANDMIZE_ORDER | SOLVER_CACHE_FRIENDLY | SOLVER_USE_WARMSTARTING; 73 m_solverMode = SOLVER_CACHE_FRIENDLY | SOLVER_RANDMIZE_ORDER | SOLVER_USE_WARMSTARTING; 74 m_restingContactRestitutionThreshold = 2;//resting contact lifetime threshold to disable restitution 72 75 } 73 76 }; -
code/branches/physics/src/bullet/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp
r2192 r2430 27 27 28 28 29 static const btScalar kSign[] = { btScalar(1.0), btScalar(-1.0), btScalar(1.0) };30 static const int kAxisA[] = { 1, 0, 0 };31 static const int kAxisB[] = { 2, 2, 1 };32 29 #define GENERIC_D6_DISABLE_WARMSTARTING 1 33 30 … … 157 154 btScalar clippedMotorImpulse; 158 155 159 // todo: should clip against accumulated impulse156 ///@todo: should clip against accumulated impulse 160 157 if (unclippedMotorImpulse>0.0f) 161 158 { -
code/branches/physics/src/bullet/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp
r2192 r2430 324 324 getRigidBodyB().computeAngularImpulseDenominator(normal); 325 325 // scale for mass and relaxation 326 //todo: expose this 0.9 factor to developer327 326 velrelOrthog *= (btScalar(1.)/denom) * m_relaxationFactor; 328 327 } -
code/branches/physics/src/bullet/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp
r2192 r2430 438 438 439 439 440 voidbtSequentialImpulseConstraintSolver::addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation)440 btSolverConstraint& btSequentialImpulseConstraintSolver::addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation) 441 441 { 442 442 … … 492 492 solverConstraint.m_jacDiagABInv = denom; 493 493 494 494 return solverConstraint; 495 495 } 496 496 … … 719 719 720 720 solverConstraint.m_friction = cp.m_combinedFriction; 721 solverConstraint.m_restitution = restitutionCurve(rel_vel, cp.m_combinedRestitution); 722 if (solverConstraint.m_restitution <= btScalar(0.)) 721 722 723 if (cp.m_lifeTime>infoGlobal.m_restingContactRestitutionThreshold) 723 724 { 724 725 solverConstraint.m_restitution = 0.f; 725 }; 726 } else 727 { 728 solverConstraint.m_restitution = restitutionCurve(rel_vel, cp.m_combinedRestitution); 729 if (solverConstraint.m_restitution <= btScalar(0.)) 730 { 731 solverConstraint.m_restitution = 0.f; 732 }; 733 } 726 734 727 735 … … 761 769 cp.m_lateralFrictionDir1 /= btSqrt(lat_rel_vel); 762 770 addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); 763 cp.m_lateralFrictionDir2 = cp.m_lateralFrictionDir1.cross(cp.m_normalWorldOnB); 764 cp.m_lateralFrictionDir2.normalize();//?? 765 addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); 771 if(infoGlobal.m_solverMode & SOLVER_USE_FRICTION_WARMSTARTING) 772 { 773 cp.m_lateralFrictionDir2 = cp.m_lateralFrictionDir1.cross(cp.m_normalWorldOnB); 774 cp.m_lateralFrictionDir2.normalize();//?? 775 addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); 776 cp.m_lateralFrictionInitialized = true; 777 } 766 778 } else 767 779 { 768 780 //re-calculate friction direction every frame, todo: check if this is really needed 769 770 781 btPlaneSpace1(cp.m_normalWorldOnB,cp.m_lateralFrictionDir1,cp.m_lateralFrictionDir2); 771 782 addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); 772 783 addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); 784 if (infoGlobal.m_solverMode & SOLVER_USE_FRICTION_WARMSTARTING) 785 { 786 cp.m_lateralFrictionInitialized = true; 787 } 773 788 } 774 cp.m_lateralFrictionInitialized = true;775 789 776 790 } else 777 791 { 778 792 addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); 779 addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); 793 if (infoGlobal.m_solverMode & SOLVER_USE_FRICTION_WARMSTARTING) 794 addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation); 780 795 } 781 796 797 if (infoGlobal.m_solverMode & SOLVER_USE_FRICTION_WARMSTARTING) 782 798 { 783 btSolverConstraint& frictionConstraint1 = m_tmpSolverFrictionConstraintPool[solverConstraint.m_frictionIndex];784 if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING)785 799 { 786 frictionConstraint1.m_appliedImpulse = cp.m_appliedImpulseLateral1 * infoGlobal.m_warmstartingFactor; 787 if (rb0) 788 m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdA].internalApplyImpulse(frictionConstraint1.m_contactNormal*rb0->getInvMass(),frictionConstraint1.m_angularComponentA,frictionConstraint1.m_appliedImpulse); 789 if (rb1) 790 m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdB].internalApplyImpulse(frictionConstraint1.m_contactNormal*rb1->getInvMass(),frictionConstraint1.m_angularComponentB,-frictionConstraint1.m_appliedImpulse); 791 } else 800 btSolverConstraint& frictionConstraint1 = m_tmpSolverFrictionConstraintPool[solverConstraint.m_frictionIndex]; 801 if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING) 802 { 803 frictionConstraint1.m_appliedImpulse = cp.m_appliedImpulseLateral1 * infoGlobal.m_warmstartingFactor; 804 if (rb0) 805 m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdA].internalApplyImpulse(frictionConstraint1.m_contactNormal*rb0->getInvMass(),frictionConstraint1.m_angularComponentA,frictionConstraint1.m_appliedImpulse); 806 if (rb1) 807 m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdB].internalApplyImpulse(frictionConstraint1.m_contactNormal*rb1->getInvMass(),frictionConstraint1.m_angularComponentB,-frictionConstraint1.m_appliedImpulse); 808 } else 809 { 810 frictionConstraint1.m_appliedImpulse = 0.f; 811 } 812 } 792 813 { 793 frictionConstraint1.m_appliedImpulse = 0.f; 794 } 795 } 796 { 797 btSolverConstraint& frictionConstraint2 = m_tmpSolverFrictionConstraintPool[solverConstraint.m_frictionIndex+1]; 798 if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING) 799 { 800 frictionConstraint2.m_appliedImpulse = cp.m_appliedImpulseLateral2 * infoGlobal.m_warmstartingFactor; 801 if (rb0) 802 m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdA].internalApplyImpulse(frictionConstraint2.m_contactNormal*rb0->getInvMass(),frictionConstraint2.m_angularComponentA,frictionConstraint2.m_appliedImpulse); 803 if (rb1) 804 m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdB].internalApplyImpulse(frictionConstraint2.m_contactNormal*rb1->getInvMass(),frictionConstraint2.m_angularComponentB,-frictionConstraint2.m_appliedImpulse); 805 } else 806 { 807 frictionConstraint2.m_appliedImpulse = 0.f; 814 btSolverConstraint& frictionConstraint2 = m_tmpSolverFrictionConstraintPool[solverConstraint.m_frictionIndex+1]; 815 if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING) 816 { 817 frictionConstraint2.m_appliedImpulse = cp.m_appliedImpulseLateral2 * infoGlobal.m_warmstartingFactor; 818 if (rb0) 819 m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdA].internalApplyImpulse(frictionConstraint2.m_contactNormal*rb0->getInvMass(),frictionConstraint2.m_angularComponentA,frictionConstraint2.m_appliedImpulse); 820 if (rb1) 821 m_tmpSolverBodyPool[solverConstraint.m_solverBodyIdB].internalApplyImpulse(frictionConstraint2.m_contactNormal*rb1->getInvMass(),frictionConstraint2.m_angularComponentB,-frictionConstraint2.m_appliedImpulse); 822 } else 823 { 824 frictionConstraint2.m_appliedImpulse = 0.f; 825 } 808 826 } 809 827 } … … 833 851 int numFrictionPool = m_tmpSolverFrictionConstraintPool.size(); 834 852 835 /// todo: use stack allocator for such temporarily memory, same for solver bodies/constraints853 ///@todo: use stack allocator for such temporarily memory, same for solver bodies/constraints 836 854 m_orderTmpConstraintPool.resize(numConstraintPool); 837 855 m_orderFrictionConstraintPool.resize(numFrictionPool); … … 985 1003 btAssert(pt); 986 1004 pt->m_appliedImpulse = solveManifold.m_appliedImpulse; 987 pt->m_appliedImpulseLateral1 = m_tmpSolverFrictionConstraintPool[solveManifold.m_frictionIndex].m_appliedImpulse; 988 pt->m_appliedImpulseLateral1 = m_tmpSolverFrictionConstraintPool[solveManifold.m_frictionIndex+1].m_appliedImpulse; 1005 if (infoGlobal.m_solverMode & SOLVER_USE_FRICTION_WARMSTARTING) 1006 { 1007 pt->m_appliedImpulseLateral1 = m_tmpSolverFrictionConstraintPool[solveManifold.m_frictionIndex].m_appliedImpulse; 1008 pt->m_appliedImpulseLateral2 = m_tmpSolverFrictionConstraintPool[solveManifold.m_frictionIndex+1].m_appliedImpulse; 1009 } 989 1010 990 1011 //do a callback here? … … 1221 1242 cpd->m_penetration = cp.getDistance();///btScalar(info.m_numIterations); 1222 1243 cpd->m_friction = cp.m_combinedFriction; 1223 cpd->m_restitution = restitutionCurve(rel_vel, combinedRestitution); 1224 if (cpd->m_restitution <= btScalar(0.)) 1225 { 1226 cpd->m_restitution = btScalar(0.0); 1227 1228 }; 1244 if (cp.m_lifeTime>info.m_restingContactRestitutionThreshold) 1245 { 1246 cpd->m_restitution = 0.f; 1247 } else 1248 { 1249 cpd->m_restitution = restitutionCurve(rel_vel, combinedRestitution); 1250 if (cpd->m_restitution <= btScalar(0.)) 1251 { 1252 cpd->m_restitution = btScalar(0.0); 1253 }; 1254 } 1229 1255 1230 1256 //restitution and penetration work in same direction so -
code/branches/physics/src/bullet/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h
r2192 r2430 24 24 25 25 26 /// btSequentialImpulseConstraintSolver uses a Propagation Method and Sequentially applies impulses27 /// 28 /// 29 /// 26 ///The btSequentialImpulseConstraintSolver uses a Propagation Method and Sequentially applies impulses 27 ///The approach is the 3D version of Erin Catto's GDC 2006 tutorial. See http://www.gphysics.com 28 ///Although Sequential Impulse is more intuitive, it is mathematically equivalent to Projected Successive Overrelaxation (iterative LCP) 29 ///Applies impulses for combined restitution and penetration recovery and to simulate friction 30 30 class btSequentialImpulseConstraintSolver : public btConstraintSolver 31 31 { … … 42 42 btScalar solveFriction(btRigidBody* body0,btRigidBody* body1, btManifoldPoint& cp, const btContactSolverInfo& info,int iter,btIDebugDraw* debugDrawer); 43 43 void prepareConstraints(btPersistentManifold* manifoldPtr, const btContactSolverInfo& info,btIDebugDraw* debugDrawer); 44 voidaddFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation);44 btSolverConstraint& addFrictionConstraint(const btVector3& normalAxis,int solverBodyIdA,int solverBodyIdB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation); 45 45 46 46 ContactSolverFunc m_contactDispatch[MAX_CONTACT_SOLVER_TYPES][MAX_CONTACT_SOLVER_TYPES]; -
code/branches/physics/src/bullet/BulletDynamics/ConstraintSolver/btSolverBody.h
r2192 r2430 25 25 26 26 27 /// btSolverBody is an internal datastructure for the constraint solver. Only necessary data is packed to increase cache coherence/performance.27 ///The btSolverBody is an internal datastructure for the constraint solver. Only necessary data is packed to increase cache coherence/performance. 28 28 ATTRIBUTE_ALIGNED16 (struct) btSolverBody 29 29 { 30 30 BT_DECLARE_ALIGNED_ALLOCATOR(); 31 31 32 btMatrix3x3 m_worldInvInertiaTensor; 33 32 34 btVector3 m_angularVelocity; 35 btVector3 m_linearVelocity; 36 btVector3 m_centerOfMassPosition; 37 btVector3 m_pushVelocity; 38 btVector3 m_turnVelocity; 39 33 40 float m_angularFactor; 34 41 float m_invMass; 35 42 float m_friction; 36 43 btRigidBody* m_originalBody; 37 btVector3 m_linearVelocity;38 btVector3 m_centerOfMassPosition;39 40 btVector3 m_pushVelocity;41 btVector3 m_turnVelocity;42 44 43 45 -
code/branches/physics/src/bullet/BulletDynamics/Dynamics/Bullet-C-API.cpp
r2192 r2430 39 39 #include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h" 40 40 #include "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h" 41 #include "BulletCollision/NarrowPhaseCollision/btGjkEpa .h"41 #include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h" 42 42 #include "BulletCollision/CollisionShapes/btMinkowskiSumShape.h" 43 43 #include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h" … … 256 256 btAssert(colShape->getShapeType()==CONVEX_HULL_SHAPE_PROXYTYPE); 257 257 btConvexHullShape* convexHullShape = reinterpret_cast<btConvexHullShape*>( cshape); 258 convexHullShape->addPoint(bt Point3(x,y,z));258 convexHullShape->addPoint(btVector3(x,y,z)); 259 259 260 260 } -
code/branches/physics/src/bullet/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp
r2192 r2430 52 52 #include "BulletDynamics/Vehicle/btVehicleRaycaster.h" 53 53 #include "BulletDynamics/Vehicle/btWheelInfo.h" 54 //character 55 #include "BulletDynamics/Character/btCharacterControllerInterface.h" 56 54 57 #include "LinearMath/btIDebugDraw.h" 55 58 #include "LinearMath/btQuickprof.h" … … 126 129 void btDiscreteDynamicsWorld::debugDrawWorld() 127 130 { 131 BT_PROFILE("debugDrawWorld"); 128 132 129 133 if (getDebugDrawer() && getDebugDrawer()->getDebugMode() & btIDebugDraw::DBG_DrawContactPoints) … … 151 155 int i; 152 156 153 //todo: iterate over awake simulation islands!154 157 for ( i=0;i<m_collisionObjects.size();i++) 155 158 { … … 180 183 if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawAabb)) 181 184 { 182 bt Point3 minAabb,maxAabb;185 btVector3 minAabb,maxAabb; 183 186 btVector3 colorvec(1,0,0); 184 187 colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb); … … 221 224 void btDiscreteDynamicsWorld::clearForces() 222 225 { 223 // todo: iterate over awake simulation islands!226 ///@todo: iterate over awake simulation islands! 224 227 for ( int i=0;i<m_collisionObjects.size();i++) 225 228 { … … 237 240 void btDiscreteDynamicsWorld::applyGravity() 238 241 { 239 // todo: iterate over awake simulation islands!242 ///@todo: iterate over awake simulation islands! 240 243 for ( int i=0;i<m_collisionObjects.size();i++) 241 244 { … … 251 254 252 255 256 void btDiscreteDynamicsWorld::synchronizeSingleMotionState(btRigidBody* body) 257 { 258 btAssert(body); 259 260 if (body->getMotionState() && !body->isStaticOrKinematicObject()) 261 { 262 //we need to call the update at least once, even for sleeping objects 263 //otherwise the 'graphics' transform never updates properly 264 ///@todo: add 'dirty' flag 265 //if (body->getActivationState() != ISLAND_SLEEPING) 266 { 267 btTransform interpolatedTransform; 268 btTransformUtil::integrateTransform(body->getInterpolationWorldTransform(), 269 body->getInterpolationLinearVelocity(),body->getInterpolationAngularVelocity(),m_localTime*body->getHitFraction(),interpolatedTransform); 270 body->getMotionState()->setWorldTransform(interpolatedTransform); 271 } 272 } 273 } 274 253 275 254 276 void btDiscreteDynamicsWorld::synchronizeMotionStates() 255 277 { 278 BT_PROFILE("synchronizeMotionStates"); 256 279 { 257 280 //todo: iterate over awake simulation islands! … … 261 284 262 285 btRigidBody* body = btRigidBody::upcast(colObj); 263 if (body && body->getMotionState() && !body->isStaticOrKinematicObject()) 264 { 265 //we need to call the update at least once, even for sleeping objects 266 //otherwise the 'graphics' transform never updates properly 267 //so todo: add 'dirty' flag 268 //if (body->getActivationState() != ISLAND_SLEEPING) 269 { 270 btTransform interpolatedTransform; 271 btTransformUtil::integrateTransform(body->getInterpolationWorldTransform(), 272 body->getInterpolationLinearVelocity(),body->getInterpolationAngularVelocity(),m_localTime*body->getHitFraction(),interpolatedTransform); 273 body->getMotionState()->setWorldTransform(interpolatedTransform); 274 } 275 } 286 if (body) 287 synchronizeSingleMotionState(body); 276 288 } 277 289 } … … 393 405 ///update vehicle simulation 394 406 updateVehicles(timeStep); 395 407 408 updateCharacters(timeStep); 396 409 397 410 updateActivationState( timeStep ); … … 469 482 } 470 483 484 void btDiscreteDynamicsWorld::updateCharacters(btScalar timeStep) 485 { 486 BT_PROFILE("updateCharacters"); 487 488 for ( int i=0;i<m_characters.size();i++) 489 { 490 btCharacterControllerInterface* character = m_characters[i]; 491 character->preStep (this); 492 character->playerStep (this,timeStep); 493 } 494 } 495 496 497 471 498 void btDiscreteDynamicsWorld::updateActivationState(btScalar timeStep) 472 499 { … … 532 559 m_vehicles.remove(vehicle); 533 560 } 561 562 void btDiscreteDynamicsWorld::addCharacter(btCharacterControllerInterface* character) 563 { 564 m_characters.push_back(character); 565 } 566 567 void btDiscreteDynamicsWorld::removeCharacter(btCharacterControllerInterface* character) 568 { 569 m_characters.remove(character); 570 } 571 534 572 535 573 SIMD_FORCE_INLINE int btGetConstraintIslandId(const btTypedConstraint* lhs) … … 665 703 666 704 /// solve all the constraints for this island 667 m_islandManager->buildAndProcessIslands(getCollisionWorld()->getDispatcher(),getCollisionWorld() ->getCollisionObjectArray(),&solverCallback);705 m_islandManager->buildAndProcessIslands(getCollisionWorld()->getDispatcher(),getCollisionWorld(),&solverCallback); 668 706 669 707 m_constraintSolver->allSolved(solverInfo, m_debugDrawer, m_stackAlloc); … … 730 768 { 731 769 if (convexResult.m_hitCollisionObject == m_me) 732 return 1.0; 770 return 1.0f; 771 772 //ignore result if there is no contact response 773 if(!convexResult.m_hitCollisionObject->hasContactResponse()) 774 return 1.0f; 733 775 734 776 btVector3 linVelA,linVelB; … … 751 793 752 794 ///don't do CCD when the collision filters are not matching 753 if (! btCollisionWorld::ClosestConvexResultCallback::needsCollision(proxy0))795 if (!ClosestConvexResultCallback::needsCollision(proxy0)) 754 796 return false; 755 797 … … 808 850 btConvexShape* convexShape = static_cast<btConvexShape*>(body->getCollisionShape()); 809 851 btSphereShape tmpSphere(body->getCcdSweptSphereRadius());//btConvexShape* convexShape = static_cast<btConvexShape*>(body->getCollisionShape()); 852 853 sweepResults.m_collisionFilterGroup = body->getBroadphaseProxy()->m_collisionFilterGroup; 854 sweepResults.m_collisionFilterMask = body->getBroadphaseProxy()->m_collisionFilterMask; 855 810 856 convexSweepTest(&tmpSphere,body->getWorldTransform(),predictedTrans,sweepResults); 811 857 if (sweepResults.hasHit() && (sweepResults.m_closestHitFraction < 1.f)) … … 827 873 828 874 875 876 829 877 void btDiscreteDynamicsWorld::predictUnconstraintMotion(btScalar timeStep) 830 878 { … … 838 886 if (!body->isStaticOrKinematicObject()) 839 887 { 840 if (body->isActive()) 841 { 842 body->integrateVelocities( timeStep); 843 //damping 844 body->applyDamping(timeStep); 845 846 body->predictIntegratedTransform(timeStep,body->getInterpolationWorldTransform()); 847 } 888 889 body->integrateVelocities( timeStep); 890 //damping 891 body->applyDamping(timeStep); 892 893 body->predictIntegratedTransform(timeStep,body->getInterpolationWorldTransform()); 848 894 } 849 895 } … … 1097 1143 btConcaveShape* concaveMesh = (btConcaveShape*) shape; 1098 1144 1099 // todo pass camera, for some culling1145 ///@todo pass camera, for some culling? no -> we are not a graphics lib 1100 1146 btVector3 aabbMax(btScalar(1e30),btScalar(1e30),btScalar(1e30)); 1101 1147 btVector3 aabbMin(btScalar(-1e30),btScalar(-1e30),btScalar(-1e30)); … … 1126 1172 for (i=0;i<polyshape->getNumEdges();i++) 1127 1173 { 1128 bt Point3 a,b;1174 btVector3 a,b; 1129 1175 polyshape->getEdge(i,a,b); 1130 1176 btVector3 wa = worldTransform * a; -
code/branches/physics/src/bullet/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h
r2192 r2430 27 27 28 28 class btRaycastVehicle; 29 class btCharacterControllerInterface; 29 30 class btIDebugDraw; 30 31 #include "LinearMath/btAlignedObjectArray.h" … … 43 44 btAlignedObjectArray<btTypedConstraint*> m_constraints; 44 45 45 46 46 btVector3 m_gravity; 47 47 … … 55 55 56 56 btAlignedObjectArray<btRaycastVehicle*> m_vehicles; 57 58 btAlignedObjectArray<btCharacterControllerInterface*> m_characters; 59 57 60 58 61 int m_profileTimings; … … 62 65 virtual void integrateTransforms(btScalar timeStep); 63 66 64 v oid calculateSimulationIslands();67 virtual void calculateSimulationIslands(); 65 68 66 v oid solveConstraints(btContactSolverInfo& solverInfo);69 virtual void solveConstraints(btContactSolverInfo& solverInfo); 67 70 68 71 void updateActivationState(btScalar timeStep); … … 70 73 void updateVehicles(btScalar timeStep); 71 74 75 void updateCharacters(btScalar timeStep); 76 72 77 void startProfiling(btScalar timeStep); 73 78 74 79 virtual void internalSingleStepSimulation( btScalar timeStep); 75 80 76 void synchronizeMotionStates();77 81 78 v oid saveKinematicState(btScalar timeStep);82 virtual void saveKinematicState(btScalar timeStep); 79 83 80 84 void debugDrawSphere(btScalar radius, const btTransform& transform, const btVector3& color); 85 81 86 82 87 public: … … 92 97 93 98 94 v oid addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies=false);99 virtual void synchronizeMotionStates(); 95 100 96 void removeConstraint(btTypedConstraint* constraint); 101 ///this can be useful to synchronize a single rigid body -> graphics object 102 void synchronizeSingleMotionState(btRigidBody* body); 97 103 98 v oid addVehicle(btRaycastVehicle* vehicle);104 virtual void addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies=false); 99 105 100 void removeVehicle(btRaycastVehicle* vehicle); 106 virtual void removeConstraint(btTypedConstraint* constraint); 107 108 virtual void addVehicle(btRaycastVehicle* vehicle); 109 110 virtual void removeVehicle(btRaycastVehicle* vehicle); 111 112 virtual void addCharacter(btCharacterControllerInterface* character); 113 114 virtual void removeCharacter(btCharacterControllerInterface* character); 115 101 116 102 117 btSimulationIslandManager* getSimulationIslandManager() … … 114 129 return this; 115 130 } 116 117 131 118 132 virtual void setGravity(const btVector3& gravity); … … 153 167 virtual void setNumTasks(int numTasks) 154 168 { 169 (void) numTasks; 155 170 } 156 171 -
code/branches/physics/src/bullet/BulletDynamics/Dynamics/btDynamicsWorld.h
r2192 r2430 24 24 class btConstraintSolver; 25 25 class btDynamicsWorld; 26 class btCharacterControllerInterface; 26 27 27 28 /// Type for the callback for each tick … … 76 77 virtual void removeVehicle(btRaycastVehicle* vehicle) {(void)vehicle;} 77 78 79 virtual void addCharacter(btCharacterControllerInterface* character) {(void)character;} 80 81 virtual void removeCharacter(btCharacterControllerInterface* character) {(void)character;} 82 83 78 84 //once a rigidbody is added to the dynamics world, it will get this gravity assigned 79 85 //existing rigidbodies in the world get gravity assigned too, during this method 80 86 virtual void setGravity(const btVector3& gravity) = 0; 81 87 virtual btVector3 getGravity () const = 0; 88 89 virtual void synchronizeMotionStates() = 0; 82 90 83 91 virtual void addRigidBody(btRigidBody* body) = 0; -
code/branches/physics/src/bullet/BulletDynamics/Dynamics/btRigidBody.h
r2192 r2430 18 18 19 19 #include "LinearMath/btAlignedObjectArray.h" 20 #include "LinearMath/btPoint3.h"21 20 #include "LinearMath/btTransform.h" 22 21 #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" … … 32 31 33 32 34 /// btRigidBody is the main class for rigid body objects. It is derived from btCollisionObject, so it keeps a pointer to a btCollisionShape.33 ///The btRigidBody is the main class for rigid body objects. It is derived from btCollisionObject, so it keeps a pointer to a btCollisionShape. 35 34 ///It is recommended for performance and memory use to share btCollisionShape objects whenever possible. 36 35 ///There are 3 types of rigid bodies: … … 76 75 77 76 78 /// btRigidBodyConstructionInfoprovides information to create a rigid body. Setting mass to zero creates a fixed (non-dynamic) rigid body.77 ///The btRigidBodyConstructionInfo structure provides information to create a rigid body. Setting mass to zero creates a fixed (non-dynamic) rigid body. 79 78 ///For dynamic objects, you can use the collision shape to approximate the local inertia tensor, otherwise use the zero vector (default argument) 80 79 ///You can use the motion state to synchronize the world transform between physics and graphics objects. … … 304 303 void updateInertiaTensor(); 305 304 306 const bt Point3& getCenterOfMassPosition() const {305 const btVector3& getCenterOfMassPosition() const { 307 306 return m_worldTransform.getOrigin(); 308 307 } … … 322 321 inline void setLinearVelocity(const btVector3& lin_vel) 323 322 { 324 assert (m_collisionFlags != btCollisionObject::CF_STATIC_OBJECT);325 323 m_linearVelocity = lin_vel; 326 324 } 327 325 328 inline void setAngularVelocity(const btVector3& ang_vel) { 329 assert (m_collisionFlags != btCollisionObject::CF_STATIC_OBJECT); 330 { 331 m_angularVelocity = ang_vel; 332 } 326 inline void setAngularVelocity(const btVector3& ang_vel) 327 { 328 m_angularVelocity = ang_vel; 333 329 } 334 330 … … 354 350 355 351 356 SIMD_FORCE_INLINE btScalar computeImpulseDenominator(const bt Point3& pos, const btVector3& normal) const352 SIMD_FORCE_INLINE btScalar computeImpulseDenominator(const btVector3& pos, const btVector3& normal) const 357 353 { 358 354 btVector3 r0 = pos - getCenterOfMassPosition(); -
code/branches/physics/src/bullet/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp
r2192 r2430 98 98 void btSimpleDynamicsWorld::clearForces() 99 99 { 100 // todo: iterate over awake simulation islands!100 ///@todo: iterate over awake simulation islands! 101 101 for ( int i=0;i<m_collisionObjects.size();i++) 102 102 { … … 157 157 if (body->isActive() && (!body->isStaticObject())) 158 158 { 159 bt Point3 minAabb,maxAabb;159 btVector3 minAabb,maxAabb; 160 160 colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb); 161 161 btBroadphaseInterface* bp = getBroadphase(); … … 211 211 void btSimpleDynamicsWorld::synchronizeMotionStates() 212 212 { 213 // todo: iterate over awake simulation islands!213 ///@todo: iterate over awake simulation islands! 214 214 for ( int i=0;i<m_collisionObjects.size();i++) 215 215 { -
code/branches/physics/src/bullet/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h
r2192 r2430 23 23 class btConstraintSolver; 24 24 25 /// btSimpleDynamicsWorld serves as unit-test and to verify more complicated and optimized dynamics worlds.25 ///The btSimpleDynamicsWorld serves as unit-test and to verify more complicated and optimized dynamics worlds. 26 26 ///Please use btDiscreteDynamicsWorld instead (or btContinuousDynamicsWorld once it is finished). 27 27 class btSimpleDynamicsWorld : public btDynamicsWorld … … 61 61 virtual void updateAabbs(); 62 62 63 v oid synchronizeMotionStates();63 virtual void synchronizeMotionStates(); 64 64 65 65 virtual void setConstraintSolver(btConstraintSolver* solver); -
code/branches/physics/src/bullet/BulletDynamics/Vehicle/btRaycastVehicle.cpp
r2192 r2430 189 189 wheel.m_raycastInfo.m_isInContact = true; 190 190 191 wheel.m_raycastInfo.m_groundObject = &s_fixedObject;// todo for driving on dynamic/movable objects!;191 wheel.m_raycastInfo.m_groundObject = &s_fixedObject;///@todo for driving on dynamic/movable objects!; 192 192 //wheel.m_raycastInfo.m_groundObject = object; 193 193 … … 692 692 btVector3 sideImp = m_axle[wheel] * m_sideImpulse[wheel]; 693 693 694 rel_pos[ 2] *= wheelInfo.m_rollInfluence;694 rel_pos[m_indexForwardAxis] *= wheelInfo.m_rollInfluence; 695 695 m_chassisBody->applyImpulse(sideImp,rel_pos); 696 696
Note: See TracChangeset
for help on using the changeset viewer.