Bullet Collision Detection & Physics Library
Classes | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
btTypedConstraint Class Referenceabstract

TypedConstraint is the baseclass for Bullet constraints and vehicles. More...

#include <btTypedConstraint.h>

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

Classes

struct  btConstraintInfo1
 
struct  btConstraintInfo2
 

Public Member Functions

 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
virtual ~btTypedConstraint ()
 
 btTypedConstraint (btTypedConstraintType type, btRigidBody &rbA)
 
 btTypedConstraint (btTypedConstraintType type, btRigidBody &rbA, btRigidBody &rbB)
 
int getOverrideNumSolverIterations () const
 
void setOverrideNumSolverIterations (int overideNumIterations)
 override the number of constraint solver iterations used to solve this constraint -1 will use the default number of iterations, as specified in SolverInfo.m_numIterations More...
 
virtual void buildJacobian ()
 internal method used by the constraint solver, don't use them directly More...
 
virtual void setupSolverConstraint (btConstraintArray &ca, int solverBodyA, int solverBodyB, btScalar timeStep)
 internal method used by the constraint solver, don't use them directly More...
 
virtual void getInfo1 (btConstraintInfo1 *info)=0
 internal method used by the constraint solver, don't use them directly More...
 
virtual void getInfo2 (btConstraintInfo2 *info)=0
 internal method used by the constraint solver, don't use them directly More...
 
void internalSetAppliedImpulse (btScalar appliedImpulse)
 internal method used by the constraint solver, don't use them directly More...
 
btScalar internalGetAppliedImpulse ()
 internal method used by the constraint solver, don't use them directly More...
 
btScalar getBreakingImpulseThreshold () const
 
void setBreakingImpulseThreshold (btScalar threshold)
 
bool isEnabled () const
 
void setEnabled (bool enabled)
 
virtual void solveConstraintObsolete (btSolverBody &, btSolverBody &, btScalar)
 internal method used by the constraint solver, don't use them directly More...
 
const btRigidBodygetRigidBodyA () const
 
const btRigidBodygetRigidBodyB () const
 
btRigidBodygetRigidBodyA ()
 
btRigidBodygetRigidBodyB ()
 
int getUserConstraintType () const
 
void setUserConstraintType (int userConstraintType)
 
void setUserConstraintId (int uid)
 
int getUserConstraintId () const
 
void setUserConstraintPtr (void *ptr)
 
void * getUserConstraintPtr ()
 
void setJointFeedback (btJointFeedback *jointFeedback)
 
const btJointFeedbackgetJointFeedback () const
 
btJointFeedbackgetJointFeedback ()
 
int getUid () const
 
bool needsFeedback () const
 
void enableFeedback (bool needsFeedback)
 enableFeedback will allow to read the applied linear and angular impulse use getAppliedImpulse, getAppliedLinearImpulse and getAppliedAngularImpulse to read feedback information More...
 
btScalar getAppliedImpulse () const
 getAppliedImpulse is an estimated total applied impulse. More...
 
btTypedConstraintType getConstraintType () const
 
void setDbgDrawSize (btScalar dbgDrawSize)
 
btScalar getDbgDrawSize ()
 
virtual void setParam (int num, btScalar value, int axis=-1)=0
 override the default global value of a parameter (such as ERP or CFM), optionally provide the axis (0..5). More...
 
virtual btScalar getParam (int num, int axis=-1) const =0
 return the local value of parameter More...
 
virtual int calculateSerializeBufferSize () const
 
virtual const char * serialize (void *dataBuffer, btSerializer *serializer) const
 fills the dataBuffer and returns the struct name (and 0 on failure) More...
 
- Public Member Functions inherited from btTypedObject
 btTypedObject (int objectType)
 
int getObjectType () const
 

Static Public Member Functions

static btRigidBodygetFixedBody ()
 

Protected Member Functions

btScalar getMotorFactor (btScalar pos, btScalar lowLim, btScalar uppLim, btScalar vel, btScalar timeFact)
 internal method used by the constraint solver, don't use them directly More...
 

Protected Attributes

btRigidBodym_rbA
 
btRigidBodym_rbB
 
btScalar m_appliedImpulse
 
btScalar m_dbgDrawSize
 
btJointFeedbackm_jointFeedback
 

Private Member Functions

btTypedConstraintoperator= (btTypedConstraint &other)
 

Private Attributes

int m_userConstraintType
 
union {
   int   m_userConstraintId
 
   void *   m_userConstraintPtr
 
}; 
 
btScalar m_breakingImpulseThreshold
 
bool m_isEnabled
 
bool m_needsFeedback
 
int m_overrideNumSolverIterations
 

Additional Inherited Members

- Public Attributes inherited from btTypedObject
int m_objectType
 

