Blender V2.61 - r43446

btHingeConstraint.h

Go to the documentation of this file.
00001 /*
00002 Bullet Continuous Collision Detection and Physics Library
00003 Copyright (c) 2003-2006 Erwin Coumans  http://continuousphysics.com/Bullet/
00004 
00005 This software is provided 'as-is', without any express or implied warranty.
00006 In no event will the authors be held liable for any damages arising from the use of this software.
00007 Permission is granted to anyone to use this software for any purpose, 
00008 including commercial applications, and to alter it and redistribute it freely, 
00009 subject to the following restrictions:
00010 
00011 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
00012 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
00013 3. This notice may not be removed or altered from any source distribution.
00014 */
00015 
00016 /* Hinge Constraint by Dirk Gregorius. Limits added by Marcus Hennix at Starbreeze Studios */
00017 
00018 #ifndef HINGECONSTRAINT_H
00019 #define HINGECONSTRAINT_H
00020 #define _BT_USE_CENTER_LIMIT_ 1
00021 
00022 
00023 #include "LinearMath/btVector3.h"
00024 #include "btJacobianEntry.h"
00025 #include "btTypedConstraint.h"
00026 
00027 class btRigidBody;
00028 
00029 #ifdef BT_USE_DOUBLE_PRECISION
00030 #define btHingeConstraintData   btHingeConstraintDoubleData
00031 #define btHingeConstraintDataName   "btHingeConstraintDoubleData"
00032 #else
00033 #define btHingeConstraintData   btHingeConstraintFloatData
00034 #define btHingeConstraintDataName   "btHingeConstraintFloatData"
00035 #endif //BT_USE_DOUBLE_PRECISION
00036 
00037 
00038 
00039 enum btHingeFlags
00040 {
00041     BT_HINGE_FLAGS_CFM_STOP = 1,
00042     BT_HINGE_FLAGS_ERP_STOP = 2,
00043     BT_HINGE_FLAGS_CFM_NORM = 4
00044 };
00045 
00046 
00049 ATTRIBUTE_ALIGNED16(class) btHingeConstraint : public btTypedConstraint
00050 {
00051 #ifdef IN_PARALLELL_SOLVER
00052 public:
00053 #endif
00054     btJacobianEntry m_jac[3]; //3 orthogonal linear constraints
00055     btJacobianEntry m_jacAng[3]; //2 orthogonal angular constraints+ 1 for limit/motor
00056 
00057     btTransform m_rbAFrame; // constraint axii. Assumes z is hinge axis.
00058     btTransform m_rbBFrame;
00059 
00060     btScalar    m_motorTargetVelocity;
00061     btScalar    m_maxMotorImpulse;
00062 
00063 
00064 #ifdef  _BT_USE_CENTER_LIMIT_
00065     btAngularLimit  m_limit;
00066 #else
00067     btScalar    m_lowerLimit;   
00068     btScalar    m_upperLimit;   
00069     btScalar    m_limitSign;
00070     btScalar    m_correction;
00071 
00072     btScalar    m_limitSoftness; 
00073     btScalar    m_biasFactor; 
00074     btScalar    m_relaxationFactor; 
00075 
00076     bool        m_solveLimit;
00077 #endif
00078 
00079     btScalar    m_kHinge;
00080 
00081 
00082     btScalar    m_accLimitImpulse;
00083     btScalar    m_hingeAngle;
00084     btScalar    m_referenceSign;
00085 
00086     bool        m_angularOnly;
00087     bool        m_enableAngularMotor;
00088     bool        m_useSolveConstraintObsolete;
00089     bool        m_useOffsetForConstraintFrame;
00090     bool        m_useReferenceFrameA;
00091 
00092     btScalar    m_accMotorImpulse;
00093 
00094     int         m_flags;
00095     btScalar    m_normalCFM;
00096     btScalar    m_stopCFM;
00097     btScalar    m_stopERP;
00098 
00099     
00100 public:
00101 
00102     btHingeConstraint(btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB, const btVector3& axisInA,const btVector3& axisInB, bool useReferenceFrameA = false);
00103 
00104     btHingeConstraint(btRigidBody& rbA,const btVector3& pivotInA,const btVector3& axisInA, bool useReferenceFrameA = false);
00105     
00106     btHingeConstraint(btRigidBody& rbA,btRigidBody& rbB, const btTransform& rbAFrame, const btTransform& rbBFrame, bool useReferenceFrameA = false);
00107 
00108     btHingeConstraint(btRigidBody& rbA,const btTransform& rbAFrame, bool useReferenceFrameA = false);
00109 
00110 
00111     virtual void    buildJacobian();
00112 
00113     virtual void getInfo1 (btConstraintInfo1* info);
00114 
00115     void getInfo1NonVirtual(btConstraintInfo1* info);
00116 
00117     virtual void getInfo2 (btConstraintInfo2* info);
00118 
00119     void    getInfo2NonVirtual(btConstraintInfo2* info,const btTransform& transA,const btTransform& transB,const btVector3& angVelA,const btVector3& angVelB);
00120 
00121     void    getInfo2Internal(btConstraintInfo2* info,const btTransform& transA,const btTransform& transB,const btVector3& angVelA,const btVector3& angVelB);
00122     void    getInfo2InternalUsingFrameOffset(btConstraintInfo2* info,const btTransform& transA,const btTransform& transB,const btVector3& angVelA,const btVector3& angVelB);
00123         
00124 
00125     void    updateRHS(btScalar  timeStep);
00126 
00127     const btRigidBody& getRigidBodyA() const
00128     {
00129         return m_rbA;
00130     }
00131     const btRigidBody& getRigidBodyB() const
00132     {
00133         return m_rbB;
00134     }
00135 
00136     btRigidBody& getRigidBodyA()    
00137     {       
00138         return m_rbA;   
00139     }   
00140 
00141     btRigidBody& getRigidBodyB()    
00142     {       
00143         return m_rbB;   
00144     }
00145 
00146     btTransform& getFrameOffsetA()
00147     {
00148     return m_rbAFrame;
00149     }
00150 
00151     btTransform& getFrameOffsetB()
00152     {
00153         return m_rbBFrame;
00154     }
00155 
00156     void setFrames(const btTransform& frameA, const btTransform& frameB);
00157     
00158     void    setAngularOnly(bool angularOnly)
00159     {
00160         m_angularOnly = angularOnly;
00161     }
00162 
00163     void    enableAngularMotor(bool enableMotor,btScalar targetVelocity,btScalar maxMotorImpulse)
00164     {
00165         m_enableAngularMotor  = enableMotor;
00166         m_motorTargetVelocity = targetVelocity;
00167         m_maxMotorImpulse = maxMotorImpulse;
00168     }
00169 
00170     // extra motor API, including ability to set a target rotation (as opposed to angular velocity)
00171     // note: setMotorTarget sets angular velocity under the hood, so you must call it every tick to
00172     //       maintain a given angular target.
00173     void enableMotor(bool enableMotor)  { m_enableAngularMotor = enableMotor; }
00174     void setMaxMotorImpulse(btScalar maxMotorImpulse) { m_maxMotorImpulse = maxMotorImpulse; }
00175     void setMotorTarget(const btQuaternion& qAinB, btScalar dt); // qAinB is rotation of body A wrt body B.
00176     void setMotorTarget(btScalar targetAngle, btScalar dt);
00177 
00178 
00179     void    setLimit(btScalar low,btScalar high,btScalar _softness = 0.9f, btScalar _biasFactor = 0.3f, btScalar _relaxationFactor = 1.0f)
00180     {
00181 #ifdef  _BT_USE_CENTER_LIMIT_
00182         m_limit.set(low, high, _softness, _biasFactor, _relaxationFactor);
00183 #else
00184         m_lowerLimit = btNormalizeAngle(low);
00185         m_upperLimit = btNormalizeAngle(high);
00186         m_limitSoftness =  _softness;
00187         m_biasFactor = _biasFactor;
00188         m_relaxationFactor = _relaxationFactor;
00189 #endif
00190     }
00191 
00192     void    setAxis(btVector3& axisInA)
00193     {
00194         btVector3 rbAxisA1, rbAxisA2;
00195         btPlaneSpace1(axisInA, rbAxisA1, rbAxisA2);
00196         btVector3 pivotInA = m_rbAFrame.getOrigin();
00197 //      m_rbAFrame.getOrigin() = pivotInA;
00198         m_rbAFrame.getBasis().setValue( rbAxisA1.getX(),rbAxisA2.getX(),axisInA.getX(),
00199                                         rbAxisA1.getY(),rbAxisA2.getY(),axisInA.getY(),
00200                                         rbAxisA1.getZ(),rbAxisA2.getZ(),axisInA.getZ() );
00201 
00202         btVector3 axisInB = m_rbA.getCenterOfMassTransform().getBasis() * axisInA;
00203 
00204         btQuaternion rotationArc = shortestArcQuat(axisInA,axisInB);
00205         btVector3 rbAxisB1 =  quatRotate(rotationArc,rbAxisA1);
00206         btVector3 rbAxisB2 = axisInB.cross(rbAxisB1);
00207 
00208         m_rbBFrame.getOrigin() = m_rbB.getCenterOfMassTransform().inverse()(m_rbA.getCenterOfMassTransform()(pivotInA));
00209 
00210         m_rbBFrame.getBasis().setValue( rbAxisB1.getX(),rbAxisB2.getX(),axisInB.getX(),
00211                                         rbAxisB1.getY(),rbAxisB2.getY(),axisInB.getY(),
00212                                         rbAxisB1.getZ(),rbAxisB2.getZ(),axisInB.getZ() );
00213         m_rbBFrame.getBasis() = m_rbB.getCenterOfMassTransform().getBasis().inverse() * m_rbBFrame.getBasis();
00214 
00215     }
00216 
00217     btScalar    getLowerLimit() const
00218     {
00219 #ifdef  _BT_USE_CENTER_LIMIT_
00220     return m_limit.getLow();
00221 #else
00222     return m_lowerLimit;
00223 #endif
00224     }
00225 
00226     btScalar    getUpperLimit() const
00227     {
00228 #ifdef  _BT_USE_CENTER_LIMIT_
00229     return m_limit.getHigh();
00230 #else       
00231     return m_upperLimit;
00232 #endif
00233     }
00234 
00235 
00236     btScalar getHingeAngle();
00237 
00238     btScalar getHingeAngle(const btTransform& transA,const btTransform& transB);
00239 
00240     void testLimit(const btTransform& transA,const btTransform& transB);
00241 
00242 
00243     const btTransform& getAFrame() const { return m_rbAFrame; };    
00244     const btTransform& getBFrame() const { return m_rbBFrame; };
00245 
00246     btTransform& getAFrame() { return m_rbAFrame; };    
00247     btTransform& getBFrame() { return m_rbBFrame; };
00248 
00249     inline int getSolveLimit()
00250     {
00251 #ifdef  _BT_USE_CENTER_LIMIT_
00252     return m_limit.isLimit();
00253 #else
00254     return m_solveLimit;
00255 #endif
00256     }
00257 
00258     inline btScalar getLimitSign()
00259     {
00260 #ifdef  _BT_USE_CENTER_LIMIT_
00261     return m_limit.getSign();
00262 #else
00263         return m_limitSign;
00264 #endif
00265     }
00266 
00267     inline bool getAngularOnly() 
00268     { 
00269         return m_angularOnly; 
00270     }
00271     inline bool getEnableAngularMotor() 
00272     { 
00273         return m_enableAngularMotor; 
00274     }
00275     inline btScalar getMotorTargetVelosity() 
00276     { 
00277         return m_motorTargetVelocity; 
00278     }
00279     inline btScalar getMaxMotorImpulse() 
00280     { 
00281         return m_maxMotorImpulse; 
00282     }
00283     // access for UseFrameOffset
00284     bool getUseFrameOffset() { return m_useOffsetForConstraintFrame; }
00285     void setUseFrameOffset(bool frameOffsetOnOff) { m_useOffsetForConstraintFrame = frameOffsetOnOff; }
00286 
00287 
00290     virtual void    setParam(int num, btScalar value, int axis = -1);
00292     virtual btScalar getParam(int num, int axis = -1) const;
00293 
00294     virtual int calculateSerializeBufferSize() const;
00295 
00297     virtual const char* serialize(void* dataBuffer, btSerializer* serializer) const;
00298 
00299 
00300 };
00301 
00303 struct  btHingeConstraintDoubleData
00304 {
00305     btTypedConstraintData   m_typeConstraintData;
00306     btTransformDoubleData m_rbAFrame; // constraint axii. Assumes z is hinge axis.
00307     btTransformDoubleData m_rbBFrame;
00308     int         m_useReferenceFrameA;
00309     int         m_angularOnly;
00310     int         m_enableAngularMotor;
00311     float   m_motorTargetVelocity;
00312     float   m_maxMotorImpulse;
00313 
00314     float   m_lowerLimit;
00315     float   m_upperLimit;
00316     float   m_limitSoftness;
00317     float   m_biasFactor;
00318     float   m_relaxationFactor;
00319 
00320 };
00322 struct  btHingeConstraintFloatData
00323 {
00324     btTypedConstraintData   m_typeConstraintData;
00325     btTransformFloatData m_rbAFrame; // constraint axii. Assumes z is hinge axis.
00326     btTransformFloatData m_rbBFrame;
00327     int         m_useReferenceFrameA;
00328     int         m_angularOnly;
00329     
00330     int         m_enableAngularMotor;
00331     float   m_motorTargetVelocity;
00332     float   m_maxMotorImpulse;
00333 
00334     float   m_lowerLimit;
00335     float   m_upperLimit;
00336     float   m_limitSoftness;
00337     float   m_biasFactor;
00338     float   m_relaxationFactor;
00339 
00340 };
00341 
00342 
00343 
00344 SIMD_FORCE_INLINE   int btHingeConstraint::calculateSerializeBufferSize() const
00345 {
00346     return sizeof(btHingeConstraintData);
00347 }
00348 
00350 SIMD_FORCE_INLINE   const char* btHingeConstraint::serialize(void* dataBuffer, btSerializer* serializer) const
00351 {
00352     btHingeConstraintData* hingeData = (btHingeConstraintData*)dataBuffer;
00353     btTypedConstraint::serialize(&hingeData->m_typeConstraintData,serializer);
00354 
00355     m_rbAFrame.serialize(hingeData->m_rbAFrame);
00356     m_rbBFrame.serialize(hingeData->m_rbBFrame);
00357 
00358     hingeData->m_angularOnly = m_angularOnly;
00359     hingeData->m_enableAngularMotor = m_enableAngularMotor;
00360     hingeData->m_maxMotorImpulse = float(m_maxMotorImpulse);
00361     hingeData->m_motorTargetVelocity = float(m_motorTargetVelocity);
00362     hingeData->m_useReferenceFrameA = m_useReferenceFrameA;
00363 #ifdef  _BT_USE_CENTER_LIMIT_
00364     hingeData->m_lowerLimit = float(m_limit.getLow());
00365     hingeData->m_upperLimit = float(m_limit.getHigh());
00366     hingeData->m_limitSoftness = float(m_limit.getSoftness());
00367     hingeData->m_biasFactor = float(m_limit.getBiasFactor());
00368     hingeData->m_relaxationFactor = float(m_limit.getRelaxationFactor());
00369 #else
00370     hingeData->m_lowerLimit = float(m_lowerLimit);
00371     hingeData->m_upperLimit = float(m_upperLimit);
00372     hingeData->m_limitSoftness = float(m_limitSoftness);
00373     hingeData->m_biasFactor = float(m_biasFactor);
00374     hingeData->m_relaxationFactor = float(m_relaxationFactor);
00375 #endif
00376 
00377     return btHingeConstraintDataName;
00378 }
00379 
00380 #endif //HINGECONSTRAINT_H