btCollisionObject.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 #ifndef BT_COLLISION_OBJECT_H
00017 #define BT_COLLISION_OBJECT_H
00018 
00019 #include "LinearMath/btTransform.h"
00020 
00021 //island management, m_activationState1
00022 #define ACTIVE_TAG 1
00023 #define ISLAND_SLEEPING 2
00024 #define WANTS_DEACTIVATION 3
00025 #define DISABLE_DEACTIVATION 4
00026 #define DISABLE_SIMULATION 5
00027 
00028 struct  btBroadphaseProxy;
00029 class   btCollisionShape;
00030 struct btCollisionShapeData;
00031 #include "LinearMath/btMotionState.h"
00032 #include "LinearMath/btAlignedAllocator.h"
00033 #include "LinearMath/btAlignedObjectArray.h"
00034 
00035 typedef btAlignedObjectArray<class btCollisionObject*> btCollisionObjectArray;
00036 
00037 #ifdef BT_USE_DOUBLE_PRECISION
00038 #define btCollisionObjectData btCollisionObjectDoubleData
00039 #define btCollisionObjectDataName "btCollisionObjectDoubleData"
00040 #else
00041 #define btCollisionObjectData btCollisionObjectFloatData
00042 #define btCollisionObjectDataName "btCollisionObjectFloatData"
00043 #endif
00044 
00045 
00049 ATTRIBUTE_ALIGNED16(class)      btCollisionObject
00050 {
00051 
00052 protected:
00053 
00054         btTransform     m_worldTransform;
00055 
00058         btTransform     m_interpolationWorldTransform;
00059         //those two are experimental: just added for bullet time effect, so you can still apply impulses (directly modifying velocities) 
00060         //without destroying the continuous interpolated motion (which uses this interpolation velocities)
00061         btVector3       m_interpolationLinearVelocity;
00062         btVector3       m_interpolationAngularVelocity;
00063         
00064         btVector3       m_anisotropicFriction;
00065         int                     m_hasAnisotropicFriction;
00066         btScalar        m_contactProcessingThreshold;   
00067 
00068         btBroadphaseProxy*              m_broadphaseHandle;
00069         btCollisionShape*               m_collisionShape;
00071         void*                                   m_extensionPointer;
00072         
00076         btCollisionShape*               m_rootCollisionShape;
00077 
00078         int                             m_collisionFlags;
00079 
00080         int                             m_islandTag1;
00081         int                             m_companionId;
00082 
00083         int                             m_activationState1;
00084         btScalar                        m_deactivationTime;
00085 
00086         btScalar                m_friction;
00087         btScalar                m_restitution;
00088 
00091         int                             m_internalType;
00092 
00094         void*                   m_userObjectPointer;
00095 
00097         btScalar                m_hitFraction; 
00098         
00100         btScalar                m_ccdSweptSphereRadius;
00101 
00103         btScalar                m_ccdMotionThreshold;
00104         
00106         int                     m_checkCollideWith;
00107 
00108         virtual bool    checkCollideWithOverride(btCollisionObject* /* co */)
00109         {
00110                 return true;
00111         }
00112 
00113 public:
00114 
00115         BT_DECLARE_ALIGNED_ALLOCATOR();
00116 
00117         enum CollisionFlags
00118         {
00119                 CF_STATIC_OBJECT= 1,
00120                 CF_KINEMATIC_OBJECT= 2,
00121                 CF_NO_CONTACT_RESPONSE = 4,
00122                 CF_CUSTOM_MATERIAL_CALLBACK = 8,//this allows per-triangle material (friction/restitution)
00123                 CF_CHARACTER_OBJECT = 16,
00124                 CF_DISABLE_VISUALIZE_OBJECT = 32, //disable debug drawing
00125                 CF_DISABLE_SPU_COLLISION_PROCESSING = 64//disable parallel/SPU processing
00126         };
00127 
00128         enum    CollisionObjectTypes
00129         {
00130                 CO_COLLISION_OBJECT =1,
00131                 CO_RIGID_BODY=2,
00134                 CO_GHOST_OBJECT=4,
00135                 CO_SOFT_BODY=8,
00136                 CO_HF_FLUID=16,
00137                 CO_USER_TYPE=32
00138         };
00139 
00140         SIMD_FORCE_INLINE bool mergesSimulationIslands() const
00141         {
00143                 return  ((m_collisionFlags & (CF_STATIC_OBJECT | CF_KINEMATIC_OBJECT | CF_NO_CONTACT_RESPONSE) )==0);
00144         }
00145 
00146         const btVector3& getAnisotropicFriction() const
00147         {
00148                 return m_anisotropicFriction;
00149         }
00150         void    setAnisotropicFriction(const btVector3& anisotropicFriction)
00151         {
00152                 m_anisotropicFriction = anisotropicFriction;
00153                 m_hasAnisotropicFriction = (anisotropicFriction[0]!=1.f) || (anisotropicFriction[1]!=1.f) || (anisotropicFriction[2]!=1.f);
00154         }
00155         bool    hasAnisotropicFriction() const
00156         {
00157                 return m_hasAnisotropicFriction!=0;
00158         }
00159 
00162         void    setContactProcessingThreshold( btScalar contactProcessingThreshold)
00163         {
00164                 m_contactProcessingThreshold = contactProcessingThreshold;
00165         }
00166         btScalar        getContactProcessingThreshold() const
00167         {
00168                 return m_contactProcessingThreshold;
00169         }
00170 
00171         SIMD_FORCE_INLINE bool          isStaticObject() const {
00172                 return (m_collisionFlags & CF_STATIC_OBJECT) != 0;
00173         }
00174 
00175         SIMD_FORCE_INLINE bool          isKinematicObject() const
00176         {
00177                 return (m_collisionFlags & CF_KINEMATIC_OBJECT) != 0;
00178         }
00179 
00180         SIMD_FORCE_INLINE bool          isStaticOrKinematicObject() const
00181         {
00182                 return (m_collisionFlags & (CF_KINEMATIC_OBJECT | CF_STATIC_OBJECT)) != 0 ;
00183         }
00184 
00185         SIMD_FORCE_INLINE bool          hasContactResponse() const {
00186                 return (m_collisionFlags & CF_NO_CONTACT_RESPONSE)==0;
00187         }
00188 
00189         
00190         btCollisionObject();
00191 
00192         virtual ~btCollisionObject();
00193 
00194         virtual void    setCollisionShape(btCollisionShape* collisionShape)
00195         {
00196                 m_collisionShape = collisionShape;
00197                 m_rootCollisionShape = collisionShape;
00198         }
00199 
00200         SIMD_FORCE_INLINE const btCollisionShape*       getCollisionShape() const
00201         {
00202                 return m_collisionShape;
00203         }
00204 
00205         SIMD_FORCE_INLINE btCollisionShape*     getCollisionShape()
00206         {
00207                 return m_collisionShape;
00208         }
00209 
00210         SIMD_FORCE_INLINE const btCollisionShape*       getRootCollisionShape() const
00211         {
00212                 return m_rootCollisionShape;
00213         }
00214 
00215         SIMD_FORCE_INLINE btCollisionShape*     getRootCollisionShape()
00216         {
00217                 return m_rootCollisionShape;
00218         }
00219 
00222         void    internalSetTemporaryCollisionShape(btCollisionShape* collisionShape)
00223         {
00224                 m_collisionShape = collisionShape;
00225         }
00226 
00229         void*           internalGetExtensionPointer() const
00230         {
00231                 return m_extensionPointer;
00232         }
00235         void    internalSetExtensionPointer(void* pointer)
00236         {
00237                 m_extensionPointer = pointer;
00238         }
00239 
00240         SIMD_FORCE_INLINE       int     getActivationState() const { return m_activationState1;}
00241         
00242         void setActivationState(int newState);
00243 
00244         void    setDeactivationTime(btScalar time)
00245         {
00246                 m_deactivationTime = time;
00247         }
00248         btScalar        getDeactivationTime() const
00249         {
00250                 return m_deactivationTime;
00251         }
00252 
00253         void forceActivationState(int newState);
00254 
00255         void    activate(bool forceActivation = false);
00256 
00257         SIMD_FORCE_INLINE bool isActive() const
00258         {
00259                 return ((getActivationState() != ISLAND_SLEEPING) && (getActivationState() != DISABLE_SIMULATION));
00260         }
00261 
00262         void    setRestitution(btScalar rest)
00263         {
00264                 m_restitution = rest;
00265         }
00266         btScalar        getRestitution() const
00267         {
00268                 return m_restitution;
00269         }
00270         void    setFriction(btScalar frict)
00271         {
00272                 m_friction = frict;
00273         }
00274         btScalar        getFriction() const
00275         {
00276                 return m_friction;
00277         }
00278 
00280         int     getInternalType() const
00281         {
00282                 return m_internalType;
00283         }
00284 
00285         btTransform&    getWorldTransform()
00286         {
00287                 return m_worldTransform;
00288         }
00289 
00290         const btTransform&      getWorldTransform() const
00291         {
00292                 return m_worldTransform;
00293         }
00294 
00295         void    setWorldTransform(const btTransform& worldTrans)
00296         {
00297                 m_worldTransform = worldTrans;
00298         }
00299 
00300 
00301         SIMD_FORCE_INLINE btBroadphaseProxy*    getBroadphaseHandle()
00302         {
00303                 return m_broadphaseHandle;
00304         }
00305 
00306         SIMD_FORCE_INLINE const btBroadphaseProxy*      getBroadphaseHandle() const
00307         {
00308                 return m_broadphaseHandle;
00309         }
00310 
00311         void    setBroadphaseHandle(btBroadphaseProxy* handle)
00312         {
00313                 m_broadphaseHandle = handle;
00314         }
00315 
00316 
00317         const btTransform&      getInterpolationWorldTransform() const
00318         {
00319                 return m_interpolationWorldTransform;
00320         }
00321 
00322         btTransform&    getInterpolationWorldTransform()
00323         {
00324                 return m_interpolationWorldTransform;
00325         }
00326 
00327         void    setInterpolationWorldTransform(const btTransform&       trans)
00328         {
00329                 m_interpolationWorldTransform = trans;
00330         }
00331 
00332         void    setInterpolationLinearVelocity(const btVector3& linvel)
00333         {
00334                 m_interpolationLinearVelocity = linvel;
00335         }
00336 
00337         void    setInterpolationAngularVelocity(const btVector3& angvel)
00338         {
00339                 m_interpolationAngularVelocity = angvel;
00340         }
00341 
00342         const btVector3&        getInterpolationLinearVelocity() const
00343         {
00344                 return m_interpolationLinearVelocity;
00345         }
00346 
00347         const btVector3&        getInterpolationAngularVelocity() const
00348         {
00349                 return m_interpolationAngularVelocity;
00350         }
00351 
00352         SIMD_FORCE_INLINE int getIslandTag() const
00353         {
00354                 return  m_islandTag1;
00355         }
00356 
00357         void    setIslandTag(int tag)
00358         {
00359                 m_islandTag1 = tag;
00360         }
00361 
00362         SIMD_FORCE_INLINE int getCompanionId() const
00363         {
00364                 return  m_companionId;
00365         }
00366 
00367         void    setCompanionId(int id)
00368         {
00369                 m_companionId = id;
00370         }
00371 
00372         SIMD_FORCE_INLINE btScalar                      getHitFraction() const
00373         {
00374                 return m_hitFraction; 
00375         }
00376 
00377         void    setHitFraction(btScalar hitFraction)
00378         {
00379                 m_hitFraction = hitFraction;
00380         }
00381 
00382         
00383         SIMD_FORCE_INLINE int   getCollisionFlags() const
00384         {
00385                 return m_collisionFlags;
00386         }
00387 
00388         void    setCollisionFlags(int flags)
00389         {
00390                 m_collisionFlags = flags;
00391         }
00392         
00394         btScalar                        getCcdSweptSphereRadius() const
00395         {
00396                 return m_ccdSweptSphereRadius;
00397         }
00398 
00400         void    setCcdSweptSphereRadius(btScalar radius)
00401         {
00402                 m_ccdSweptSphereRadius = radius;
00403         }
00404 
00405         btScalar        getCcdMotionThreshold() const
00406         {
00407                 return m_ccdMotionThreshold;
00408         }
00409 
00410         btScalar        getCcdSquareMotionThreshold() const
00411         {
00412                 return m_ccdMotionThreshold*m_ccdMotionThreshold;
00413         }
00414 
00415 
00416 
00418         void    setCcdMotionThreshold(btScalar ccdMotionThreshold)
00419         {
00420                 m_ccdMotionThreshold = ccdMotionThreshold;
00421         }
00422 
00424         void*   getUserPointer() const
00425         {
00426                 return m_userObjectPointer;
00427         }
00428         
00430         void    setUserPointer(void* userPointer)
00431         {
00432                 m_userObjectPointer = userPointer;
00433         }
00434 
00435 
00436         inline bool checkCollideWith(btCollisionObject* co)
00437         {
00438                 if (m_checkCollideWith)
00439                         return checkCollideWithOverride(co);
00440 
00441                 return true;
00442         }
00443 
00444         virtual int     calculateSerializeBufferSize()  const;
00445 
00447         virtual const char*     serialize(void* dataBuffer, class btSerializer* serializer) const;
00448 
00449         virtual void serializeSingleObject(class btSerializer* serializer) const;
00450 
00451 };
00452 
00454 struct  btCollisionObjectDoubleData
00455 {
00456         void                                    *m_broadphaseHandle;
00457         void                                    *m_collisionShape;
00458         btCollisionShapeData    *m_rootCollisionShape;
00459         char                                    *m_name;
00460 
00461         btTransformDoubleData   m_worldTransform;
00462         btTransformDoubleData   m_interpolationWorldTransform;
00463         btVector3DoubleData             m_interpolationLinearVelocity;
00464         btVector3DoubleData             m_interpolationAngularVelocity;
00465         btVector3DoubleData             m_anisotropicFriction;
00466         double                                  m_contactProcessingThreshold;   
00467         double                                  m_deactivationTime;
00468         double                                  m_friction;
00469         double                                  m_restitution;
00470         double                                  m_hitFraction; 
00471         double                                  m_ccdSweptSphereRadius;
00472         double                                  m_ccdMotionThreshold;
00473 
00474         int                                             m_hasAnisotropicFriction;
00475         int                                             m_collisionFlags;
00476         int                                             m_islandTag1;
00477         int                                             m_companionId;
00478         int                                             m_activationState1;
00479         int                                             m_internalType;
00480         int                                             m_checkCollideWith;
00481 
00482         char    m_padding[4];
00483 };
00484 
00486 struct  btCollisionObjectFloatData
00487 {
00488         void                                    *m_broadphaseHandle;
00489         void                                    *m_collisionShape;
00490         btCollisionShapeData    *m_rootCollisionShape;
00491         char                                    *m_name;
00492 
00493         btTransformFloatData    m_worldTransform;
00494         btTransformFloatData    m_interpolationWorldTransform;
00495         btVector3FloatData              m_interpolationLinearVelocity;
00496         btVector3FloatData              m_interpolationAngularVelocity;
00497         btVector3FloatData              m_anisotropicFriction;
00498         float                                   m_contactProcessingThreshold;   
00499         float                                   m_deactivationTime;
00500         float                                   m_friction;
00501         float                                   m_restitution;
00502         float                                   m_hitFraction; 
00503         float                                   m_ccdSweptSphereRadius;
00504         float                                   m_ccdMotionThreshold;
00505 
00506         int                                             m_hasAnisotropicFriction;
00507         int                                             m_collisionFlags;
00508         int                                             m_islandTag1;
00509         int                                             m_companionId;
00510         int                                             m_activationState1;
00511         int                                             m_internalType;
00512         int                                             m_checkCollideWith;
00513 };
00514 
00515 
00516 
00517 SIMD_FORCE_INLINE       int     btCollisionObject::calculateSerializeBufferSize() const
00518 {
00519         return sizeof(btCollisionObjectData);
00520 }
00521 
00522 
00523 
00524 #endif //BT_COLLISION_OBJECT_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