btBvhTriangleMeshShape.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_BVH_TRIANGLE_MESH_SHAPE_H
00017 #define BT_BVH_TRIANGLE_MESH_SHAPE_H
00018 
00019 #include "btTriangleMeshShape.h"
00020 #include "btOptimizedBvh.h"
00021 #include "LinearMath/btAlignedAllocator.h"
00022 #include "btTriangleInfoMap.h"
00023 
00028 ATTRIBUTE_ALIGNED16(class) btBvhTriangleMeshShape : public btTriangleMeshShape
00029 {
00030 
00031         btOptimizedBvh* m_bvh;
00032         btTriangleInfoMap*      m_triangleInfoMap;
00033 
00034         bool m_useQuantizedAabbCompression;
00035         bool m_ownsBvh;
00036         bool m_pad[11];
00037 
00038 public:
00039 
00040         BT_DECLARE_ALIGNED_ALLOCATOR();
00041 
00042         
00043         btBvhTriangleMeshShape(btStridingMeshInterface* meshInterface, bool useQuantizedAabbCompression, bool buildBvh = true);
00044 
00046         btBvhTriangleMeshShape(btStridingMeshInterface* meshInterface, bool useQuantizedAabbCompression,const btVector3& bvhAabbMin,const btVector3& bvhAabbMax, bool buildBvh = true);
00047         
00048         virtual ~btBvhTriangleMeshShape();
00049 
00050         bool getOwnsBvh () const
00051         {
00052                 return m_ownsBvh;
00053         }
00054 
00055 
00056         
00057         void performRaycast (btTriangleCallback* callback, const btVector3& raySource, const btVector3& rayTarget);
00058         void performConvexcast (btTriangleCallback* callback, const btVector3& boxSource, const btVector3& boxTarget, const btVector3& boxMin, const btVector3& boxMax);
00059 
00060         virtual void    processAllTriangles(btTriangleCallback* callback,const btVector3& aabbMin,const btVector3& aabbMax) const;
00061 
00062         void    refitTree(const btVector3& aabbMin,const btVector3& aabbMax);
00063 
00065         void    partialRefitTree(const btVector3& aabbMin,const btVector3& aabbMax);
00066 
00067         //debugging
00068         virtual const char*     getName()const {return "BVHTRIANGLEMESH";}
00069 
00070 
00071         virtual void    setLocalScaling(const btVector3& scaling);
00072         
00073         btOptimizedBvh* getOptimizedBvh()
00074         {
00075                 return m_bvh;
00076         }
00077 
00078         void    setOptimizedBvh(btOptimizedBvh* bvh, const btVector3& localScaling=btVector3(1,1,1));
00079 
00080         void    buildOptimizedBvh();
00081 
00082         bool    usesQuantizedAabbCompression() const
00083         {
00084                 return  m_useQuantizedAabbCompression;
00085         }
00086 
00087         void    setTriangleInfoMap(btTriangleInfoMap* triangleInfoMap)
00088         {
00089                 m_triangleInfoMap = triangleInfoMap;
00090         }
00091 
00092         const btTriangleInfoMap*        getTriangleInfoMap() const
00093         {
00094                 return m_triangleInfoMap;
00095         }
00096         
00097         btTriangleInfoMap*      getTriangleInfoMap()
00098         {
00099                 return m_triangleInfoMap;
00100         }
00101 
00102         virtual int     calculateSerializeBufferSize() const;
00103 
00105         virtual const char*     serialize(void* dataBuffer, btSerializer* serializer) const;
00106 
00107         virtual void    serializeSingleBvh(btSerializer* serializer) const;
00108 
00109         virtual void    serializeSingleTriangleInfoMap(btSerializer* serializer) const;
00110 
00111 };
00112 
00114 struct  btTriangleMeshShapeData
00115 {
00116         btCollisionShapeData    m_collisionShapeData;
00117 
00118         btStridingMeshInterfaceData m_meshInterface;
00119 
00120         btQuantizedBvhFloatData         *m_quantizedFloatBvh;
00121         btQuantizedBvhDoubleData        *m_quantizedDoubleBvh;
00122 
00123         btTriangleInfoMapData   *m_triangleInfoMap;
00124         
00125         float   m_collisionMargin;
00126 
00127         char m_pad3[4];
00128         
00129 };
00130 
00131 
00132 SIMD_FORCE_INLINE       int     btBvhTriangleMeshShape::calculateSerializeBufferSize() const
00133 {
00134         return sizeof(btTriangleMeshShapeData);
00135 }
00136 
00137 
00138 
00139 #endif //BT_BVH_TRIANGLE_MESH_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