Blender V2.61 - r43446

CcdPhysicsController.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 
00021 #ifndef BULLET2_PHYSICSCONTROLLER_H
00022 #define BULLET2_PHYSICSCONTROLLER_H
00023 
00024 #include <vector>
00025 #include <map>
00026 
00027 #include "PHY_IPhysicsController.h"
00028 
00031 #include "btBulletDynamicsCommon.h"
00032 #include "LinearMath/btTransform.h"
00033 
00034 #include "PHY_IMotionState.h"
00035 
00036 extern float gDeactivationTime;
00037 extern float gLinearSleepingTreshold;
00038 extern float gAngularSleepingTreshold;
00039 extern bool gDisableDeactivation;
00040 class CcdPhysicsEnvironment;
00041 class btMotionState;
00042 class RAS_MeshObject;
00043 struct DerivedMesh;
00044 class btCollisionShape;
00045 
00046 
00047 #define CCD_BSB_SHAPE_MATCHING  2
00048 #define CCD_BSB_BENDING_CONSTRAINTS 8
00049 #define CCD_BSB_AERO_VPOINT 16 /* aero model, Vertex normals are oriented toward velocity*/
00050 #define CCD_BSB_AERO_VTWOSIDE 32 /* aero model, Vertex normals are flipped to match velocity */
00051 
00052 /* BulletSoftBody.collisionflags */
00053 #define CCD_BSB_COL_SDF_RS  2 /* SDF based rigid vs soft */
00054 #define CCD_BSB_COL_CL_RS   4 /* Cluster based rigid vs soft */
00055 #define CCD_BSB_COL_CL_SS   8 /* Cluster based soft vs soft */
00056 #define CCD_BSB_COL_VF_SS   16 /* Vertex/Face based soft vs soft */
00057 
00058 
00059 // Shape contructor
00060 // It contains all the information needed to create a simple bullet shape at runtime
00061 class CcdShapeConstructionInfo
00062 {
00063 public:
00064     struct UVco 
00065     {
00066         float uv[2];
00067     };
00068     
00069     static CcdShapeConstructionInfo* FindMesh(class RAS_MeshObject* mesh, struct DerivedMesh* dm, bool polytope);
00070 
00071     CcdShapeConstructionInfo() :
00072         m_shapeType(PHY_SHAPE_NONE),
00073         m_radius(1.0),
00074         m_height(1.0),
00075         m_halfExtend(0.f,0.f,0.f),
00076         m_childScale(1.0f,1.0f,1.0f),
00077         m_userData(NULL),
00078         m_refCount(1),
00079         m_meshObject(NULL),
00080         m_unscaledShape(NULL),
00081         m_forceReInstance(false),
00082         m_weldingThreshold1(0.f),
00083         m_shapeProxy(NULL)
00084     {
00085         m_childTrans.setIdentity();
00086     }
00087 
00088     ~CcdShapeConstructionInfo();
00089 
00090     CcdShapeConstructionInfo* AddRef()
00091     { 
00092         m_refCount++;
00093         return this;
00094     }
00095 
00096     int Release()
00097     {
00098         if (--m_refCount > 0)
00099             return m_refCount;
00100         delete this;
00101         return 0;
00102     }
00103 
00104     bool IsUnused(void)
00105     {
00106         return (m_meshObject==NULL && m_shapeArray.size() == 0 && m_shapeProxy == NULL);
00107     }
00108 
00109     void AddShape(CcdShapeConstructionInfo* shapeInfo);
00110 
00111     btTriangleMeshShape* GetMeshShape(void)
00112     {
00113         return (m_unscaledShape);
00114     }
00115     CcdShapeConstructionInfo* GetChildShape(int i)
00116     {
00117         if (i < 0 || i >= (int)m_shapeArray.size())
00118             return NULL;
00119 
00120         return m_shapeArray.at(i);
00121     }
00122     int FindChildShape(CcdShapeConstructionInfo* shapeInfo, void* userData)
00123     {
00124         if (shapeInfo == NULL)
00125             return -1;
00126         for (int i=0; i<(int)m_shapeArray.size(); i++)
00127         {
00128             CcdShapeConstructionInfo* childInfo = m_shapeArray.at(i);
00129             if ((userData == NULL || userData == childInfo->m_userData) &&
00130                 (childInfo == shapeInfo ||
00131                  (childInfo->m_shapeType == PHY_SHAPE_PROXY && 
00132                   childInfo->m_shapeProxy == shapeInfo)))
00133                 return i;
00134         }
00135         return -1;
00136     }
00137 
00138     bool RemoveChildShape(int i)
00139     {
00140         if (i < 0 || i >= (int)m_shapeArray.size())
00141             return false;
00142         m_shapeArray.at(i)->Release();
00143         if (i < (int)m_shapeArray.size()-1)
00144             m_shapeArray[i] = m_shapeArray.back();
00145         m_shapeArray.pop_back();
00146         return true;
00147     }
00148 
00149     bool SetMesh(class RAS_MeshObject* mesh, struct DerivedMesh* dm, bool polytope);
00150     RAS_MeshObject* GetMesh(void)
00151     {
00152         return m_meshObject;
00153     }
00154 
00155     bool UpdateMesh(class KX_GameObject* gameobj, class RAS_MeshObject* mesh);
00156 
00157 
00158     bool SetProxy(CcdShapeConstructionInfo* shapeInfo);
00159     CcdShapeConstructionInfo* GetProxy(void)
00160     {
00161         return m_shapeProxy;
00162     }
00163 
00164     btCollisionShape* CreateBulletShape(btScalar margin, bool useGimpact=false, bool useBvh=true);
00165 
00166     // member variables
00167     PHY_ShapeType           m_shapeType;
00168     btScalar                m_radius;
00169     btScalar                m_height;
00170     btVector3               m_halfExtend;
00171     btTransform             m_childTrans;
00172     btVector3               m_childScale;
00173     void*                   m_userData; 
00174     btAlignedObjectArray<btScalar>  m_vertexArray;  // Contains both vertex array for polytope shape and
00175                                             // triangle array for concave mesh shape. Each vertex is 3 consecutive values
00176                                             // In this case a triangle is made of 3 consecutive points
00177     std::vector<int>        m_polygonIndexArray;    // Contains the array of polygon index in the 
00178                                                     // original mesh that correspond to shape triangles.
00179                                                     // only set for concave mesh shape.
00180     
00181     std::vector<int>        m_triFaceArray; // Contains an array of triplets of face indicies
00182                                             // quads turn into 2 tris
00183 
00184     std::vector<UVco>       m_triFaceUVcoArray; // Contains an array of pair of UV coordinate for each vertex of faces
00185                                                 // quads turn into 2 tris
00186 
00187     void    setVertexWeldingThreshold1(float threshold)
00188     {
00189         m_weldingThreshold1  = threshold*threshold;
00190     }
00191 protected:
00192     static std::map<RAS_MeshObject*, CcdShapeConstructionInfo*> m_meshShapeMap;
00193     int                     m_refCount;     // this class is shared between replicas
00194                                             // keep track of users so that we can release it 
00195     RAS_MeshObject* m_meshObject;           // Keep a pointer to the original mesh 
00196     btBvhTriangleMeshShape* m_unscaledShape;// holds the shared unscale BVH mesh shape, 
00197                                             // the actual shape is of type btScaledBvhTriangleMeshShape
00198     std::vector<CcdShapeConstructionInfo*> m_shapeArray;    // for compound shapes
00199     bool    m_forceReInstance; //use gimpact for concave dynamic/moving collision detection
00200     float   m_weldingThreshold1;    //welding closeby vertices together can improve softbody stability etc.
00201     CcdShapeConstructionInfo* m_shapeProxy; // only used for PHY_SHAPE_PROXY, pointer to actual shape info
00202 
00203 
00204 #ifdef WITH_CXX_GUARDEDALLOC
00205 public:
00206     void *operator new(size_t num_bytes) { return MEM_mallocN(num_bytes, "GE:CcdShapeConstructionInfo"); }
00207     void operator delete( void *mem ) { MEM_freeN(mem); }
00208 #endif
00209 };
00210 
00211 struct CcdConstructionInfo
00212 {
00213 
00217     enum CollisionFilterGroups
00218     {
00219         DefaultFilter = 1,
00220         StaticFilter = 2,
00221         KinematicFilter = 4,
00222         DebrisFilter = 8,
00223         SensorFilter = 16,
00224         AllFilter = DefaultFilter | StaticFilter | KinematicFilter | DebrisFilter | SensorFilter,
00225     };
00226 
00227 
00228     CcdConstructionInfo()
00229         :m_localInertiaTensor(1.f, 1.f, 1.f),
00230         m_gravity(0,0,0),
00231         m_scaling(1.f,1.f,1.f),
00232         m_mass(0.f),
00233         m_clamp_vel_min(-1.f),
00234         m_clamp_vel_max(-1.f),
00235         m_restitution(0.1f),
00236         m_friction(0.5f),
00237         m_linearDamping(0.1f),
00238         m_angularDamping(0.1f),
00239         m_margin(0.06f),
00240         m_gamesoftFlag(0),
00241         m_soft_linStiff(1.f),
00242         m_soft_angStiff(1.f),
00243         m_soft_volume(1.f),
00244         m_soft_viterations(0),
00245         m_soft_piterations(1),
00246         m_soft_diterations(0),
00247         m_soft_citerations(4),
00248         m_soft_kSRHR_CL(0.1f),
00249         m_soft_kSKHR_CL(1.f),
00250         m_soft_kSSHR_CL(0.5f),
00251         m_soft_kSR_SPLT_CL(0.5f),
00252         m_soft_kSK_SPLT_CL(0.5f),
00253         m_soft_kSS_SPLT_CL(0.5f),
00254         m_soft_kVCF(1.f),
00255         m_soft_kDP(0.f),
00256         m_soft_kDG(0.f),
00257         m_soft_kLF(0.f),
00258         m_soft_kPR(0.f),
00259         m_soft_kVC(0.f),
00260         m_soft_kDF(0.2f),
00261         m_soft_kMT(0),
00262         m_soft_kCHR(1.0f),
00263         m_soft_kKHR(0.1f),
00264         m_soft_kSHR(1.0f),
00265         m_soft_kAHR(0.7f),
00266         m_collisionFlags(0),
00267         m_bRigid(false),
00268         m_bSoft(false),
00269         m_bSensor(false),
00270         m_bGimpact(false),
00271         m_collisionFilterGroup(DefaultFilter),
00272         m_collisionFilterMask(AllFilter),
00273         m_collisionShape(0),
00274         m_MotionState(0),
00275         m_shapeInfo(0),
00276         m_physicsEnv(0),
00277         m_inertiaFactor(1.f),
00278         m_do_anisotropic(false),
00279         m_anisotropicFriction(1.f,1.f,1.f),
00280         m_do_fh(false),
00281         m_do_rot_fh(false),
00282         m_fh_spring(0.f),
00283         m_fh_damping(0.f),
00284         m_fh_distance(1.f),
00285         m_fh_normal(false),
00286         m_contactProcessingThreshold(1e10f)
00287     {
00288 
00289     }
00290 
00291     btVector3   m_localInertiaTensor;
00292     btVector3   m_gravity;
00293     btVector3   m_scaling;
00294     btScalar    m_mass;
00295     btScalar    m_clamp_vel_min;  
00296     btScalar    m_clamp_vel_max;  
00297     btScalar    m_restitution;
00298     btScalar    m_friction;
00299     btScalar    m_linearDamping;
00300     btScalar    m_angularDamping;
00301     btScalar    m_margin;
00302 
00304     int     m_gamesoftFlag;
00305     float   m_soft_linStiff;            /* linear stiffness 0..1 */
00306     float   m_soft_angStiff;        /* angular stiffness 0..1 */
00307     float   m_soft_volume;          /* volume preservation 0..1 */
00308 
00309     int     m_soft_viterations;     /* Velocities solver iterations */
00310     int     m_soft_piterations;     /* Positions solver iterations */
00311     int     m_soft_diterations;     /* Drift solver iterations */
00312     int     m_soft_citerations;     /* Cluster solver iterations */
00313 
00314     float   m_soft_kSRHR_CL;        /* Soft vs rigid hardness [0,1] (cluster only) */
00315     float   m_soft_kSKHR_CL;        /* Soft vs kinetic hardness [0,1] (cluster only) */
00316     float   m_soft_kSSHR_CL;        /* Soft vs soft hardness [0,1] (cluster only) */
00317     float   m_soft_kSR_SPLT_CL; /* Soft vs rigid impulse split [0,1] (cluster only) */
00318 
00319     float   m_soft_kSK_SPLT_CL; /* Soft vs rigid impulse split [0,1] (cluster only) */
00320     float   m_soft_kSS_SPLT_CL; /* Soft vs rigid impulse split [0,1] (cluster only) */
00321     float   m_soft_kVCF;            /* Velocities correction factor (Baumgarte) */
00322     float   m_soft_kDP;         /* Damping coefficient [0,1] */
00323 
00324     float   m_soft_kDG;         /* Drag coefficient [0,+inf] */
00325     float   m_soft_kLF;         /* Lift coefficient [0,+inf] */
00326     float   m_soft_kPR;         /* Pressure coefficient [-inf,+inf] */
00327     float   m_soft_kVC;         /* Volume conversation coefficient [0,+inf] */
00328 
00329     float   m_soft_kDF;         /* Dynamic friction coefficient [0,1] */
00330     float   m_soft_kMT;         /* Pose matching coefficient [0,1] */
00331     float   m_soft_kCHR;            /* Rigid contacts hardness [0,1] */
00332     float   m_soft_kKHR;            /* Kinetic contacts hardness [0,1] */
00333 
00334     float   m_soft_kSHR;            /* Soft contacts hardness [0,1] */
00335     float   m_soft_kAHR;            /* Anchors hardness [0,1] */
00336     int     m_soft_collisionflags;  /* Vertex/Face or Signed Distance Field(SDF) or Clusters, Soft versus Soft or Rigid */
00337     int     m_soft_numclusteriterations;    /* number of iterations to refine collision clusters*/
00339 
00340 
00341 
00342     int         m_collisionFlags;
00343     bool        m_bRigid;
00344     bool        m_bSoft;
00345     bool        m_bSensor;
00346     bool        m_bGimpact;         // use Gimpact for mesh body
00347 
00353     short int   m_collisionFilterGroup;
00354     short int   m_collisionFilterMask;
00355 
00358     class btCollisionShape* m_collisionShape;
00359     class PHY_IMotionState* m_MotionState;
00360     class CcdShapeConstructionInfo* m_shapeInfo;
00361     
00362     CcdPhysicsEnvironment*  m_physicsEnv; //needed for self-replication
00363     float   m_inertiaFactor;//tweak the inertia (hooked up to Blender 'formfactor'
00364     bool    m_do_anisotropic;
00365     btVector3 m_anisotropicFriction;
00366 
00367     bool        m_do_fh;                 
00368     bool        m_do_rot_fh;             
00369     btScalar    m_fh_spring;             
00370     btScalar    m_fh_damping;            
00371     btScalar    m_fh_distance;           
00372     bool        m_fh_normal;             
00373     float       m_radius;//for fh backwards compatibility
00374     
00380     float       m_contactProcessingThreshold;
00381 
00382 };
00383 
00384 
00385 class btRigidBody;
00386 class btCollisionObject;
00387 class btSoftBody;
00388 
00390 class CcdPhysicsController : public PHY_IPhysicsController  
00391 {
00392 protected:
00393     btCollisionObject* m_object;
00394     
00395 
00396     class PHY_IMotionState*     m_MotionState;
00397     btMotionState*  m_bulletMotionState;
00398     class btCollisionShape* m_collisionShape;
00399     class CcdShapeConstructionInfo* m_shapeInfo;
00400 
00401     friend class CcdPhysicsEnvironment; // needed when updating the controller
00402 
00403     //some book keeping for replication
00404     bool    m_softbodyMappingDone;
00405     bool    m_softBodyTransformInitialized;
00406     bool    m_prototypeTransformInitialized;
00407     btTransform m_softbodyStartTrans;
00408 
00409 
00410     void*       m_newClientInfo;
00411     int         m_registerCount;    // needed when multiple sensors use the same controller
00412     CcdConstructionInfo m_cci;//needed for replication
00413 
00414     CcdPhysicsController* m_parentCtrl;
00415 
00416     void GetWorldOrientation(btMatrix3x3& mat);
00417 
00418     void CreateRigidbody();
00419     bool CreateSoftbody();
00420 
00421     bool Register() { 
00422         return (m_registerCount++ == 0) ? true : false;
00423     }
00424     bool Unregister() {
00425         return (--m_registerCount == 0) ? true : false;
00426     }
00427 
00428     void setWorldOrientation(const btMatrix3x3& mat);
00429     void forceWorldTransform(const btMatrix3x3& mat, const btVector3& pos);
00430 
00431     public:
00432     
00433         int             m_collisionDelay;
00434     
00435 
00436         CcdPhysicsController (const CcdConstructionInfo& ci);
00437 
00438         bool DeleteControllerShape();
00439         bool ReplaceControllerShape(btCollisionShape *newShape);
00440 
00441         virtual ~CcdPhysicsController();
00442 
00443         CcdConstructionInfo& getConstructionInfo()
00444         {
00445             return m_cci;
00446         }
00447         const CcdConstructionInfo& getConstructionInfo() const
00448         {
00449             return m_cci;
00450         }
00451 
00452 
00453         btRigidBody* GetRigidBody();
00454         btCollisionObject*  GetCollisionObject();
00455         btSoftBody* GetSoftBody();
00456 
00457         CcdShapeConstructionInfo* GetShapeInfo() { return m_shapeInfo; }
00458 
00459         btCollisionShape*   GetCollisionShape() { 
00460             return m_object->getCollisionShape();
00461         }
00463         // PHY_IPhysicsController interface
00465 
00466 
00470         virtual bool        SynchronizeMotionStates(float time);
00475         virtual void        WriteMotionStateToDynamics(bool nondynaonly);
00476         virtual void        WriteDynamicsToMotionState();
00477 
00478         // controller replication
00479         virtual void        PostProcessReplica(class PHY_IMotionState* motionstate,class PHY_IPhysicsController* parentctrl);
00480         virtual void        SetPhysicsEnvironment(class PHY_IPhysicsEnvironment *env);
00481 
00482         // kinematic methods
00483         virtual void        RelativeTranslate(float dlocX,float dlocY,float dlocZ,bool local);
00484         virtual void        RelativeRotate(const float drot[9],bool local);
00485         virtual void        getOrientation(float &quatImag0,float &quatImag1,float &quatImag2,float &quatReal);
00486         virtual void        setOrientation(float quatImag0,float quatImag1,float quatImag2,float quatReal);
00487         virtual void        setPosition(float posX,float posY,float posZ);
00488         virtual void        getPosition(PHY__Vector3&   pos) const;
00489 
00490         virtual void        setScaling(float scaleX,float scaleY,float scaleZ);
00491         
00492         // physics methods
00493         virtual void        ApplyTorque(float torqueX,float torqueY,float torqueZ,bool local);
00494         virtual void        ApplyForce(float forceX,float forceY,float forceZ,bool local);
00495         virtual void        SetAngularVelocity(float ang_velX,float ang_velY,float ang_velZ,bool local);
00496         virtual void        SetLinearVelocity(float lin_velX,float lin_velY,float lin_velZ,bool local);
00497         virtual void        applyImpulse(float attachX,float attachY,float attachZ, float impulseX,float impulseY,float impulseZ);
00498         virtual void        SetActive(bool active);
00499 
00500         // reading out information from physics
00501         virtual void        GetLinearVelocity(float& linvX,float& linvY,float& linvZ);
00502         virtual void        GetAngularVelocity(float& angVelX,float& angVelY,float& angVelZ);
00503         virtual void        GetVelocity(const float posX,const float posY,const float posZ,float& linvX,float& linvY,float& linvZ); 
00504         virtual void        getReactionForce(float& forceX,float& forceY,float& forceZ);
00505 
00506         // dyna's that are rigidbody are free in orientation, dyna's with non-rigidbody are restricted 
00507         virtual void        setRigidBody(bool rigid);
00508 
00509         
00510         virtual void        resolveCombinedVelocities(float linvelX,float linvelY,float linvelZ,float angVelX,float angVelY,float angVelZ);
00511 
00512         // clientinfo for raycasts for example
00513         virtual void*               getNewClientInfo();
00514         virtual void                setNewClientInfo(void* clientinfo);
00515         virtual PHY_IPhysicsController* GetReplica();
00516         
00518         short int   GetCollisionFilterGroup() const
00519         {
00520             return m_cci.m_collisionFilterGroup;
00521         }
00523         short int   GetCollisionFilterMask() const
00524         {
00525             return m_cci.m_collisionFilterMask;
00526         }
00527 
00528         virtual void    calcXform() {} ;
00529         virtual void SetMargin(float margin) 
00530         {
00531             if (m_collisionShape)
00532                 m_collisionShape->setMargin(btScalar(margin));
00533         }
00534         virtual float GetMargin() const 
00535         {
00536             return (m_collisionShape) ? m_collisionShape->getMargin() : 0.f;
00537         }
00538         virtual float GetRadius() const 
00539         { 
00540             // this is not the actual shape radius, it's only used for Fh support
00541             return m_cci.m_radius;
00542         }
00543         virtual void  SetRadius(float margin) 
00544         {
00545             if (m_collisionShape && m_collisionShape->getShapeType() == SPHERE_SHAPE_PROXYTYPE)
00546             {
00547                 btSphereShape* sphereShape = static_cast<btSphereShape*>(m_collisionShape);
00548                 sphereShape->setUnscaledRadius(margin);
00549             }
00550             m_cci.m_radius = margin;
00551         }
00552         
00553         // velocity clamping
00554         virtual void SetLinVelocityMin(float val) 
00555         {
00556             m_cci.m_clamp_vel_min= val;
00557         }
00558         virtual float GetLinVelocityMin() const 
00559         {
00560             return m_cci.m_clamp_vel_min;
00561         }
00562         virtual void SetLinVelocityMax(float val) 
00563         {
00564             m_cci.m_clamp_vel_max= val;
00565         }
00566         virtual float GetLinVelocityMax() const 
00567         {
00568             return m_cci.m_clamp_vel_max;
00569         }
00570 
00571         bool    wantsSleeping();
00572 
00573         void    UpdateDeactivation(float timeStep);
00574 
00575         void    SetCenterOfMassTransform(btTransform& xform);
00576 
00577         static btTransform& GetTransformFromMotionState(PHY_IMotionState* motionState);
00578 
00579         void    setAabb(const btVector3& aabbMin,const btVector3& aabbMax);
00580 
00581 
00582         class   PHY_IMotionState*           GetMotionState()
00583         {
00584             return m_MotionState;
00585         }
00586 
00587         const class PHY_IMotionState*           GetMotionState() const
00588         {
00589             return m_MotionState;
00590         }
00591 
00592         class CcdPhysicsEnvironment* GetPhysicsEnvironment()
00593         {
00594             return m_cci.m_physicsEnv;
00595         }
00596 
00597         void    setParentCtrl(CcdPhysicsController* parentCtrl)
00598         {
00599             m_parentCtrl = parentCtrl;
00600         }
00601 
00602         CcdPhysicsController*   getParentCtrl()
00603         {
00604             return m_parentCtrl;
00605         }
00606 
00607         const CcdPhysicsController* getParentCtrl() const
00608         {
00609             return m_parentCtrl;
00610         }
00611 
00612         virtual const char* getName()
00613         {
00614             return 0;
00615         }
00616 
00617 #ifdef WITH_CXX_GUARDEDALLOC
00618 public:
00619     void *operator new(size_t num_bytes) { return MEM_mallocN(num_bytes, "GE:CcdPhysicsController"); }
00620     void operator delete( void *mem ) { MEM_freeN(mem); }
00621 #endif
00622 };
00623 
00624 
00625 
00626 
00628 class   DefaultMotionState : public PHY_IMotionState
00629 
00630 {
00631     public:
00632         DefaultMotionState();
00633 
00634         virtual ~DefaultMotionState();
00635 
00636         virtual void    getWorldPosition(float& posX,float& posY,float& posZ);
00637         virtual void    getWorldScaling(float& scaleX,float& scaleY,float& scaleZ);
00638         virtual void    getWorldOrientation(float& quatIma0,float& quatIma1,float& quatIma2,float& quatReal);
00639         
00640         virtual void    setWorldPosition(float posX,float posY,float posZ);
00641         virtual void    setWorldOrientation(float quatIma0,float quatIma1,float quatIma2,float quatReal);
00642         virtual void    getWorldOrientation(float* ori);
00643         virtual void    setWorldOrientation(const float* ori);
00644         
00645         virtual void    calculateWorldTransformations();
00646         
00647         btTransform m_worldTransform;
00648         btVector3       m_localScaling;
00649     
00650     
00651 #ifdef WITH_CXX_GUARDEDALLOC
00652 public:
00653     void *operator new(size_t num_bytes) { return MEM_mallocN(num_bytes, "GE:DefaultMotionState"); }
00654     void operator delete( void *mem ) { MEM_freeN(mem); }
00655 #endif
00656 };
00657 
00658 
00659 #endif //BULLET2_PHYSICSCONTROLLER_H