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

The getAccumulatedHingeAngle returns the accumulated hinge angle, taking rotation across the -PI/PI boundary into account. More...

#include <btHingeConstraint.h>

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

Public Member Functions

 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btHingeAccumulatedAngleConstraint (btRigidBody &rbA, btRigidBody &rbB, const btVector3 &pivotInA, const btVector3 &pivotInB, const btVector3 &axisInA, const btVector3 &axisInB, bool useReferenceFrameA=false)
 
 btHingeAccumulatedAngleConstraint (btRigidBody &rbA, const btVector3 &pivotInA, const btVector3 &axisInA, bool useReferenceFrameA=false)
 
 btHingeAccumulatedAngleConstraint (btRigidBody &rbA, btRigidBody &rbB, const btTransform &rbAFrame, const btTransform &rbBFrame, bool useReferenceFrameA=false)
 
 btHingeAccumulatedAngleConstraint (btRigidBody &rbA, const btTransform &rbAFrame, bool useReferenceFrameA=false)
 
btScalar getAccumulatedHingeAngle ()
 
void setAccumulatedHingeAngle (btScalar accAngle)
 
virtual void getInfo1 (btConstraintInfo1 *info)
 internal method used by the constraint solver, don't use them directly More...
 
- Public Member Functions inherited from btHingeConstraint
 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btHingeConstraint (btRigidBody &rbA, btRigidBody &rbB, const btVector3 &pivotInA, const btVector3 &pivotInB, const btVector3 &axisInA, const btVector3 &axisInB, bool useReferenceFrameA=false)
 
 btHingeConstraint (btRigidBody &rbA, const btVector3 &pivotInA, const btVector3 &axisInA, bool useReferenceFrameA=false)
 
 btHingeConstraint (btRigidBody &rbA, btRigidBody &rbB, const btTransform &rbAFrame, const btTransform &rbBFrame, bool useReferenceFrameA=false)
 
 btHingeConstraint (btRigidBody &rbA, const btTransform &rbAFrame, bool useReferenceFrameA=false)
 
virtual void buildJacobian ()
 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 &transA, const btTransform &transB, const btVector3 &angVelA, const btVector3 &angVelB)
 
void getInfo2Internal (btConstraintInfo2 *info, const btTransform &transA, const btTransform &transB, const btVector3 &angVelA, const btVector3 &angVelB)
 
void getInfo2InternalUsingFrameOffset (btConstraintInfo2 *info, const btTransform &transA, const btTransform &transB, const btVector3 &angVelA, const btVector3 &angVelB)
 
void updateRHS (btScalar timeStep)
 
const btRigidBodygetRigidBodyA () const
 
const btRigidBodygetRigidBodyB () const
 
btRigidBodygetRigidBodyA ()
 
btRigidBodygetRigidBodyB ()
 
btTransformgetFrameOffsetA ()
 
btTransformgetFrameOffsetB ()
 
void setFrames (const btTransform &frameA, const btTransform &frameB)
 
void setAngularOnly (bool angularOnly)
 
void enableAngularMotor (bool enableMotor, btScalar targetVelocity, btScalar maxMotorImpulse)
 
void enableMotor (bool enableMotor)
 
void setMaxMotorImpulse (btScalar maxMotorImpulse)
 
void setMotorTargetVelocity (btScalar motorTargetVelocity)
 
void setMotorTarget (const btQuaternion &qAinB, btScalar dt)
 
void setMotorTarget (btScalar targetAngle, btScalar dt)
 
void setLimit (btScalar low, btScalar high, btScalar _softness=0.9f, btScalar _biasFactor=0.3f, btScalar _relaxationFactor=1.0f)
 
btScalar getLimitSoftness () const
 
btScalar getLimitBiasFactor () const
 
btScalar getLimitRelaxationFactor () const
 
void setAxis (btVector3 &axisInA)
 
bool hasLimit () const
 
