btConeTwistConstraint can be used to simulate ragdoll joints (upper arm, leg etc) More...
#include <btConeTwistConstraint.h>
btConeTwistConstraint can be used to simulate ragdoll joints (upper arm, leg etc)
Definition at line 53 of file btConeTwistConstraint.h.
btConeTwistConstraint::btConeTwistConstraint | ( | btRigidBody & | rbA, | |
btRigidBody & | rbB, | |||
const btTransform & | rbAFrame, | |||
const btTransform & | rbBFrame | |||
) |
btConeTwistConstraint::btConeTwistConstraint | ( | btRigidBody & | rbA, | |
const btTransform & | rbAFrame | |||
) |
void btConeTwistConstraint::adjustSwingAxisToUseEllipseNormal | ( | btVector3 & | vSwingAxis | ) | const [protected] |
virtual void btConeTwistConstraint::buildJacobian | ( | ) | [virtual] |
internal method used by the constraint solver, don't use them directly
Reimplemented from btTypedConstraint.
void btConeTwistConstraint::calcAngleInfo | ( | ) |
void btConeTwistConstraint::calcAngleInfo2 | ( | const btTransform & | transA, | |
const btTransform & | transB, | |||
const btMatrix3x3 & | invInertiaWorldA, | |||
const btMatrix3x3 & | invInertiaWorldB | |||
) |
SIMD_FORCE_INLINE int btConeTwistConstraint::calculateSerializeBufferSize | ( | ) | const [virtual] |
Reimplemented from btTypedConstraint.
Definition at line 304 of file btConeTwistConstraint.h.
void btConeTwistConstraint::computeConeLimitInfo | ( | const btQuaternion & | qCone, | |
btScalar & | swingAngle, | |||
btVector3 & | vSwingAxis, | |||
btScalar & | swingLimit | |||
) | [protected] |
void btConeTwistConstraint::computeTwistLimitInfo | ( | const btQuaternion & | qTwist, | |
btScalar & | twistAngle, | |||
btVector3 & | vTwistAxis | |||
) | [protected] |
void btConeTwistConstraint::enableMotor | ( | bool | b | ) | [inline] |
Definition at line 250 of file btConeTwistConstraint.h.
const btTransform& btConeTwistConstraint::getAFrame | ( | ) | [inline] |
Definition at line 208 of file btConeTwistConstraint.h.
const btTransform& btConeTwistConstraint::getBFrame | ( | ) | [inline] |
Definition at line 209 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::getFixThresh | ( | ) | [inline] |
Definition at line 254 of file btConeTwistConstraint.h.
virtual void btConeTwistConstraint::getInfo1 | ( | btConstraintInfo1 * | info | ) | [virtual] |
internal method used by the constraint solver, don't use them directly
Implements btTypedConstraint.
void btConeTwistConstraint::getInfo1NonVirtual | ( | btConstraintInfo1 * | info | ) |
virtual void btConeTwistConstraint::getInfo2 | ( | btConstraintInfo2 * | info | ) | [virtual] |
internal method used by the constraint solver, don't use them directly
Implements btTypedConstraint.
void btConeTwistConstraint::getInfo2NonVirtual | ( | btConstraintInfo2 * | info, | |
const btTransform & | transA, | |||
const btTransform & | transB, | |||
const btMatrix3x3 & | invInertiaWorldA, | |||
const btMatrix3x3 & | invInertiaWorldB | |||
) |
virtual btScalar btConeTwistConstraint::getParam | ( | int | num, | |
int | axis = -1 | |||
) | const [virtual] |
return the local value of parameter
Implements btTypedConstraint.
btVector3 btConeTwistConstraint::GetPointForAngle | ( | btScalar | fAngleInRadians, | |
btScalar | fLength | |||
) | const |
const btRigidBody& btConeTwistConstraint::getRigidBodyA | ( | ) | const [inline] |
Reimplemented from btTypedConstraint.
Definition at line 147 of file btConeTwistConstraint.h.
const btRigidBody& btConeTwistConstraint::getRigidBodyB | ( | ) | const [inline] |
Reimplemented from btTypedConstraint.
Definition at line 151 of file btConeTwistConstraint.h.
int btConeTwistConstraint::getSolveSwingLimit | ( | ) | [inline] |
Definition at line 216 of file btConeTwistConstraint.h.
int btConeTwistConstraint::getSolveTwistLimit | ( | ) | [inline] |
Definition at line 211 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::getSwingSpan1 | ( | ) | [inline] |
Definition at line 229 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::getSwingSpan2 | ( | ) | [inline] |
Definition at line 233 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::getTwistAngle | ( | ) | [inline] |
Definition at line 241 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::getTwistLimitSign | ( | ) | [inline] |
Definition at line 221 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::getTwistSpan | ( | ) | [inline] |
Definition at line 237 of file btConeTwistConstraint.h.
void btConeTwistConstraint::init | ( | ) | [protected] |
bool btConeTwistConstraint::isPastSwingLimit | ( | ) | [inline] |
Definition at line 245 of file btConeTwistConstraint.h.
SIMD_FORCE_INLINE const char * btConeTwistConstraint::serialize | ( | void * | dataBuffer, | |
btSerializer * | serializer | |||
) | const [virtual] |
fills the dataBuffer and returns the struct name (and 0 on failure)
Reimplemented from btTypedConstraint.
Definition at line 312 of file btConeTwistConstraint.h.
void btConeTwistConstraint::setAngularOnly | ( | bool | angularOnly | ) | [inline] |
Definition at line 156 of file btConeTwistConstraint.h.
void btConeTwistConstraint::setDamping | ( | btScalar | damping | ) | [inline] |
Definition at line 248 of file btConeTwistConstraint.h.
void btConeTwistConstraint::setFixThresh | ( | btScalar | fixThresh | ) | [inline] |
Definition at line 255 of file btConeTwistConstraint.h.
void btConeTwistConstraint::setLimit | ( | btScalar | _swingSpan1, | |
btScalar | _swingSpan2, | |||
btScalar | _twistSpan, | |||
btScalar | _softness = 1.f , |
|||
btScalar | _biasFactor = 0.3f , |
|||
btScalar | _relaxationFactor = 1.0f | |||
) | [inline] |
Definition at line 197 of file btConeTwistConstraint.h.
void btConeTwistConstraint::setLimit | ( | int | limitIndex, | |
btScalar | limitValue | |||
) | [inline] |
Definition at line 161 of file btConeTwistConstraint.h.
void btConeTwistConstraint::setMaxMotorImpulse | ( | btScalar | maxMotorImpulse | ) | [inline] |
Definition at line 251 of file btConeTwistConstraint.h.
void btConeTwistConstraint::setMaxMotorImpulseNormalized | ( | btScalar | maxMotorImpulse | ) | [inline] |
Definition at line 252 of file btConeTwistConstraint.h.
void btConeTwistConstraint::setMotorTarget | ( | const btQuaternion & | q | ) |
void btConeTwistConstraint::setMotorTargetInConstraintSpace | ( | const btQuaternion & | q | ) |
virtual void btConeTwistConstraint::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.
virtual void btConeTwistConstraint::solveConstraintObsolete | ( | btRigidBody & | bodyA, | |
btRigidBody & | bodyB, | |||
btScalar | timeStep | |||
) | [virtual] |
internal method used by the constraint solver, don't use them directly
Reimplemented from btTypedConstraint.
void btConeTwistConstraint::updateRHS | ( | btScalar | timeStep | ) |
btVector3 btConeTwistConstraint::m_accMotorImpulse [private] |
Definition at line 106 of file btConeTwistConstraint.h.
Definition at line 87 of file btConeTwistConstraint.h.
Definition at line 88 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_angCFM [private] |
Definition at line 112 of file btConeTwistConstraint.h.
bool btConeTwistConstraint::m_angularOnly [private] |
Definition at line 90 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_biasFactor [private] |
Definition at line 64 of file btConeTwistConstraint.h.
bool btConeTwistConstraint::m_bMotorEnabled [private] |
Definition at line 102 of file btConeTwistConstraint.h.
bool btConeTwistConstraint::m_bNormalizedMotorStrength [private] |
Definition at line 103 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_damping [private] |
Definition at line 67 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_fixThresh [private] |
Definition at line 73 of file btConeTwistConstraint.h.
int btConeTwistConstraint::m_flags [private] |
Definition at line 109 of file btConeTwistConstraint.h.
btJacobianEntry btConeTwistConstraint::m_jac[3] [private] |
Definition at line 58 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_kSwing [private] |
Definition at line 78 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_kTwist [private] |
Definition at line 79 of file btConeTwistConstraint.h.
Definition at line 63 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_linCFM [private] |
Definition at line 110 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_linERP [private] |
Definition at line 111 of file btConeTwistConstraint.h.
Definition at line 105 of file btConeTwistConstraint.h.
btQuaternion btConeTwistConstraint::m_qTarget [private] |
Definition at line 104 of file btConeTwistConstraint.h.
btTransform btConeTwistConstraint::m_rbAFrame [private] |
Definition at line 60 of file btConeTwistConstraint.h.
btTransform btConeTwistConstraint::m_rbBFrame [private] |
Definition at line 61 of file btConeTwistConstraint.h.
Definition at line 65 of file btConeTwistConstraint.h.
bool btConeTwistConstraint::m_solveSwingLimit [private] |
Definition at line 92 of file btConeTwistConstraint.h.
bool btConeTwistConstraint::m_solveTwistLimit [private] |
Definition at line 91 of file btConeTwistConstraint.h.
btVector3 btConeTwistConstraint::m_swingAxis [private] |
Definition at line 75 of file btConeTwistConstraint.h.
Definition at line 82 of file btConeTwistConstraint.h.
Definition at line 97 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_swingSpan1 [private] |
Definition at line 69 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_swingSpan2 [private] |
Definition at line 70 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_twistAngle [private] |
Definition at line 85 of file btConeTwistConstraint.h.
btVector3 btConeTwistConstraint::m_twistAxis [private] |
Definition at line 76 of file btConeTwistConstraint.h.
btVector3 btConeTwistConstraint::m_twistAxisA [private] |
Definition at line 99 of file btConeTwistConstraint.h.
Definition at line 83 of file btConeTwistConstraint.h.
Definition at line 98 of file btConeTwistConstraint.h.
Definition at line 81 of file btConeTwistConstraint.h.
btScalar btConeTwistConstraint::m_twistSpan [private] |
Definition at line 71 of file btConeTwistConstraint.h.
bool btConeTwistConstraint::m_useSolveConstraintObsolete [private] |
Definition at line 94 of file btConeTwistConstraint.h.