Classes | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
btTypedConstraint Class Reference

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

#include <btTypedConstraint.h>

Inheritance diagram for btTypedConstraint:
Inheritance graph
[legend]

List of all members.

Classes

struct  btConstraintInfo1
struct  btConstraintInfo2

Public Member Functions

 btTypedConstraint (btTypedConstraintType type, btRigidBody &rbA)
 btTypedConstraint (btTypedConstraintType type, btRigidBody &rbA, btRigidBody &rbB)
virtual void buildJacobian ()
 internal method used by the constraint solver, don't use them directly
virtual int calculateSerializeBufferSize () const
void enableFeedback (bool needsFeedback)
btScalar getAppliedImpulse () const
btScalar getBreakingImpulseThreshold () const
btTypedConstraintType getConstraintType () const
btScalar getDbgDrawSize ()
virtual void getInfo1 (btConstraintInfo1 *info)=0
 internal method used by the constraint solver, don't use them directly
virtual void getInfo2 (btConstraintInfo2 *info)=0
 internal method used by the constraint solver, don't use them directly
virtual btScalar getParam (int num, int axis=-1) const =0
 return the local value of parameter
const btRigidBodygetRigidBodyA () const
btRigidBodygetRigidBodyA ()
const btRigidBodygetRigidBodyB () const
btRigidBodygetRigidBodyB ()
int getUid () const
int getUserConstraintId () const
void * getUserConstraintPtr ()
int getUserConstraintType () const
btScalar internalGetAppliedImpulse ()
 internal method used by the constraint solver, don't use them directly
void internalSetAppliedImpulse (btScalar appliedImpulse)
 internal method used by the constraint solver, don't use them directly
bool isEnabled () const
bool needsFeedback () const
virtual const char * serialize (void *dataBuffer, btSerializer *serializer) const
 fills the dataBuffer and returns the struct name (and 0 on failure)
void setBreakingImpulseThreshold (btScalar threshold)
void setDbgDrawSize (btScalar dbgDrawSize)
void setEnabled (bool enabled)
virtual void setParam (int num, btScalar value, int axis=-1)=0
virtual void setupSolverConstraint (btConstraintArray &ca, int solverBodyA, int solverBodyB, btScalar timeStep)
 internal method used by the constraint solver, don't use them directly
void setUserConstraintId (int uid)
void setUserConstraintPtr (void *ptr)
void setUserConstraintType (int userConstraintType)
virtual void solveConstraintObsolete (btRigidBody &, btRigidBody &, btScalar)
 internal method used by the constraint solver, don't use them directly
virtual ~btTypedConstraint ()

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

Static Protected Member Functions

static btRigidBodygetFixedBody ()

Protected Attributes

btScalar m_appliedImpulse
btScalar m_dbgDrawSize
btRigidBodym_rbA
btRigidBodym_rbB

Private Member Functions

btTypedConstraintoperator= (btTypedConstraint &other)

Private Attributes

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

Detailed Description

TypedConstraint is the baseclass for Bullet constraints and vehicles.

Definition at line 55 of file btTypedConstraint.h.


Constructor & Destructor Documentation

virtual btTypedConstraint::~btTypedConstraint ( ) [inline, virtual]

Definition at line 91 of file btTypedConstraint.h.


Member Function Documentation

virtual void btTypedConstraint::buildJacobian ( ) [inline, virtual]

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

Reimplemented in btGeneric6DofConstraint, and btConeTwistConstraint.

Definition at line 134 of file btTypedConstraint.h.

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 248 of file btTypedConstraint.h.

getAppliedImpulse is an estimated total applied impulse. This feedback could be used to determine breaking constraints or playing sounds.

Definition at line 255 of file btTypedConstraint.h.

Definition at line 163 of file btTypedConstraint.h.

Definition at line 261 of file btTypedConstraint.h.

Definition at line 270 of file btTypedConstraint.h.

static btRigidBody& btTypedConstraint::getFixedBody ( ) [static, protected]
virtual void btTypedConstraint::getInfo1 ( btConstraintInfo1 info) [pure virtual]

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

