btConvexInternalShape.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_CONVEX_INTERNAL_SHAPE_H
00017 #define BT_CONVEX_INTERNAL_SHAPE_H
00018 
00019 #include "btConvexShape.h"
00020 #include "LinearMath/btAabbUtil2.h"
00021 
00022 
00029 class btConvexInternalShape : public btConvexShape
00030 {
00031 
00032         protected:
00033 
00034         //local scaling. collisionMargin is not scaled !
00035         btVector3       m_localScaling;
00036 
00037         btVector3       m_implicitShapeDimensions;
00038         
00039         btScalar        m_collisionMargin;
00040 
00041         btScalar        m_padding;
00042 
00043         btConvexInternalShape();
00044 
00045 public:
00046 
00047         
00048 
00049         virtual ~btConvexInternalShape()
00050         {
00051 
00052         }
00053 
00054         virtual btVector3       localGetSupportingVertex(const btVector3& vec)const;
00055 
00056         const btVector3& getImplicitShapeDimensions() const
00057         {
00058                 return m_implicitShapeDimensions;
00059         }
00060 
00065         void    setImplicitShapeDimensions(const btVector3& dimensions)
00066         {
00067                 m_implicitShapeDimensions = dimensions;
00068         }
00069 
00070         void    setSafeMargin(btScalar minDimension, btScalar defaultMarginMultiplier = 0.1f)
00071         {
00072                 btScalar safeMargin = defaultMarginMultiplier*minDimension;
00073                 if (safeMargin < getMargin())
00074                 {
00075                         setMargin(safeMargin);
00076                 }
00077         }
00078         void    setSafeMargin(const btVector3& halfExtents, btScalar defaultMarginMultiplier = 0.1f)
00079         {
00080                 //see http://code.google.com/p/bullet/issues/detail?id=349
00081                 //this margin check could could be added to other collision shapes too,
00082                 //or add some assert/warning somewhere
00083                 btScalar minDimension=halfExtents[halfExtents.minAxis()];               
00084                 setSafeMargin(minDimension, defaultMarginMultiplier);
00085         }
00086 
00088         void getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const
00089         {
00090                 getAabbSlow(t,aabbMin,aabbMax);
00091         }
00092 
00093 
00094         
00095         virtual void getAabbSlow(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const;
00096 
00097 
00098         virtual void    setLocalScaling(const btVector3& scaling);
00099         virtual const btVector3& getLocalScaling() const 
00100         {
00101                 return m_localScaling;
00102         }
00103 
00104         const btVector3& getLocalScalingNV() const 
00105         {
00106                 return m_localScaling;
00107         }
00108 
00109         virtual void    setMargin(btScalar margin)
00110         {
00111                 m_collisionMargin = margin;
00112         }
00113         virtual btScalar        getMargin() const
00114         {
00115                 return m_collisionMargin;
00116         }
00117 
00118         btScalar        getMarginNV() const
00119         {
00120                 return m_collisionMargin;
00121         }
00122 
00123         virtual int             getNumPreferredPenetrationDirections() const
00124         {
00125                 return 0;
00126         }
00127         
00128         virtual void    getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const
00129         {
00130                 (void)penetrationVector;
00131                 (void)index;
00132                 btAssert(0);
00133         }
00134 
00135         virtual int     calculateSerializeBufferSize() const;
00136 
00138         virtual const char*     serialize(void* dataBuffer, btSerializer* serializer) const;
00139 
00140         
00141 };
00142 
00144 struct  btConvexInternalShapeData
00145 {
00146         btCollisionShapeData    m_collisionShapeData;
00147 
00148         btVector3FloatData      m_localScaling;
00149 
00150         btVector3FloatData      m_implicitShapeDimensions;
00151         
00152         float                   m_collisionMargin;
00153 
00154         int     m_padding;
00155 
00156 };
00157 
00158 
00159 
00160 SIMD_FORCE_INLINE       int     btConvexInternalShape::calculateSerializeBufferSize() const
00161 {
00162         return sizeof(btConvexInternalShapeData);
00163 }
00164 
00166 SIMD_FORCE_INLINE       const char*     btConvexInternalShape::serialize(void* dataBuffer, btSerializer* serializer) const
00167 {
00168         btConvexInternalShapeData* shapeData = (btConvexInternalShapeData*) dataBuffer;
00169         btCollisionShape::serialize(&shapeData->m_collisionShapeData, serializer);
00170 
00171         m_implicitShapeDimensions.serializeFloat(shapeData->m_implicitShapeDimensions);
00172         m_localScaling.serializeFloat(shapeData->m_localScaling);
00173         shapeData->m_collisionMargin = float(m_collisionMargin);
00174 
00175         return "btConvexInternalShapeData";
00176 }
00177 
00178 
00179 
00180 
00182 class btConvexInternalAabbCachingShape : public btConvexInternalShape
00183 {
00184         btVector3       m_localAabbMin;
00185         btVector3       m_localAabbMax;
00186         bool            m_isLocalAabbValid;
00187         
00188 protected:
00189                                         
00190         btConvexInternalAabbCachingShape();
00191         
00192         void setCachedLocalAabb (const btVector3& aabbMin, const btVector3& aabbMax)
00193         {
00194                 m_isLocalAabbValid = true;
00195                 m_localAabbMin = aabbMin;
00196                 m_localAabbMax = aabbMax;
00197         }
00198 
00199         inline void getCachedLocalAabb (btVector3& aabbMin, btVector3& aabbMax) const
00200         {
00201                 btAssert(m_isLocalAabbValid);
00202                 aabbMin = m_localAabbMin;
00203                 aabbMax = m_localAabbMax;
00204         }
00205 
00206         inline void getNonvirtualAabb(const btTransform& trans,btVector3& aabbMin,btVector3& aabbMax, btScalar margin) const
00207         {
00208 
00209                 //lazy evaluation of local aabb
00210                 btAssert(m_isLocalAabbValid);
00211                 btTransformAabb(m_localAabbMin,m_localAabbMax,margin,trans,aabbMin,aabbMax);
00212         }
00213                 
00214 public:
00215                 
00216         virtual void    setLocalScaling(const btVector3& scaling);
00217 
00218         virtual void getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const;
00219 
00220         void    recalcLocalAabb();
00221 
00222 };
00223 
00224 #endif //BT_CONVEX_INTERNAL_SHAPE_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