btCapsuleShape.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_CAPSULE_SHAPE_H
00017 #define BT_CAPSULE_SHAPE_H
00018 
00019 #include "btConvexInternalShape.h"
00020 #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" // for the types
00021 
00022 
00026 class btCapsuleShape : public btConvexInternalShape
00027 {
00028 protected:
00029         int     m_upAxis;
00030 
00031 protected:
00033         btCapsuleShape() : btConvexInternalShape() {m_shapeType = CAPSULE_SHAPE_PROXYTYPE;};
00034 
00035 public:
00036         btCapsuleShape(btScalar radius,btScalar height);
00037 
00039         virtual void    calculateLocalInertia(btScalar mass,btVector3& inertia) const;
00040 
00042         virtual btVector3       localGetSupportingVertexWithoutMargin(const btVector3& vec)const;
00043 
00044         virtual void    batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const;
00045         
00046         virtual void setMargin(btScalar collisionMargin)
00047         {
00048                 //correct the m_implicitShapeDimensions for the margin
00049                 btVector3 oldMargin(getMargin(),getMargin(),getMargin());
00050                 btVector3 implicitShapeDimensionsWithMargin = m_implicitShapeDimensions+oldMargin;
00051                 
00052                 btConvexInternalShape::setMargin(collisionMargin);
00053                 btVector3 newMargin(getMargin(),getMargin(),getMargin());
00054                 m_implicitShapeDimensions = implicitShapeDimensionsWithMargin - newMargin;
00055 
00056         }
00057 
00058         virtual void getAabb (const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const
00059         {
00060                         btVector3 halfExtents(getRadius(),getRadius(),getRadius());
00061                         halfExtents[m_upAxis] = getRadius() + getHalfHeight();
00062                         halfExtents += btVector3(getMargin(),getMargin(),getMargin());
00063                         btMatrix3x3 abs_b = t.getBasis().absolute();  
00064                         btVector3 center = t.getOrigin();
00065                         btVector3 extent = btVector3(abs_b[0].dot(halfExtents),abs_b[1].dot(halfExtents),abs_b[2].dot(halfExtents));              
00066                         
00067                         aabbMin = center - extent;
00068                         aabbMax = center + extent;
00069         }
00070 
00071         virtual const char*     getName()const 
00072         {
00073                 return "CapsuleShape";
00074         }
00075 
00076         int     getUpAxis() const
00077         {
00078                 return m_upAxis;
00079         }
00080 
00081         btScalar        getRadius() const
00082         {
00083                 int radiusAxis = (m_upAxis+2)%3;
00084                 return m_implicitShapeDimensions[radiusAxis];
00085         }
00086 
00087         btScalar        getHalfHeight() const
00088         {
00089                 return m_implicitShapeDimensions[m_upAxis];
00090         }
00091 
00092         virtual void    setLocalScaling(const btVector3& scaling)
00093         {
00094                 btVector3 oldMargin(getMargin(),getMargin(),getMargin());
00095                 btVector3 implicitShapeDimensionsWithMargin = m_implicitShapeDimensions+oldMargin;
00096                 btVector3 unScaledImplicitShapeDimensionsWithMargin = implicitShapeDimensionsWithMargin / m_localScaling;
00097 
00098                 btConvexInternalShape::setLocalScaling(scaling);
00099 
00100                 m_implicitShapeDimensions = (unScaledImplicitShapeDimensionsWithMargin * m_localScaling) - oldMargin;
00101 
00102         }
00103 
00104         virtual int     calculateSerializeBufferSize() const;
00105 
00107         virtual const char*     serialize(void* dataBuffer, btSerializer* serializer) const;
00108 
00109 
00110 };
00111 
00114 class btCapsuleShapeX : public btCapsuleShape
00115 {
00116 public:
00117 
00118         btCapsuleShapeX(btScalar radius,btScalar height);
00119                 
00120         //debugging
00121         virtual const char*     getName()const
00122         {
00123                 return "CapsuleX";
00124         }
00125 
00126         
00127 
00128 };
00129 
00132 class btCapsuleShapeZ : public btCapsuleShape
00133 {
00134 public:
00135         btCapsuleShapeZ(btScalar radius,btScalar height);
00136 
00137                 //debugging
00138         virtual const char*     getName()const
00139         {
00140                 return "CapsuleZ";
00141         }
00142 
00143         
00144 };
00145 
00147 struct  btCapsuleShapeData
00148 {
00149         btConvexInternalShapeData       m_convexInternalShapeData;
00150 
00151         int     m_upAxis;
00152 
00153         char    m_padding[4];
00154 };
00155 
00156 SIMD_FORCE_INLINE       int     btCapsuleShape::calculateSerializeBufferSize() const
00157 {
00158         return sizeof(btCapsuleShapeData);
00159 }
00160 
00162 SIMD_FORCE_INLINE       const char*     btCapsuleShape::serialize(void* dataBuffer, btSerializer* serializer) const
00163 {
00164         btCapsuleShapeData* shapeData = (btCapsuleShapeData*) dataBuffer;
00165         
00166         btConvexInternalShape::serialize(&shapeData->m_convexInternalShapeData,serializer);
00167 
00168         shapeData->m_upAxis = m_upAxis;
00169         
00170         return "btCapsuleShapeData";
00171 }
00172 
00173 #endif //BT_CAPSULE_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