Bullet Collision Detection & Physics Library
Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
btDiscreteDynamicsWorldMt Class Reference

btDiscreteDynamicsWorldMt – a version of DiscreteDynamicsWorld with some minor changes to support solving simulation islands on multiple threads. More...

#include <btDiscreteDynamicsWorldMt.h>

Inheritance diagram for btDiscreteDynamicsWorldMt:
Inheritance graph
[legend]
Collaboration diagram for btDiscreteDynamicsWorldMt:
Collaboration graph
[legend]

Classes

struct  UpdaterCreatePredictiveContacts
 
struct  UpdaterIntegrateTransforms
 

Public Member Functions

 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btDiscreteDynamicsWorldMt (btDispatcher *dispatcher, btBroadphaseInterface *pairCache, btConstraintSolverPoolMt *constraintSolver, btConstraintSolver *constraintSolverMt, btCollisionConfiguration *collisionConfiguration)
 btDiscreteDynamicsWorldMt More...
 
virtual ~btDiscreteDynamicsWorldMt ()
 
virtual int stepSimulation (btScalar timeStep, int maxSubSteps, btScalar fixedTimeStep) BT_OVERRIDE
 if maxSubSteps > 0, it will interpolate motion between fixedTimeStep's More...
 
- Public Member Functions inherited from btDiscreteDynamicsWorld
 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btDiscreteDynamicsWorld (btDispatcher *dispatcher, btBroadphaseInterface *pairCache, btConstraintSolver *constraintSolver, btCollisionConfiguration *collisionConfiguration)
 this btDiscreteDynamicsWorld constructor gets created objects from the user, and will not delete those More...
 
virtual ~btDiscreteDynamicsWorld ()
 
virtual void synchronizeMotionStates ()
 
void synchronizeSingleMotionState (btRigidBody *body)
 this can be useful to synchronize a single rigid body -> graphics object More...
 
virtual void addConstraint (btTypedConstraint *constraint, bool disableCollisionsBetweenLinkedBodies=false)
 
virtual void removeConstraint (btTypedConstraint *constraint)
 
virtual void addAction (btActionInterface *)
 
virtual void removeAction (btActionInterface *)
 
btSimulationIslandManagergetSimulationIslandManager ()
 
const btSimulationIslandManagergetSimulationIslandManager () const
 
btCollisionWorldgetCollisionWorld ()
 
virtual void setGravity (const btVector3 &gravity)
 
virtual btVector3 getGravity () const
 
virtual void addCollisionObject (btCollisionObject *collisionObject, int collisionFilterGroup=btBroadphaseProxy::StaticFilter, int collisionFilterMask=btBroadphaseProxy::AllFilter^btBroadphaseProxy::StaticFilter)
 
virtual void addRigidBody (btRigidBody *body)
 
virtual void addRigidBody (btRigidBody *body, int group, int mask)
 
virtual void removeRigidBody (btRigidBody *body)
 
virtual void removeCollisionObject (btCollisionObject *collisionObject)
 removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btCollisionWorld::removeCollisionObject More...
 
virtual void debugDrawConstraint (btTypedConstraint *constraint)
 
virtual void debugDrawWorld ()
 
virtual void setConstraintSolver (btConstraintSolver *solver)
 
virtual btConstraintSolvergetConstraintSolver ()
 
virtual int getNumConstraints () const
 
virtual btTypedConstraintgetConstraint (int index)
 
virtual const btTypedConstraintgetConstraint (int index) const
 
virtual btDynamicsWorldType getWorldType () const
 
virtual void clearForces ()
 the forces on each rigidbody is accumulating together with gravity. clear this after each timestep. More...
 
virtual void applyGravity ()
 apply gravity, call this once per timestep More...
 
virtual void setNumTasks (int numTasks)
 
virtual void updateVehicles (btScalar timeStep)
 obsolete, use updateActions instead More...
 
virtual void addVehicle (btActionInterface *vehicle)
 obsolete, use addAction instead More...
 