Implemented in btGeneric6DofConstraint, btSliderConstraint, and btConeTwistConstraint.

virtual void btTypedConstraint::getInfo2 ( btConstraintInfo2 info) [pure virtual]

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

Implemented in btGeneric6DofConstraint, btSliderConstraint, btConeTwistConstraint, and btGeneric6DofSpringConstraint.

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

virtual btScalar btTypedConstraint::getParam ( int  num,
int  axis = -1 
) const [pure virtual]

return the local value of parameter

Implemented in btGeneric6DofConstraint, btConeTwistConstraint, and btSliderConstraint.

const btRigidBody& btTypedConstraint::getRigidBodyA ( ) const [inline]

Reimplemented in btSliderConstraint, and btConeTwistConstraint.

Definition at line 188 of file btTypedConstraint.h.

Definition at line 197 of file btTypedConstraint.h.

const btRigidBody& btTypedConstraint::getRigidBodyB ( ) const [inline]

Reimplemented in btSliderConstraint, and btConeTwistConstraint.

Definition at line 192 of file btTypedConstraint.h.

Definition at line 201 of file btTypedConstraint.h.

int btTypedConstraint::getUid ( ) const [inline]

Definition at line 236 of file btTypedConstraint.h.

Definition at line 221 of file btTypedConstraint.h.

Definition at line 231 of file btTypedConstraint.h.

Definition at line 206 of file btTypedConstraint.h.

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

Definition at line 157 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 152 of file btTypedConstraint.h.

bool btTypedConstraint::isEnabled ( ) const [inline]

Definition at line 173 of file btTypedConstraint.h.

bool btTypedConstraint::needsFeedback ( ) const [inline]

Definition at line 241 of file btTypedConstraint.h.

btTypedConstraint& btTypedConstraint::operator= ( btTypedConstraint other) [inline, private]

Definition at line 71 of file btTypedConstraint.h.

virtual 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, btSliderConstraint, and btGeneric6DofSpringConstraint.

Definition at line 168 of file btTypedConstraint.h.

void btTypedConstraint::setDbgDrawSize ( btScalar  dbgDrawSize) [inline]

Definition at line 266 of file btTypedConstraint.h.

void btTypedConstraint::setEnabled ( bool  enabled) [inline]

Definition at line 178 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, btSliderConstraint, and btConeTwistConstraint.

virtual void btTypedConstraint::setupSolverConstraint ( btConstraintArray ca,
int  solverBodyA,
int  solverBodyB,
btScalar  timeStep 
) [inline, virtual]

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

Definition at line 137 of file btTypedConstraint.h.

void btTypedConstraint::setUserConstraintId ( int  uid) [inline]

Definition at line 216 of file btTypedConstraint.h.

void btTypedConstraint::setUserConstraintPtr ( void *  ptr) [inline]

Definition at line 226 of file btTypedConstraint.h.

void btTypedConstraint::setUserConstraintType ( int  userConstraintType) [inline]

Definition at line 211 of file btTypedConstraint.h.

virtual void btTypedConstraint::solveConstraintObsolete ( btRigidBody ,
btRigidBody ,
btScalar   
) [inline, virtual]

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

Reimplemented in btConeTwistConstraint.

Definition at line 185 of file btTypedConstraint.h.


Member Data Documentation

union { ... } [private]

Definition at line 81 of file btTypedConstraint.h.

Definition at line 65 of file btTypedConstraint.h.

Definition at line 82 of file btTypedConstraint.h.

Definition at line 66 of file btTypedConstraint.h.

Definition at line 69 of file btTypedConstraint.h.

Definition at line 79 of file btTypedConstraint.h.

Definition at line 80 of file btTypedConstraint.h.

Definition at line 61 of file btTypedConstraint.h.

Definition at line 62 of file btTypedConstraint.h.

Definition at line 57 of file btTypedConstraint.h.


The documentation for this class was generated from the following file:
 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:33