Detailed Description

TypedConstraint is the baseclass for Bullet constraints and vehicles.

Definition at line 78 of file btTypedConstraint.h.

Constructor & Destructor Documentation

virtual btTypedConstraint::~btTypedConstraint ( )
inlinevirtual

Definition at line 116 of file btTypedConstraint.h.

btTypedConstraint::btTypedConstraint ( btTypedConstraintType  type,
btRigidBody rbA 
)

Definition at line 24 of file btTypedConstraint.cpp.

btTypedConstraint::btTypedConstraint ( btTypedConstraintType  type,
btRigidBody rbA,
btRigidBody rbB 
)

Definition at line 41 of file btTypedConstraint.cpp.

Member Function Documentation

btTypedConstraint::BT_DECLARE_ALIGNED_ALLOCATOR ( )
virtual void btTypedConstraint::buildJacobian ( )
inlinevirtual

internal method used by the constraint solver, don't use them directly

Reimplemented in btGeneric6DofConstraint, btGeneric6DofSpring2Constraint, btConeTwistConstraint, btHingeConstraint, btPoint2PointConstraint, and btContactConstraint.

Definition at line 168 of file btTypedConstraint.h.

int btTypedConstraint::calculateSerializeBufferSize ( ) const
inlinevirtual
void btTypedConstraint::enableFeedback ( bool  needsFeedback)
inline

enableFeedback will allow to read the applied linear and angular impulse use getAppliedImpulse, getAppliedLinearImpulse and getAppliedAngularImpulse to read feedback information

Definition at line 298 of file btTypedConstraint.h.

btScalar btTypedConstraint::getAppliedImpulse ( ) const
inline

getAppliedImpulse is an estimated total applied impulse.

This feedback could be used to determine breaking constraints or playing sounds.

Definition at line 305 of file btTypedConstraint.h.

btScalar btTypedConstraint::getBreakingImpulseThreshold ( ) const
inline

Definition at line 197 of file btTypedConstraint.h.

btTypedConstraintType btTypedConstraint::getConstraintType ( ) const
inline

Definition at line 311 of file btTypedConstraint.h.

btScalar btTypedConstraint::getDbgDrawSize ( )
inline

Definition at line 320 of file btTypedConstraint.h.

btRigidBody & btTypedConstraint::getFixedBody ( )
static

Definition at line 148 of file btTypedConstraint.cpp.

virtual void btTypedConstraint::getInfo1 ( btConstraintInfo1 info)
pure virtual
virtual void btTypedConstraint::getInfo2 ( btConstraintInfo2 info)
pure virtual
const btJointFeedback* btTypedConstraint::getJointFeedback ( ) const
inline

Definition at line 275 of file btTypedConstraint.h.

btJointFeedback* btTypedConstraint::getJointFeedback ( )
inline

Definition at line 280 of file btTypedConstraint.h.

btScalar btTypedConstraint::getMotorFactor ( btScalar  pos,
btScalar  lowLim,
btScalar  uppLim,
btScalar  vel,
btScalar  timeFact 
)
protected

internal method used by the constraint solver, don't use them directly

Definition at line 60 of file btTypedConstraint.cpp.

int btTypedConstraint::getOverrideNumSolverIterations ( ) const
inline

Definition at line 155 of file btTypedConstraint.h.

virtual btScalar btTypedConstraint::getParam ( int  num,
int  axis = -1 
) const
pure virtual
const btRigidBody& btTypedConstraint::getRigidBodyA ( ) const
inline

Definition at line 222 of file btTypedConstraint.h.

btRigidBody& btTypedConstraint::getRigidBodyA ( )
inline

Definition at line 231 of file btTypedConstraint.h.

const btRigidBody& btTypedConstraint::getRigidBodyB ( ) const
inline

Definition at line 226 of file btTypedConstraint.h.

btRigidBody& btTypedConstraint::getRigidBodyB ( )
inline

Definition at line 235 of file btTypedConstraint.h.

int btTypedConstraint::getUid ( ) const
inline

Definition at line 286 of file btTypedConstraint.h.

int btTypedConstraint::getUserConstraintId ( ) const
inline

Definition at line 255 of file btTypedConstraint.h.

void* btTypedConstraint::getUserConstraintPtr ( )
inline

Definition at line 265 of file btTypedConstraint.h.

int btTypedConstraint::getUserConstraintType ( ) const
inline

Definition at line 240 of file btTypedConstraint.h.

btScalar btTypedConstraint::internalGetAppliedImpulse ( )
inline

internal method used by the constraint solver, don't use them directly

Definition at line 191 of file btTypedConstraint.h.

void btTypedConstraint::internalSetAppliedImpulse ( btScalar  appliedImpulse)
inline

internal method used by the constraint solver, don't use them directly