virtual void removeVehicle (btActionInterface *vehicle)
 obsolete, use removeAction instead More...
 
virtual void addCharacter (btActionInterface *character)
 obsolete, use addAction instead More...
 
virtual void removeCharacter (btActionInterface *character)
 obsolete, use removeAction instead More...
 
void setSynchronizeAllMotionStates (bool synchronizeAll)
 
bool getSynchronizeAllMotionStates () const
 
void setApplySpeculativeContactRestitution (bool enable)
 
bool getApplySpeculativeContactRestitution () const
 
virtual void serialize (btSerializer *serializer)
 Preliminary serialization test for Bullet 2.76. Loading those files requires a separate parser (see Bullet/Demos/SerializeDemo) More...
 
void setLatencyMotionStateInterpolation (bool latencyInterpolation)
 Interpolate motion state between previous and current transform, instead of current and next transform. More...
 
bool getLatencyMotionStateInterpolation () const
 
- Public Member Functions inherited from btDynamicsWorld
 btDynamicsWorld (btDispatcher *dispatcher, btBroadphaseInterface *broadphase, btCollisionConfiguration *collisionConfiguration)
 
virtual ~btDynamicsWorld ()
 
void setInternalTickCallback (btInternalTickCallback cb, void *worldUserInfo=0, bool isPreTick=false)
 Set the callback for when an internal tick (simulation substep) happens, optional user info. More...
 
void setWorldUserInfo (void *worldUserInfo)
 
void * getWorldUserInfo () const
 
btContactSolverInfogetSolverInfo ()
 
const btContactSolverInfogetSolverInfo () const
 
- Public Member Functions inherited from btCollisionWorld
 btCollisionWorld (btDispatcher *dispatcher, btBroadphaseInterface *broadphasePairCache, btCollisionConfiguration *collisionConfiguration)
 for debug drawing More...
 
virtual ~btCollisionWorld ()
 
void setBroadphase (btBroadphaseInterface *pairCache)
 
const btBroadphaseInterfacegetBroadphase () const
 
btBroadphaseInterfacegetBroadphase ()
 
btOverlappingPairCachegetPairCache ()
 
btDispatchergetDispatcher ()
 
const btDispatchergetDispatcher () const
 
void updateSingleAabb (btCollisionObject *colObj)
 
virtual void updateAabbs ()
 
virtual void computeOverlappingPairs ()
 the computeOverlappingPairs is usually already called by performDiscreteCollisionDetection (or stepSimulation) it can be useful to use if you perform ray tests without collision detection/simulation More...
 
virtual void setDebugDrawer (btIDebugDraw *debugDrawer)
 
virtual btIDebugDrawgetDebugDrawer ()
 
virtual void debugDrawObject (const btTransform &worldTransform, const btCollisionShape *shape, const btVector3 &color)
 
int getNumCollisionObjects () const
 
virtual void rayTest (const btVector3 &rayFromWorld, const btVector3 &rayToWorld, RayResultCallback &resultCallback) const
 rayTest performs a raycast on all objects in the btCollisionWorld, and calls the resultCallback This allows for several queries: first hit, all hits, any hit, dependent on the value returned by the callback. More...
 
void convexSweepTest (const btConvexShape *castShape, const btTransform &from, const btTransform &to, ConvexResultCallback &resultCallback, btScalar allowedCcdPenetration=btScalar(0.)) const
 convexTest performs a swept convex cast on all objects in the btCollisionWorld, and calls the resultCallback This allows for several queries: first hit, all hits, any hit, dependent on the value return by the callback. More...
 
void contactTest (btCollisionObject *colObj, ContactResultCallback &resultCallback)
 contactTest performs a discrete collision test between colObj against all objects in the btCollisionWorld, and calls the resultCallback. More...
 
void contactPairTest (btCollisionObject *colObjA, btCollisionObject *colObjB, ContactResultCallback &resultCallback)
 contactTest performs a discrete collision test between two collision objects and calls the resultCallback if overlap if detected. More...
 