btScalar getLowerLimit () const
 
btScalar getUpperLimit () const
 
btScalar getHingeAngle ()
 The getHingeAngle gives the hinge angle in range [-PI,PI]. More...
 
btScalar getHingeAngle (const btTransform &transA, const btTransform &transB)
 
void testLimit (const btTransform &transA, const btTransform &transB)
 
const btTransformgetAFrame () const
 
const btTransformgetBFrame () const
 
btTransformgetAFrame ()
 
btTransformgetBFrame ()
 
int getSolveLimit ()
 
btScalar getLimitSign ()
 
bool getAngularOnly ()
 
bool getEnableAngularMotor ()
 
btScalar getMotorTargetVelocity ()
 
btScalar getMaxMotorImpulse ()
 
bool getUseFrameOffset ()
 
void setUseFrameOffset (bool frameOffsetOnOff)
 
bool getUseReferenceFrameA () const
 
void setUseReferenceFrameA (bool useReferenceFrameA)
 
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
 

Protected Attributes

btScalar m_accumulatedAngle
 
- Protected Attributes inherited from btTypedConstraint
btRigidBodym_rbA
 
btRigidBodym_rbB
 
btScalar m_appliedImpulse
 
btScalar m_dbgDrawSize
 
btJointFeedbackm_jointFeedback
 

Additional Inherited Members

- Static Public Member Functions inherited from btTypedConstraint
static btRigidBodygetFixedBody ()
 
- Public Attributes inherited from btTypedObject
int m_objectType
 
- 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...
 

Detailed Description

The getAccumulatedHingeAngle returns the accumulated hinge angle, taking rotation across the -PI/PI boundary into account.

Definition at line 376 of file btHingeConstraint.h.

Constructor & Destructor Documentation

btHingeAccumulatedAngleConstraint::btHingeAccumulatedAngleConstraint ( btRigidBody rbA,
btRigidBody rbB,
const btVector3 pivotInA,
const btVector3 pivotInB,
const btVector3 axisInA,
const btVector3 axisInB,
bool  useReferenceFrameA = false 
)
inline

Definition at line 384 of file btHingeConstraint.h.

btHingeAccumulatedAngleConstraint::btHingeAccumulatedAngleConstraint ( btRigidBody rbA,
const btVector3 pivotInA,
const btVector3 axisInA,
bool  useReferenceFrameA = false 
)
inline

Definition at line 390 of file btHingeConstraint.h.

btHingeAccumulatedAngleConstraint::btHingeAccumulatedAngleConstraint ( btRigidBody rbA,
btRigidBody rbB,
const btTransform rbAFrame,
const btTransform rbBFrame,
bool  useReferenceFrameA = false 
)
inline

Definition at line 396 of file btHingeConstraint.h.

btHingeAccumulatedAngleConstraint::btHingeAccumulatedAngleConstraint ( btRigidBody rbA,
const btTransform rbAFrame,
bool  useReferenceFrameA = false 
)
inline

Definition at line 402 of file btHingeConstraint.h.

Member Function Documentation

btHingeAccumulatedAngleConstraint::BT_DECLARE_ALIGNED_ALLOCATOR ( )
btScalar btHingeAccumulatedAngleConstraint::getAccumulatedHingeAngle ( )

Definition at line 332 of file btHingeConstraint.cpp.

void btHingeAccumulatedAngleConstraint::getInfo1 ( btConstraintInfo1 info)
virtual

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

Reimplemented from btHingeConstraint.

Definition at line 343 of file btHingeConstraint.cpp.

void btHingeAccumulatedAngleConstraint::setAccumulatedHingeAngle ( btScalar  accAngle)

Definition at line 338 of file btHingeConstraint.cpp.

Member Data Documentation

btScalar btHingeAccumulatedAngleConstraint::m_accumulatedAngle
protected

Definition at line 379 of file btHingeConstraint.h.


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