btTriangleShape.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_OBB_TRIANGLE_MINKOWSKI_H
00017 #define BT_OBB_TRIANGLE_MINKOWSKI_H
00018 
00019 #include "btConvexShape.h"
00020 #include "btBoxShape.h"
00021 
00022 ATTRIBUTE_ALIGNED16(class) btTriangleShape : public btPolyhedralConvexShape
00023 {
00024 
00025 
00026 public:
00027 
00028         btVector3       m_vertices1[3];
00029 
00030         virtual int getNumVertices() const
00031         {
00032                 return 3;
00033         }
00034 
00035         btVector3& getVertexPtr(int index)
00036         {
00037                 return m_vertices1[index];
00038         }
00039 
00040         const btVector3& getVertexPtr(int index) const
00041         {
00042                 return m_vertices1[index];
00043         }
00044         virtual void getVertex(int index,btVector3& vert) const
00045         {
00046                 vert = m_vertices1[index];
00047         }
00048 
00049         virtual int getNumEdges() const
00050         {
00051                 return 3;
00052         }
00053         
00054         virtual void getEdge(int i,btVector3& pa,btVector3& pb) const
00055         {
00056                 getVertex(i,pa);
00057                 getVertex((i+1)%3,pb);
00058         }
00059 
00060 
00061         virtual void getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax)const 
00062         {
00063 //              btAssert(0);
00064                 getAabbSlow(t,aabbMin,aabbMax);
00065         }
00066 
00067         btVector3 localGetSupportingVertexWithoutMargin(const btVector3& dir)const 
00068         {
00069                 btVector3 dots(dir.dot(m_vertices1[0]), dir.dot(m_vertices1[1]), dir.dot(m_vertices1[2]));
00070                 return m_vertices1[dots.maxAxis()];
00071 
00072         }
00073 
00074         virtual void    batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const
00075         {
00076                 for (int i=0;i<numVectors;i++)
00077                 {
00078                         const btVector3& dir = vectors[i];
00079                         btVector3 dots(dir.dot(m_vertices1[0]), dir.dot(m_vertices1[1]), dir.dot(m_vertices1[2]));
00080                         supportVerticesOut[i] = m_vertices1[dots.maxAxis()];
00081                 }
00082 
00083         }
00084 
00085         btTriangleShape() : btPolyhedralConvexShape ()
00086     {
00087                 m_shapeType = TRIANGLE_SHAPE_PROXYTYPE;
00088         }
00089 
00090         btTriangleShape(const btVector3& p0,const btVector3& p1,const btVector3& p2) : btPolyhedralConvexShape ()
00091     {
00092                 m_shapeType = TRIANGLE_SHAPE_PROXYTYPE;
00093         m_vertices1[0] = p0;
00094         m_vertices1[1] = p1;
00095         m_vertices1[2] = p2;
00096     }
00097 
00098 
00099         virtual void getPlane(btVector3& planeNormal,btVector3& planeSupport,int i) const
00100         {
00101                 getPlaneEquation(i,planeNormal,planeSupport);
00102         }
00103 
00104         virtual int     getNumPlanes() const
00105         {
00106                 return 1;
00107         }
00108 
00109         void calcNormal(btVector3& normal) const
00110         {
00111                 normal = (m_vertices1[1]-m_vertices1[0]).cross(m_vertices1[2]-m_vertices1[0]);
00112                 normal.normalize();
00113         }
00114 
00115         virtual void getPlaneEquation(int i, btVector3& planeNormal,btVector3& planeSupport) const
00116         {
00117                 (void)i;
00118                 calcNormal(planeNormal);
00119                 planeSupport = m_vertices1[0];
00120         }
00121 
00122         virtual void    calculateLocalInertia(btScalar mass,btVector3& inertia) const
00123         {
00124                 (void)mass;
00125                 btAssert(0);
00126                 inertia.setValue(btScalar(0.),btScalar(0.),btScalar(0.));
00127         }
00128 
00129                 virtual bool isInside(const btVector3& pt,btScalar tolerance) const
00130         {
00131                 btVector3 normal;
00132                 calcNormal(normal);
00133                 //distance to plane
00134                 btScalar dist = pt.dot(normal);
00135                 btScalar planeconst = m_vertices1[0].dot(normal);
00136                 dist -= planeconst;
00137                 if (dist >= -tolerance && dist <= tolerance)
00138                 {
00139                         //inside check on edge-planes
00140                         int i;
00141                         for (i=0;i<3;i++)
00142                         {
00143                                 btVector3 pa,pb;
00144                                 getEdge(i,pa,pb);
00145                                 btVector3 edge = pb-pa;
00146                                 btVector3 edgeNormal = edge.cross(normal);
00147                                 edgeNormal.normalize();
00148                                 btScalar dist = pt.dot( edgeNormal);
00149                                 btScalar edgeConst = pa.dot(edgeNormal);
00150                                 dist -= edgeConst;
00151                                 if (dist < -tolerance)
00152                                         return false;
00153                         }
00154                         
00155                         return true;
00156                 }
00157 
00158                 return false;
00159         }
00160                 //debugging
00161                 virtual const char*     getName()const
00162                 {
00163                         return "Triangle";
00164                 }
00165 
00166                 virtual int             getNumPreferredPenetrationDirections() const
00167                 {
00168                         return 2;
00169                 }
00170                 
00171                 virtual void    getPreferredPenetrationDirection(int index, btVector3& penetrationVector) const
00172                 {
00173                         calcNormal(penetrationVector);
00174                         if (index)
00175                                 penetrationVector *= btScalar(-1.);
00176                 }
00177 
00178 
00179 };
00180 
00181 #endif //BT_OBB_TRIANGLE_MINKOWSKI_H
00182 
 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