virtual void refreshBroadphaseProxy (btCollisionObject *collisionObject)
 
btCollisionObjectArraygetCollisionObjectArray ()
 
const btCollisionObjectArraygetCollisionObjectArray () const
 
virtual void performDiscreteCollisionDetection ()
 
btDispatcherInfogetDispatchInfo ()
 
const btDispatcherInfogetDispatchInfo () const
 
bool getForceUpdateAllAabbs () const
 
void setForceUpdateAllAabbs (bool forceUpdateAllAabbs)
 

Protected Member Functions

virtual void solveConstraints (btContactSolverInfo &solverInfo) BT_OVERRIDE
 
virtual void predictUnconstraintMotion (btScalar timeStep) BT_OVERRIDE
 
virtual void createPredictiveContacts (btScalar timeStep) BT_OVERRIDE
 
virtual void integrateTransforms (btScalar timeStep) BT_OVERRIDE
 
- Protected Member Functions inherited from btDiscreteDynamicsWorld
void integrateTransformsInternal (btRigidBody **bodies, int numBodies, btScalar timeStep)
 
virtual void calculateSimulationIslands ()
 
virtual void updateActivationState (btScalar timeStep)
 
void updateActions (btScalar timeStep)
 
void startProfiling (btScalar timeStep)
 
virtual void internalSingleStepSimulation (btScalar timeStep)
 
void releasePredictiveContacts ()
 
void createPredictiveContactsInternal (btRigidBody **bodies, int numBodies, btScalar timeStep)
 
virtual void saveKinematicState (btScalar timeStep)
 
void serializeRigidBodies (btSerializer *serializer)
 
void serializeDynamicsWorldInfo (btSerializer *serializer)
 
- Protected Member Functions inherited from btCollisionWorld
void serializeCollisionObjects (btSerializer *serializer)
 
void serializeContactManifolds (btSerializer *serializer)
 

Protected Attributes

btConstraintSolverm_constraintSolverMt
 
- Protected Attributes inherited from btDiscreteDynamicsWorld
btAlignedObjectArray< btTypedConstraint * > m_sortedConstraints
 
InplaceSolverIslandCallbackm_solverIslandCallback
 
btConstraintSolverm_constraintSolver
 
btSimulationIslandManagerm_islandManager
 
btAlignedObjectArray< btTypedConstraint * > m_constraints
 
btAlignedObjectArray< btRigidBody * > m_nonStaticRigidBodies
 
btVector3 m_gravity
 
btScalar m_localTime
 
btScalar m_fixedTimeStep
 
bool m_ownsIslandManager
 
bool m_ownsConstraintSolver
 
bool m_synchronizeAllMotionStates
 
bool m_applySpeculativeContactRestitution
 
btAlignedObjectArray< btActionInterface * > m_actions
 
int m_profileTimings
 
bool m_latencyMotionStateInterpolation
 
btAlignedObjectArray< btPersistentManifold * > m_predictiveManifolds
 
btSpinMutex m_predictiveManifoldsMutex
 
- Protected Attributes inherited from btDynamicsWorld
btInternalTickCallback m_internalTickCallback
 
btInternalTickCallback m_internalPreTickCallback
 
void * m_worldUserInfo
 
btContactSolverInfo m_solverInfo
 
- Protected Attributes inherited from btCollisionWorld
btAlignedObjectArray< btCollisionObject * > m_collisionObjects
 
btDispatcherm_dispatcher1
 
btDispatcherInfo m_dispatchInfo
 
btBroadphaseInterfacem_broadphasePairCache
 
btIDebugDrawm_debugDrawer
 
