btTypedConstraint.h
Go to the documentation of this file.
00001 /*
00002 Bullet Continuous Collision Detection and Physics Library
00003 Copyright (c) 2003-2010 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 #ifndef BT_TYPED_CONSTRAINT_H
00017 #define BT_TYPED_CONSTRAINT_H
00018 
00019 class btRigidBody;
00020 #include "LinearMath/btScalar.h"
00021 #include "btSolverConstraint.h"
00022 
00023 class btSerializer;
00024 
00025 //Don't change any of the existing enum values, so add enum types at the end for serialization compatibility
00026 enum btTypedConstraintType
00027 {
00028         POINT2POINT_CONSTRAINT_TYPE=3,
00029         HINGE_CONSTRAINT_TYPE,
00030         CONETWIST_CONSTRAINT_TYPE,
00031         D6_CONSTRAINT_TYPE,
00032         SLIDER_CONSTRAINT_TYPE,
00033         CONTACT_CONSTRAINT_TYPE,
00034         D6_SPRING_CONSTRAINT_TYPE,
00035         MAX_CONSTRAINT_TYPE
00036 };
00037 
00038 
00039 enum btConstraintParams
00040 {
00041         BT_CONSTRAINT_ERP=1,
00042         BT_CONSTRAINT_STOP_ERP,
00043         BT_CONSTRAINT_CFM,
00044         BT_CONSTRAINT_STOP_CFM
00045 };
00046 
00047 #if 1
00048         #define btAssertConstrParams(_par) btAssert(_par) 
00049 #else
00050         #define btAssertConstrParams(_par)
00051 #endif
00052 
00053 
00055 class btTypedConstraint : public btTypedObject
00056 {
00057         int     m_userConstraintType;
00058 
00059         union
00060         {
00061                 int     m_userConstraintId;
00062                 void* m_userConstraintPtr;
00063         };
00064 
00065         btScalar        m_breakingImpulseThreshold;
00066         bool            m_isEnabled;
00067 
00068 
00069         bool m_needsFeedback;
00070 
00071         btTypedConstraint&      operator=(btTypedConstraint&    other)
00072         {
00073                 btAssert(0);
00074                 (void) other;
00075                 return *this;
00076         }
00077 
00078 protected:
00079         btRigidBody&    m_rbA;
00080         btRigidBody&    m_rbB;
00081         btScalar        m_appliedImpulse;
00082         btScalar        m_dbgDrawSize;
00083 
00085         btScalar getMotorFactor(btScalar pos, btScalar lowLim, btScalar uppLim, btScalar vel, btScalar timeFact);
00086         
00087         static btRigidBody& getFixedBody();
00088 
00089 public:
00090 
00091         virtual ~btTypedConstraint() {};
00092         btTypedConstraint(btTypedConstraintType type, btRigidBody& rbA);
00093         btTypedConstraint(btTypedConstraintType type, btRigidBody& rbA,btRigidBody& rbB);
00094 
00095         struct btConstraintInfo1 {
00096                 int m_numConstraintRows,nub;
00097         };
00098 
00099         struct btConstraintInfo2 {
00100                 // integrator parameters: frames per second (1/stepsize), default error
00101                 // reduction parameter (0..1).
00102                 btScalar fps,erp;
00103 
00104                 // for the first and second body, pointers to two (linear and angular)
00105                 // n*3 jacobian sub matrices, stored by rows. these matrices will have
00106                 // been initialized to 0 on entry. if the second body is zero then the
00107                 // J2xx pointers may be 0.
00108                 btScalar *m_J1linearAxis,*m_J1angularAxis,*m_J2linearAxis,*m_J2angularAxis;
00109 
00110                 // elements to jump from one row to the next in J's
00111                 int rowskip;
00112 
00113                 // right hand sides of the equation J*v = c + cfm * lambda. cfm is the
00114                 // "constraint force mixing" vector. c is set to zero on entry, cfm is
00115                 // set to a constant value (typically very small or zero) value on entry.
00116                 btScalar *m_constraintError,*cfm;
00117 
00118                 // lo and hi limits for variables (set to -/+ infinity on entry).
00119                 btScalar *m_lowerLimit,*m_upperLimit;
00120 
00121                 // findex vector for variables. see the LCP solver interface for a
00122                 // description of what this does. this is set to -1 on entry.
00123                 // note that the returned indexes are relative to the first index of
00124                 // the constraint.
00125                 int *findex;
00126                 // number of solver iterations
00127                 int m_numIterations;
00128 
00129                 //damping of the velocity
00130                 btScalar        m_damping;
00131         };
00132 
00134         virtual void    buildJacobian() {};
00135 
00137         virtual void    setupSolverConstraint(btConstraintArray& ca, int solverBodyA,int solverBodyB, btScalar timeStep)
00138         {
00139         (void)ca;
00140         (void)solverBodyA;
00141         (void)solverBodyB;
00142         (void)timeStep;
00143         }
00144         
00146         virtual void getInfo1 (btConstraintInfo1* info)=0;
00147 
00149         virtual void getInfo2 (btConstraintInfo2* info)=0;
00150 
00152         void    internalSetAppliedImpulse(btScalar appliedImpulse)
00153         {
00154                 m_appliedImpulse = appliedImpulse;
00155         }
00157         btScalar        internalGetAppliedImpulse()
00158         {
00159                 return m_appliedImpulse;
00160         }
00161 
00162 
00163         btScalar        getBreakingImpulseThreshold() const
00164         {
00165                 return  m_breakingImpulseThreshold;
00166         }
00167 
00168         void    setBreakingImpulseThreshold(btScalar threshold)
00169         {
00170                 m_breakingImpulseThreshold = threshold;
00171         }
00172 
00173         bool    isEnabled() const
00174         {
00175                 return m_isEnabled;
00176         }
00177 
00178         void    setEnabled(bool enabled)
00179         {
00180                 m_isEnabled=enabled;
00181         }
00182 
00183 
00185         virtual void    solveConstraintObsolete(btRigidBody& /*bodyA*/,btRigidBody& /*bodyB*/,btScalar  /*timeStep*/) {};
00186 
00187         
00188         const btRigidBody& getRigidBodyA() const
00189         {
00190                 return m_rbA;
00191         }
00192         const btRigidBody& getRigidBodyB() const
00193         {
00194                 return m_rbB;
00195         }
00196 
00197         btRigidBody& getRigidBodyA() 
00198         {
00199                 return m_rbA;
00200         }
00201         btRigidBody& getRigidBodyB()
00202         {
00203                 return m_rbB;
00204         }
00205 
00206         int getUserConstraintType() const
00207         {
00208                 return m_userConstraintType ;
00209         }
00210 
00211         void    setUserConstraintType(int userConstraintType)
00212         {
00213                 m_userConstraintType = userConstraintType;
00214         };
00215 
00216         void    setUserConstraintId(int uid)
00217         {
00218                 m_userConstraintId = uid;
00219         }
00220 
00221         int getUserConstraintId() const
00222         {
00223                 return m_userConstraintId;
00224         }
00225 
00226         void    setUserConstraintPtr(void* ptr)
00227         {
00228                 m_userConstraintPtr = ptr;
00229         }
00230 
00231         void*   getUserConstraintPtr()
00232         {
00233                 return m_userConstraintPtr;
00234         }
00235 
00236         int getUid() const
00237         {
00238                 return m_userConstraintId;   
00239         } 
00240 
00241         bool    needsFeedback() const
00242         {
00243                 return m_needsFeedback;
00244         }
00245 
00248         void    enableFeedback(bool needsFeedback)
00249         {
00250                 m_needsFeedback = needsFeedback;
00251         }
00252 
00255         btScalar        getAppliedImpulse() const
00256         {
00257                 btAssert(m_needsFeedback);
00258                 return m_appliedImpulse;
00259         }
00260 
00261         btTypedConstraintType getConstraintType () const
00262         {
00263                 return btTypedConstraintType(m_objectType);
00264         }
00265         
00266         void setDbgDrawSize(btScalar dbgDrawSize)
00267         {
00268                 m_dbgDrawSize = dbgDrawSize;
00269         }
00270         btScalar getDbgDrawSize()
00271         {
00272                 return m_dbgDrawSize;
00273         }
00274 
00277         virtual void    setParam(int num, btScalar value, int axis = -1) = 0;
00278 
00280         virtual btScalar getParam(int num, int axis = -1) const = 0;
00281         
00282         virtual int     calculateSerializeBufferSize() const;
00283 
00285         virtual const char*     serialize(void* dataBuffer, btSerializer* serializer) const;
00286 
00287 };
00288 
00289 // returns angle in range [-SIMD_2_PI, SIMD_2_PI], closest to one of the limits 
00290 // all arguments should be normalized angles (i.e. in range [-SIMD_PI, SIMD_PI])
00291 SIMD_FORCE_INLINE btScalar btAdjustAngleToLimits(btScalar angleInRadians, btScalar angleLowerLimitInRadians, btScalar angleUpperLimitInRadians)
00292 {
00293         if(angleLowerLimitInRadians >= angleUpperLimitInRadians)
00294         {
00295                 return angleInRadians;
00296         }
00297         else if(angleInRadians < angleLowerLimitInRadians)
00298         {
00299                 btScalar diffLo = btFabs(btNormalizeAngle(angleLowerLimitInRadians - angleInRadians));
00300                 btScalar diffHi = btFabs(btNormalizeAngle(angleUpperLimitInRadians - angleInRadians));
00301                 return (diffLo < diffHi) ? angleInRadians : (angleInRadians + SIMD_2_PI);
00302         }
00303         else if(angleInRadians > angleUpperLimitInRadians)
00304         {
00305                 btScalar diffHi = btFabs(btNormalizeAngle(angleInRadians - angleUpperLimitInRadians));
00306                 btScalar diffLo = btFabs(btNormalizeAngle(angleInRadians - angleLowerLimitInRadians));
00307                 return (diffLo < diffHi) ? (angleInRadians - SIMD_2_PI) : angleInRadians;
00308         }
00309         else
00310         {
00311                 return angleInRadians;
00312         }
00313 }
00314 
00316 struct  btTypedConstraintData
00317 {
00318         btRigidBodyData         *m_rbA;
00319         btRigidBodyData         *m_rbB;
00320         char    *m_name;
00321 
00322         int     m_objectType;
00323         int     m_userConstraintType;
00324         int     m_userConstraintId;
00325         int     m_needsFeedback;
00326 
00327         float   m_appliedImpulse;
00328         float   m_dbgDrawSize;
00329 
00330         int     m_disableCollisionsBetweenLinkedBodies;
00331         char    m_pad4[4];
00332         
00333 };
00334 
00335 SIMD_FORCE_INLINE       int     btTypedConstraint::calculateSerializeBufferSize() const
00336 {
00337         return sizeof(btTypedConstraintData);
00338 }
00339 
00340 
00341 
00342 class btAngularLimit
00343 {
00344 private:
00345         btScalar 
00346                 m_center,
00347                 m_halfRange,
00348                 m_softness,
00349                 m_biasFactor,
00350                 m_relaxationFactor,
00351                 m_correction,
00352                 m_sign;
00353 
00354         bool
00355                 m_solveLimit;
00356 
00357 public:
00359         btAngularLimit()
00360                 :m_center(0.0f),
00361                 m_halfRange(-1.0f),
00362                 m_softness(0.9f),
00363                 m_biasFactor(0.3f),
00364                 m_relaxationFactor(1.0f),
00365                 m_correction(0.0f),
00366                 m_sign(0.0f),
00367                 m_solveLimit(false)
00368         {}
00369 
00373         void set(btScalar low, btScalar high, btScalar _softness = 0.9f, btScalar _biasFactor = 0.3f, btScalar _relaxationFactor = 1.0f);
00374 
00377         void test(const btScalar angle);
00378 
00380         inline btScalar getSoftness() const
00381         {
00382                 return m_softness;
00383         }
00384 
00386         inline btScalar getBiasFactor() const
00387         {
00388                 return m_biasFactor;
00389         }
00390 
00392         inline btScalar getRelaxationFactor() const
00393         {
00394                 return m_relaxationFactor;
00395         }
00396 
00398         inline btScalar getCorrection() const
00399         {
00400                 return m_correction;
00401         }
00402 
00404         inline btScalar getSign() const
00405         {
00406                 return m_sign;
00407         }
00408 
00410         inline btScalar getHalfRange() const
00411         {
00412                 return m_halfRange;
00413         }
00414 
00416         inline bool isLimit() const
00417         {
00418                 return m_solveLimit;
00419         }
00420 
00423         void fit(btScalar& angle) const;
00424 
00426         btScalar getError() const;
00427 
00428         btScalar getLow() const;
00429 
00430         btScalar getHigh() const;
00431 
00432 };
00433 
00434 
00435 
00436 #endif //BT_TYPED_CONSTRAINT_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


bullet
Author(s): Erwin Coumans, ROS package maintained by Tully Foote
autogenerated on Wed Oct 31 2012 07:54:31