Bullet Collision Detection & Physics Library
Public Member Functions | Public Attributes | Private Attributes | List of all members
btPoint2PointConstraint Class Reference

point to point constraint between two rigidbodies each with a pivotpoint that descibes the 'ballsocket' location in local space More...

#include <btPoint2PointConstraint.h>

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

Public Member Functions

 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btPoint2PointConstraint (btRigidBody &rbA, btRigidBody &rbB, const btVector3 &pivotInA, const btVector3 &pivotInB)
 
 btPoint2PointConstraint (btRigidBody &rbA, const btVector3 &pivotInA)
 
virtual void buildJacobian ()
 internal method used by the constraint solver, don't use them directly More...
 
virtual void getInfo1 (btConstraintInfo1 *info)
 internal method used by the constraint solver, don't use them directly More...
 
void getInfo1NonVirtual (btConstraintInfo1 *info)
 
virtual void getInfo2 (btConstraintInfo2 *info)
 internal method used by the constraint solver, don't use them directly More...
 
void getInfo2NonVirtual (btConstraintInfo2 *info, const btTransform &body0_trans, const btTransform &body1_trans)
 
void updateRHS (btScalar timeStep)
 
void setPivotA (const btVector3 &pivotA)
 
void setPivotB (const btVector3 &pivotB)
 
const btVector3getPivotInA () const
 
const btVector3getPivotInB () const
 
virtual void setParam (int num, btScalar value, int axis=-1)
 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
 return the local value of parameter More...
 
virtual int getFlags () const
 
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 btTypedConstraint
 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 setupSolverConstraint (btConstraintArray &ca, int solverBodyA, int solverBodyB, btScalar timeStep)
 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 ()
 
- Public Member Functions inherited from btTypedObject
 btTypedObject (int objectType)
 
int getObjectType () const
 

Public Attributes

bool m_useSolveConstraintObsolete
 for backwards compatibility during the transition to 'getInfo/getInfo2' More...
 
btConstraintSetting m_setting
 
- Public Attributes inherited from btTypedObject
int m_objectType
 

Private Attributes

btJacobianEntry m_jac [3]
 
btVector3 m_pivotInA
 
btVector3 m_pivotInB
 
int m_flags
 
btScalar m_erp
 
btScalar m_cfm
 

Additional Inherited Members

- Static Public Member Functions inherited from btTypedConstraint
static btRigidBodygetFixedBody ()
 
- Protected Member Functions inherited from btTypedConstraint
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 inherited from btTypedConstraint
btRigidBodym_rbA
 
btRigidBodym_rbB
 
btScalar m_appliedImpulse
 
btScalar m_dbgDrawSize
 
btJointFeedbackm_jointFeedback
 

Detailed Description

point to point constraint between two rigidbodies each with a pivotpoint that descibes the 'ballsocket' location in local space

Definition at line 54 of file btPoint2PointConstraint.h.

Constructor & Destructor Documentation

btPoint2PointConstraint::btPoint2PointConstraint ( btRigidBody rbA,
btRigidBody rbB,
const btVector3 pivotInA,
const btVector3 pivotInB 
)

Definition at line 25 of file btPoint2PointConstraint.cpp.

btPoint2PointConstraint::btPoint2PointConstraint ( btRigidBody rbA,
const btVector3 pivotInA 
)

Definition at line 34 of file btPoint2PointConstraint.cpp.

Member Function Documentation

btPoint2PointConstraint::BT_DECLARE_ALIGNED_ALLOCATOR ( )
void btPoint2PointConstraint::buildJacobian ( )
virtual

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

we need it for both methods

Reimplemented from btTypedConstraint.

Definition at line 42 of file btPoint2PointConstraint.cpp.

int btPoint2PointConstraint::calculateSerializeBufferSize ( ) const
inlinevirtual

Reimplemented from btTypedConstraint.

Definition at line 162 of file btPoint2PointConstraint.h.

virtual int btPoint2PointConstraint::getFlags ( ) const
inlinevirtual

Definition at line 120 of file btPoint2PointConstraint.h.

void btPoint2PointConstraint::getInfo1 ( btConstraintInfo1 info)
virtual

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

Implements btTypedConstraint.

Definition at line 71 of file btPoint2PointConstraint.cpp.

void btPoint2PointConstraint::getInfo1NonVirtual ( btConstraintInfo1 info)

Definition at line 76 of file btPoint2PointConstraint.cpp.

void btPoint2PointConstraint::getInfo2 ( btConstraintInfo2 info)
virtual

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

Implements btTypedConstraint.

Definition at line 92 of file btPoint2PointConstraint.cpp.

void btPoint2PointConstraint::getInfo2NonVirtual ( btConstraintInfo2 info,
const btTransform body0_trans,
const btTransform body1_trans 
)

Definition at line 97 of file btPoint2PointConstraint.cpp.

btScalar btPoint2PointConstraint::getParam ( int  num,
int  axis = -1 
) const
virtual

return the local value of parameter

Implements btTypedConstraint.

Definition at line 202 of file btPoint2PointConstraint.cpp.

const btVector3& btPoint2PointConstraint::getPivotInA ( ) const
inline

Definition at line 104 of file btPoint2PointConstraint.h.

const btVector3& btPoint2PointConstraint::getPivotInB ( ) const
inline

Definition at line 109 of file btPoint2PointConstraint.h.

const char * btPoint2PointConstraint::serialize ( void *  dataBuffer,
btSerializer serializer 
) const
inlinevirtual

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

Reimplemented from btTypedConstraint.

Definition at line 169 of file btPoint2PointConstraint.h.

void btPoint2PointConstraint::setParam ( int  num,
btScalar  value,
int  axis = -1 
)
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.

Implements btTypedConstraint.

Definition at line 175 of file btPoint2PointConstraint.cpp.

void btPoint2PointConstraint::setPivotA ( const btVector3 pivotA)
inline

Definition at line 94 of file btPoint2PointConstraint.h.

void btPoint2PointConstraint::setPivotB ( const btVector3 pivotB)
inline

Definition at line 99 of file btPoint2PointConstraint.h.

void btPoint2PointConstraint::updateRHS ( btScalar  timeStep)

Definition at line 167 of file btPoint2PointConstraint.cpp.

Member Data Documentation

btScalar btPoint2PointConstraint::m_cfm
private

Definition at line 66 of file btPoint2PointConstraint.h.

btScalar btPoint2PointConstraint::m_erp
private

Definition at line 65 of file btPoint2PointConstraint.h.

int btPoint2PointConstraint::m_flags
private

Definition at line 64 of file btPoint2PointConstraint.h.

btJacobianEntry btPoint2PointConstraint::m_jac[3]
private

Definition at line 59 of file btPoint2PointConstraint.h.

btVector3 btPoint2PointConstraint::m_pivotInA
private

Definition at line 61 of file btPoint2PointConstraint.h.

btVector3 btPoint2PointConstraint::m_pivotInB
private

Definition at line 62 of file btPoint2PointConstraint.h.

btConstraintSetting btPoint2PointConstraint::m_setting

Definition at line 75 of file btPoint2PointConstraint.h.

bool btPoint2PointConstraint::m_useSolveConstraintObsolete

for backwards compatibility during the transition to 'getInfo/getInfo2'

Definition at line 73 of file btPoint2PointConstraint.h.


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