btSequentialImpulseConstraintSolver.h
Go to the documentation of this file.
00001 /*
00002 Bullet Continuous Collision Detection and Physics Library
00003 Copyright (c) 2003-2006 Erwin Coumans  http://continuousphysics.com/Bullet/
00004 
00005 This software is provided 'as-is', without any express or implied warranty.
00006 In no event will the authors be held liable for any damages arising from the use of this software.
00007 Permission is granted to anyone to use this software for any purpose, 
00008 including commercial applications, and to alter it and redistribute it freely, 
00009 subject to the following restrictions:
00010 
00011 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.
00012 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
00013 3. This notice may not be removed or altered from any source distribution.
00014 */
00015 
00016 #ifndef BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_H
00017 #define BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_H
00018 
00019 #include "btConstraintSolver.h"
00020 class btIDebugDraw;
00021 #include "btContactConstraint.h"
00022 #include "btSolverBody.h"
00023 #include "btSolverConstraint.h"
00024 #include "btTypedConstraint.h"
00025 #include "BulletCollision/NarrowPhaseCollision/btManifoldPoint.h"
00026 
00028 class btSequentialImpulseConstraintSolver : public btConstraintSolver
00029 {
00030 protected:
00031 
00032         btConstraintArray                       m_tmpSolverContactConstraintPool;
00033         btConstraintArray                       m_tmpSolverNonContactConstraintPool;
00034         btConstraintArray                       m_tmpSolverContactFrictionConstraintPool;
00035         btAlignedObjectArray<int>       m_orderTmpConstraintPool;
00036         btAlignedObjectArray<int>       m_orderFrictionConstraintPool;
00037         btAlignedObjectArray<btTypedConstraint::btConstraintInfo1> m_tmpConstraintSizesPool;
00038 
00039         void setupFrictionConstraint(   btSolverConstraint& solverConstraint, const btVector3& normalAxis,btRigidBody* solverBodyA,btRigidBody* solverBodyIdB,
00040                                                                         btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,
00041                                                                         btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, 
00042                                                                         btScalar desiredVelocity=0., btScalar cfmSlip=0.);
00043 
00044         btSolverConstraint&     addFrictionConstraint(const btVector3& normalAxis,btRigidBody* solverBodyA,btRigidBody* solverBodyB,int frictionIndex,btManifoldPoint& cp,const btVector3& rel_pos1,const btVector3& rel_pos2,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity=0., btScalar cfmSlip=0.);
00045         
00046         void setupContactConstraint(btSolverConstraint& solverConstraint, btCollisionObject* colObj0, btCollisionObject* colObj1, btManifoldPoint& cp, 
00047                                                                 const btContactSolverInfo& infoGlobal, btVector3& vel, btScalar& rel_vel, btScalar& relaxation, 
00048                                                                 btVector3& rel_pos1, btVector3& rel_pos2);
00049 
00050         void setFrictionConstraintImpulse( btSolverConstraint& solverConstraint, btRigidBody* rb0, btRigidBody* rb1, 
00051                                                                                  btManifoldPoint& cp, const btContactSolverInfo& infoGlobal);
00052 
00054         unsigned long   m_btSeed2;
00055 
00056 //      void    initSolverBody(btSolverBody* solverBody, btCollisionObject* collisionObject);
00057         btScalar restitutionCurve(btScalar rel_vel, btScalar restitution);
00058 
00059         void    convertContact(btPersistentManifold* manifold,const btContactSolverInfo& infoGlobal);
00060 
00061 
00062         void    resolveSplitPenetrationSIMD(
00063         btRigidBody& body1,
00064         btRigidBody& body2,
00065         const btSolverConstraint& contactConstraint);
00066 
00067         void    resolveSplitPenetrationImpulseCacheFriendly(
00068         btRigidBody& body1,
00069         btRigidBody& body2,
00070         const btSolverConstraint& contactConstraint);
00071 
00072         //internal method
00073         int     getOrInitSolverBody(btCollisionObject& body);
00074 
00075         void    resolveSingleConstraintRowGeneric(btRigidBody& body1,btRigidBody& body2,const btSolverConstraint& contactConstraint);
00076 
00077         void    resolveSingleConstraintRowGenericSIMD(btRigidBody& body1,btRigidBody& body2,const btSolverConstraint& contactConstraint);
00078         
00079         void    resolveSingleConstraintRowLowerLimit(btRigidBody& body1,btRigidBody& body2,const btSolverConstraint& contactConstraint);
00080         
00081         void    resolveSingleConstraintRowLowerLimitSIMD(btRigidBody& body1,btRigidBody& body2,const btSolverConstraint& contactConstraint);
00082                 
00083 protected:
00084         static btRigidBody& getFixedBody();
00085         
00086         virtual void solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc);
00087         virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject** bodies ,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc);
00088         btScalar solveSingleIteration(int iteration, btCollisionObject** bodies ,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc);
00089 
00090         virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc);
00091         virtual btScalar solveGroupCacheFriendlyIterations(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer,btStackAlloc* stackAlloc);
00092 
00093 
00094 public:
00095 
00096         
00097         btSequentialImpulseConstraintSolver();
00098         virtual ~btSequentialImpulseConstraintSolver();
00099 
00100         virtual btScalar solveGroup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifold,int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btStackAlloc* stackAlloc,btDispatcher* dispatcher);
00101         
00102 
00103         
00105         virtual void    reset();
00106         
00107         unsigned long btRand2();
00108 
00109         int btRandInt2 (int n);
00110 
00111         void    setRandSeed(unsigned long seed)
00112         {
00113                 m_btSeed2 = seed;
00114         }
00115         unsigned long   getRandSeed() const
00116         {
00117                 return m_btSeed2;
00118         }
00119 
00120 };
00121 
00122 #ifndef BT_PREFER_SIMD
00123 typedef btSequentialImpulseConstraintSolver btSequentialImpulseConstraintSolverPrefered;
00124 #endif
00125 
00126 
00127 #endif //BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_H
00128 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


bullet
Author(s): Erwin Coumans, ROS package maintained by Tully Foote
autogenerated on Wed Oct 31 2012 07:54:31