btCollisionShape.h
Go to the documentation of this file.
00001 /*
00002 Bullet Continuous Collision Detection and Physics Library
00003 Copyright (c) 2003-2009 Erwin Coumans  http://bulletphysics.org
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_SHAPE_H
00017 #define BT_COLLISION_SHAPE_H
00018 
00019 #include "LinearMath/btTransform.h"
00020 #include "LinearMath/btVector3.h"
00021 #include "LinearMath/btMatrix3x3.h"
00022 #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" //for the shape types
00023 class btSerializer;
00024 
00025 
00027 class btCollisionShape
00028 {
00029 protected:
00030         int m_shapeType;
00031         void* m_userPointer;
00032 
00033 public:
00034 
00035         btCollisionShape() : m_shapeType (INVALID_SHAPE_PROXYTYPE), m_userPointer(0)
00036         {
00037         }
00038 
00039         virtual ~btCollisionShape()
00040         {
00041         }
00042 
00044         virtual void getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const =0;
00045 
00046         virtual void    getBoundingSphere(btVector3& center,btScalar& radius) const;
00047 
00049         virtual btScalar        getAngularMotionDisc() const;
00050 
00051         virtual btScalar        getContactBreakingThreshold(btScalar defaultContactThresholdFactor) const;
00052 
00053 
00056         void calculateTemporalAabb(const btTransform& curTrans,const btVector3& linvel,const btVector3& angvel,btScalar timeStep, btVector3& temporalAabbMin,btVector3& temporalAabbMax) const;
00057 
00058 
00059 
00060         SIMD_FORCE_INLINE bool  isPolyhedral() const
00061         {
00062                 return btBroadphaseProxy::isPolyhedral(getShapeType());
00063         }
00064 
00065         SIMD_FORCE_INLINE bool  isConvex2d() const
00066         {
00067                 return btBroadphaseProxy::isConvex2d(getShapeType());
00068         }
00069 
00070         SIMD_FORCE_INLINE bool  isConvex() const
00071         {
00072                 return btBroadphaseProxy::isConvex(getShapeType());
00073         }
00074         SIMD_FORCE_INLINE bool  isNonMoving() const
00075         {
00076                 return btBroadphaseProxy::isNonMoving(getShapeType());
00077         }
00078         SIMD_FORCE_INLINE bool  isConcave() const
00079         {
00080                 return btBroadphaseProxy::isConcave(getShapeType());
00081         }
00082         SIMD_FORCE_INLINE bool  isCompound() const
00083         {
00084                 return btBroadphaseProxy::isCompound(getShapeType());
00085         }
00086 
00087         SIMD_FORCE_INLINE bool  isSoftBody() const
00088         {
00089                 return btBroadphaseProxy::isSoftBody(getShapeType());
00090         }
00091 
00093         SIMD_FORCE_INLINE bool isInfinite() const
00094         {
00095                 return btBroadphaseProxy::isInfinite(getShapeType());
00096         }
00097 
00098 #ifndef __SPU__
00099         virtual void    setLocalScaling(const btVector3& scaling) =0;
00100         virtual const btVector3& getLocalScaling() const =0;
00101         virtual void    calculateLocalInertia(btScalar mass,btVector3& inertia) const = 0;
00102 
00103 
00104 //debugging support
00105         virtual const char*     getName()const =0 ;
00106 #endif //__SPU__
00107 
00108         
00109         int             getShapeType() const { return m_shapeType; }
00110         virtual void    setMargin(btScalar margin) = 0;
00111         virtual btScalar        getMargin() const = 0;
00112 
00113         
00115         void    setUserPointer(void*  userPtr)
00116         {
00117                 m_userPointer = userPtr;
00118         }
00119 
00120         void*   getUserPointer() const
00121         {
00122                 return m_userPointer;
00123         }
00124 
00125         virtual int     calculateSerializeBufferSize() const;
00126 
00128         virtual const char*     serialize(void* dataBuffer, btSerializer* serializer) const;
00129 
00130         virtual void    serializeSingleShape(btSerializer* serializer) const;
00131 
00132 };      
00133 
00135 struct  btCollisionShapeData
00136 {
00137         char    *m_name;
00138         int             m_shapeType;
00139         char    m_padding[4];
00140 };
00141 
00142 SIMD_FORCE_INLINE       int     btCollisionShape::calculateSerializeBufferSize() const
00143 {
00144         return sizeof(btCollisionShapeData);
00145 }
00146 
00147 
00148 
00149 #endif //BT_COLLISION_SHAPE_H
00150 
 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