bool m_forceUpdateAllAabbs
 m_forceUpdateAllAabbs can be set to false as an optimization to only update active object AABBs it is true by default, because it is error-prone (setting the position of static objects wouldn't update their AABB) More...
 

Additional Inherited Members

- Static Public Member Functions inherited from btCollisionWorld
static void rayTestSingle (const btTransform &rayFromTrans, const btTransform &rayToTrans, btCollisionObject *collisionObject, const btCollisionShape *collisionShape, const btTransform &colObjWorldTransform, RayResultCallback &resultCallback)
 rayTestSingle performs a raycast call and calls the resultCallback. More...
 
static void rayTestSingleInternal (const btTransform &rayFromTrans, const btTransform &rayToTrans, const btCollisionObjectWrapper *collisionObjectWrap, RayResultCallback &resultCallback)
 
static void objectQuerySingle (const btConvexShape *castShape, const btTransform &rayFromTrans, const btTransform &rayToTrans, btCollisionObject *collisionObject, const btCollisionShape *collisionShape, const btTransform &colObjWorldTransform, ConvexResultCallback &resultCallback, btScalar allowedPenetration)
 objectQuerySingle performs a collision detection query and calls the resultCallback. It is used internally by rayTest. More...
 
static void objectQuerySingleInternal (const btConvexShape *castShape, const btTransform &convexFromTrans, const btTransform &convexToTrans, const btCollisionObjectWrapper *colObjWrap, ConvexResultCallback &resultCallback, btScalar allowedPenetration)
 

Detailed Description

btDiscreteDynamicsWorldMt – a version of DiscreteDynamicsWorld with some minor changes to support solving simulation islands on multiple threads.

Should function exactly like btDiscreteDynamicsWorld. Also 3 methods that iterate over all of the rigidbodies can run in parallel:

Definition at line 87 of file btDiscreteDynamicsWorldMt.h.

Constructor & Destructor Documentation

btDiscreteDynamicsWorldMt::btDiscreteDynamicsWorldMt ( btDispatcher dispatcher,
btBroadphaseInterface pairCache,
btConstraintSolverPoolMt constraintSolver,
btConstraintSolver constraintSolverMt,
btCollisionConfiguration collisionConfiguration 
)
btDiscreteDynamicsWorldMt::~btDiscreteDynamicsWorldMt ( )
virtual

Definition at line 178 of file btDiscreteDynamicsWorldMt.cpp.

Member Function Documentation

btDiscreteDynamicsWorldMt::BT_DECLARE_ALIGNED_ALLOCATOR ( )
void btDiscreteDynamicsWorldMt::createPredictiveContacts ( btScalar  timeStep)
protectedvirtual

Reimplemented from btDiscreteDynamicsWorld.

Definition at line 238 of file btDiscreteDynamicsWorldMt.cpp.

void btDiscreteDynamicsWorldMt::integrateTransforms ( btScalar  timeStep)
protectedvirtual

Reimplemented from btDiscreteDynamicsWorld.

Definition at line 254 of file btDiscreteDynamicsWorldMt.cpp.

void btDiscreteDynamicsWorldMt::predictUnconstraintMotion ( btScalar  timeStep)
protectedvirtual

Reimplemented from btDiscreteDynamicsWorld.

Definition at line 224 of file btDiscreteDynamicsWorldMt.cpp.

void btDiscreteDynamicsWorldMt::solveConstraints ( btContactSolverInfo solverInfo)
protectedvirtual

solve all the constraints for this island

Reimplemented from btDiscreteDynamicsWorld.

Definition at line 183 of file btDiscreteDynamicsWorldMt.cpp.

int btDiscreteDynamicsWorldMt::stepSimulation ( btScalar  timeStep,
int  maxSubSteps,
btScalar  fixedTimeStep 
)
virtual

if maxSubSteps > 0, it will interpolate motion between fixedTimeStep's

Reimplemented from btDiscreteDynamicsWorld.

Definition at line 269 of file btDiscreteDynamicsWorldMt.cpp.

Member Data Documentation

btConstraintSolver* btDiscreteDynamicsWorldMt::m_constraintSolverMt
protected

Definition at line 90 of file btDiscreteDynamicsWorldMt.h.


The documentation for this class was generated from the following files: