36 #ifndef BT_CONETWISTCONSTRAINT_H    37 #define BT_CONETWISTCONSTRAINT_H    43 #ifdef BT_USE_DOUBLE_PRECISION    44 #define btConeTwistConstraintData2      btConeTwistConstraintDoubleData    45 #define btConeTwistConstraintDataName   "btConeTwistConstraintDoubleData"    47 #define btConeTwistConstraintData2      btConeTwistConstraintData     48 #define btConeTwistConstraintDataName   "btConeTwistConstraintData"     49 #endif //BT_USE_DOUBLE_PRECISION    64 #ifdef IN_PARALLELL_SOLVER   133         void adjustSwingAxisToUseEllipseNormal(
btVector3& vSwingAxis) 
const;
   144         virtual void    buildJacobian();
   171                 m_angularOnly = angularOnly;
   176             return m_angularOnly;
   185                                 m_twistSpan = limitValue;
   190                                 m_swingSpan2 = limitValue;
   195                                 m_swingSpan1 = limitValue;
   225                             btAssert(0 && 
"Invalid limitIndex specified for btConeTwistConstraint");
   244                 m_swingSpan1 = _swingSpan1;
   245                 m_swingSpan2 = _swingSpan2;
   246                 m_twistSpan  = _twistSpan;
   248                 m_limitSoftness =  _softness;
   249                 m_biasFactor = _biasFactor;
   250                 m_relaxationFactor = _relaxationFactor;
   258                 return m_solveTwistLimit;
   263                 return m_solveSwingLimit;
   268                 return m_twistLimitSign;
   271         void calcAngleInfo();
   288                 return m_limitSoftness;
   296                 return m_relaxationFactor;
   325         void setMotorTargetInConstraintSpace(
const btQuaternion &q);
   331         virtual void setParam(
int num, 
btScalar value, 
int axis = -1);
   347         virtual btScalar getParam(
int num, 
int axis = -1) 
const;
   383 #ifdef BT_BACKWARDS_COMPATIBLE_SERIALIZATION   404 #endif //BT_BACKWARDS_COMPATIBLE_SERIALIZATION   435 #endif //BT_CONETWISTCONSTRAINT_H 
void setMaxMotorImpulseNormalized(btScalar maxMotorImpulse)
void setLimit(int limitIndex, btScalar limitValue)
btTransformDoubleData m_rbAFrame
btScalar m_maxMotorImpulse
btTransformFloatData m_rbAFrame
btScalar m_swingCorrection
btTypedConstraintDoubleData m_typeConstraintData
Jacobian entry is an abstraction that allows to describe constraints it can be used in combination wi...
#define btConeTwistConstraintData2
btScalar getTwistLimitSign()
const btRigidBody & getRigidBodyB() const 
void setMaxMotorImpulse(btScalar maxMotorImpulse)
bool isMotorEnabled() const 
#define SIMD_FORCE_INLINE
btScalar getBiasFactor() const 
const btTransform & getFrameOffsetA() const 
void setDamping(btScalar damping)
btTransformFloatData m_rbBFrame
btScalar getTwistSpan() const 
btScalar getRelaxationFactor() const 
btScalar m_twistLimitRatio
double m_relaxationFactor
const btQuaternion & getMotorTarget() const 
btScalar m_relaxationFactor
virtual const char * serialize(void *dataBuffer, btSerializer *serializer) const 
fills the dataBuffer and returns the struct name (and 0 on failure) 
void setLimit(btScalar _swingSpan1, btScalar _swingSpan2, btScalar _twistSpan, btScalar _softness=1.f, btScalar _biasFactor=0.3f, btScalar _relaxationFactor=1.0f)
virtual int calculateSerializeBufferSize() const 
btScalar getMaxMotorImpulse() const 
btScalar m_twistLimitSign
bool getAngularOnly() const 
btTypedConstraintData m_typeConstraintData
btScalar getDamping() const 
btVector3 m_accMotorImpulse
btScalar getLimit(int limitIndex) const 
btScalar getLimitSoftness() const 
The btRigidBody is the main class for rigid body objects. 
bool m_useSolveConstraintObsolete
btScalar m_twistCorrection
this structure is not used, except for loading pre-2.82 .bullet files 
bool isMaxMotorImpulseNormalized() const 
btScalar getSwingSpan2() const 
void setAngularOnly(bool angularOnly)
btTransformDoubleData m_rbBFrame
btVector3 can be used to represent 3D points and vectors. 
#define ATTRIBUTE_ALIGNED16(a)
const btTransform & getAFrame() const 
btConeTwistConstraint can be used to simulate ragdoll joints (upper arm, leg etc) ...
void setFixThresh(btScalar fixThresh)
The btSolverBody is an internal datastructure for the constraint solver. Only necessary data is packe...
TypedConstraint is the baseclass for Bullet constraints and vehicles. 
#define BT_DECLARE_ALIGNED_ALLOCATOR()
virtual const char * serialize(void *dataBuffer, class btSerializer *serializer) const 
fills the dataBuffer and returns the struct name (and 0 on failure) 
virtual const char * serialize(void *dataBuffer, btSerializer *serializer) const 
fills the dataBuffer and returns the struct name (and 0 on failure) 
btScalar m_accSwingLimitImpulse
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
this structure is not used, except for loading pre-2.82 .bullet files 
const btRigidBody & getRigidBodyA() const 
btScalar m_swingLimitRatio
btScalar m_accTwistLimitImpulse
The btQuaternion implements quaternion to perform linear algebra rotations in combination with btMatr...
const btTransform & getFrameOffsetB() const 
btScalar getSwingSpan1() const 
const btTransform & getBFrame() const 
btScalar getTwistAngle() const 
bool m_bNormalizedMotorStrength
virtual int calculateSerializeBufferSize() const 
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
#define btConeTwistConstraintDataName