btCylinderShape.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_CYLINDER_MINKOWSKI_H
00017 #define BT_CYLINDER_MINKOWSKI_H
00018 
00019 #include "btBoxShape.h"
00020 #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" // for the types
00021 #include "LinearMath/btVector3.h"
00022 
00024 class btCylinderShape : public btConvexInternalShape
00025 
00026 {
00027 
00028 protected:
00029 
00030         int     m_upAxis;
00031 
00032 public:
00033 
00034         btVector3 getHalfExtentsWithMargin() const
00035         {
00036                 btVector3 halfExtents = getHalfExtentsWithoutMargin();
00037                 btVector3 margin(getMargin(),getMargin(),getMargin());
00038                 halfExtents += margin;
00039                 return halfExtents;
00040         }
00041         
00042         const btVector3& getHalfExtentsWithoutMargin() const
00043         {
00044                 return m_implicitShapeDimensions;//changed in Bullet 2.63: assume the scaling and margin are included
00045         }
00046 
00047         btCylinderShape (const btVector3& halfExtents);
00048         
00049         void getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const;
00050 
00051         virtual void    calculateLocalInertia(btScalar mass,btVector3& inertia) const;
00052 
00053         virtual btVector3       localGetSupportingVertexWithoutMargin(const btVector3& vec)const;
00054 
00055         virtual void    batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const;
00056 
00057         virtual void setMargin(btScalar collisionMargin)
00058         {
00059                 //correct the m_implicitShapeDimensions for the margin
00060                 btVector3 oldMargin(getMargin(),getMargin(),getMargin());
00061                 btVector3 implicitShapeDimensionsWithMargin = m_implicitShapeDimensions+oldMargin;
00062                 
00063                 btConvexInternalShape::setMargin(collisionMargin);
00064                 btVector3 newMargin(getMargin(),getMargin(),getMargin());
00065                 m_implicitShapeDimensions = implicitShapeDimensionsWithMargin - newMargin;
00066 
00067         }
00068 
00069         virtual btVector3       localGetSupportingVertex(const btVector3& vec) const
00070         {
00071 
00072                 btVector3 supVertex;
00073                 supVertex = localGetSupportingVertexWithoutMargin(vec);
00074                 
00075                 if ( getMargin()!=btScalar(0.) )
00076                 {
00077                         btVector3 vecnorm = vec;
00078                         if (vecnorm .length2() < (SIMD_EPSILON*SIMD_EPSILON))
00079                         {
00080                                 vecnorm.setValue(btScalar(-1.),btScalar(-1.),btScalar(-1.));
00081                         } 
00082                         vecnorm.normalize();
00083                         supVertex+= getMargin() * vecnorm;
00084                 }
00085                 return supVertex;
00086         }
00087 
00088 
00089         //use box inertia
00090         //      virtual void    calculateLocalInertia(btScalar mass,btVector3& inertia) const;
00091 
00092 
00093         int     getUpAxis() const
00094         {
00095                 return m_upAxis;
00096         }
00097 
00098         virtual btScalar getRadius() const
00099         {
00100                 return getHalfExtentsWithMargin().getX();
00101         }
00102 
00103         virtual void    setLocalScaling(const btVector3& scaling)
00104         {
00105                 btVector3 oldMargin(getMargin(),getMargin(),getMargin());
00106                 btVector3 implicitShapeDimensionsWithMargin = m_implicitShapeDimensions+oldMargin;
00107                 btVector3 unScaledImplicitShapeDimensionsWithMargin = implicitShapeDimensionsWithMargin / m_localScaling;
00108 
00109                 btConvexInternalShape::setLocalScaling(scaling);
00110 
00111                 m_implicitShapeDimensions = (unScaledImplicitShapeDimensionsWithMargin * m_localScaling) - oldMargin;
00112 
00113         }
00114 
00115         //debugging
00116         virtual const char*     getName()const
00117         {
00118                 return "CylinderY";
00119         }
00120 
00121         virtual int     calculateSerializeBufferSize() const;
00122 
00124         virtual const char*     serialize(void* dataBuffer, btSerializer* serializer) const;
00125 
00126 };
00127 
00128 class btCylinderShapeX : public btCylinderShape
00129 {
00130 public:
00131         btCylinderShapeX (const btVector3& halfExtents);
00132 
00133         virtual btVector3       localGetSupportingVertexWithoutMargin(const btVector3& vec)const;
00134         virtual void    batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const;
00135         
00136                 //debugging
00137         virtual const char*     getName()const
00138         {
00139                 return "CylinderX";
00140         }
00141 
00142         virtual btScalar getRadius() const
00143         {
00144                 return getHalfExtentsWithMargin().getY();
00145         }
00146 
00147 };
00148 
00149 class btCylinderShapeZ : public btCylinderShape
00150 {
00151 public:
00152         btCylinderShapeZ (const btVector3& halfExtents);
00153 
00154         virtual btVector3       localGetSupportingVertexWithoutMargin(const btVector3& vec)const;
00155         virtual void    batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const;
00156 
00157                 //debugging
00158         virtual const char*     getName()const
00159         {
00160                 return "CylinderZ";
00161         }
00162 
00163         virtual btScalar getRadius() const
00164         {
00165                 return getHalfExtentsWithMargin().getX();
00166         }
00167 
00168 };
00169 
00171 struct  btCylinderShapeData
00172 {
00173         btConvexInternalShapeData       m_convexInternalShapeData;
00174 
00175         int     m_upAxis;
00176 
00177         char    m_padding[4];
00178 };
00179 
00180 SIMD_FORCE_INLINE       int     btCylinderShape::calculateSerializeBufferSize() const
00181 {
00182         return sizeof(btCylinderShapeData);
00183 }
00184 
00186 SIMD_FORCE_INLINE       const char*     btCylinderShape::serialize(void* dataBuffer, btSerializer* serializer) const
00187 {
00188         btCylinderShapeData* shapeData = (btCylinderShapeData*) dataBuffer;
00189         
00190         btConvexInternalShape::serialize(&shapeData->m_convexInternalShapeData,serializer);
00191 
00192         shapeData->m_upAxis = m_upAxis;
00193         
00194         return "btCylinderShapeData";
00195 }
00196 
00197 
00198 
00199 #endif //BT_CYLINDER_MINKOWSKI_H
00200 
 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