Definition at line 186 of file btTypedConstraint.h.

bool btTypedConstraint::isEnabled ( ) const
inline

Definition at line 207 of file btTypedConstraint.h.

bool btTypedConstraint::needsFeedback ( ) const
inline

Definition at line 291 of file btTypedConstraint.h.

btTypedConstraint& btTypedConstraint::operator= ( btTypedConstraint other)
inlineprivate

Definition at line 94 of file btTypedConstraint.h.

const char * btTypedConstraint::serialize ( void *  dataBuffer,
btSerializer serializer 
) const
virtual

fills the dataBuffer and returns the struct name (and 0 on failure)

Reimplemented in btGeneric6DofConstraint, btConeTwistConstraint, btHingeConstraint, btGeneric6DofSpring2Constraint, btSliderConstraint, btPoint2PointConstraint, btGearConstraint, and btGeneric6DofSpringConstraint.

Definition at line 110 of file btTypedConstraint.cpp.

void btTypedConstraint::setBreakingImpulseThreshold ( btScalar  threshold)
inline

Definition at line 202 of file btTypedConstraint.h.

void btTypedConstraint::setDbgDrawSize ( btScalar  dbgDrawSize)
inline

Definition at line 316 of file btTypedConstraint.h.

void btTypedConstraint::setEnabled ( bool  enabled)
inline

Definition at line 212 of file btTypedConstraint.h.

void btTypedConstraint::setJointFeedback ( btJointFeedback jointFeedback)
inline

Definition at line 270 of file btTypedConstraint.h.

void btTypedConstraint::setOverrideNumSolverIterations ( int  overideNumIterations)
inline

override the number of constraint solver iterations used to solve this constraint -1 will use the default number of iterations, as specified in SolverInfo.m_numIterations

Definition at line 162 of file btTypedConstraint.h.

virtual void btTypedConstraint::setParam ( int  num,
btScalar  value,
int  axis = -1 
)
pure virtual

override the default global value of a parameter (such as ERP or CFM), optionally provide the axis (0..5).

If no axis is provided, it uses the default axis for this constraint.

Implemented in btGeneric6DofConstraint, btGeneric6DofSpring2Constraint, btHingeConstraint, btConeTwistConstraint, btSliderConstraint, btPoint2PointConstraint, and btGearConstraint.

virtual void btTypedConstraint::setupSolverConstraint ( btConstraintArray ca,
int  solverBodyA,
int  solverBodyB,
btScalar  timeStep 
)
inlinevirtual

internal method used by the constraint solver, don't use them directly

Definition at line 171 of file btTypedConstraint.h.

void btTypedConstraint::setUserConstraintId ( int  uid)
inline

Definition at line 250 of file btTypedConstraint.h.

void btTypedConstraint::setUserConstraintPtr ( void *  ptr)
inline

Definition at line 260 of file btTypedConstraint.h.

void btTypedConstraint::setUserConstraintType ( int  userConstraintType)
inline

Definition at line 245 of file btTypedConstraint.h.

virtual void btTypedConstraint::solveConstraintObsolete ( btSolverBody ,
btSolverBody ,
btScalar   
)
inlinevirtual

internal method used by the constraint solver, don't use them directly

Reimplemented in btConeTwistConstraint.

Definition at line 219 of file btTypedConstraint.h.

Member Data Documentation

union { ... }
btScalar btTypedConstraint::m_appliedImpulse
protected

Definition at line 104 of file btTypedConstraint.h.

btScalar btTypedConstraint::m_breakingImpulseThreshold
private

Definition at line 88 of file btTypedConstraint.h.

btScalar btTypedConstraint::m_dbgDrawSize
protected

Definition at line 105 of file btTypedConstraint.h.

bool btTypedConstraint::m_isEnabled
private

Definition at line 89 of file btTypedConstraint.h.

btJointFeedback* btTypedConstraint::m_jointFeedback
protected

Definition at line 106 of file btTypedConstraint.h.

bool btTypedConstraint::m_needsFeedback
private

Definition at line 90 of file btTypedConstraint.h.

int btTypedConstraint::m_overrideNumSolverIterations
private

Definition at line 91 of file btTypedConstraint.h.

btRigidBody& btTypedConstraint::m_rbA
protected

Definition at line 102 of file btTypedConstraint.h.

btRigidBody& btTypedConstraint::m_rbB
protected

Definition at line 103 of file btTypedConstraint.h.

int btTypedConstraint::m_userConstraintId

Definition at line 84 of file btTypedConstraint.h.

void* btTypedConstraint::m_userConstraintPtr

Definition at line 85 of file btTypedConstraint.h.

int btTypedConstraint::m_userConstraintType
private

Definition at line 80 of file btTypedConstraint.h.


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