btVoronoiSimplexSolver.h
Go to the documentation of this file.
00001 /*
00002 Bullet Continuous Collision Detection and Physics Library
00003 Copyright (c) 2003-2006 Erwin Coumans  http://continuousphysics.com/Bullet/
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 
00017 
00018 #ifndef BT_VORONOI_SIMPLEX_SOLVER_H
00019 #define BT_VORONOI_SIMPLEX_SOLVER_H
00020 
00021 #include "btSimplexSolverInterface.h"
00022 
00023 
00024 
00025 #define VORONOI_SIMPLEX_MAX_VERTS 5
00026 
00028 #define BT_USE_EQUAL_VERTEX_THRESHOLD
00029 #define VORONOI_DEFAULT_EQUAL_VERTEX_THRESHOLD 0.0001f
00030 
00031 
00032 struct btUsageBitfield{
00033         btUsageBitfield()
00034         {
00035                 reset();
00036         }
00037 
00038         void reset()
00039         {
00040                 usedVertexA = false;
00041                 usedVertexB = false;
00042                 usedVertexC = false;
00043                 usedVertexD = false;
00044         }
00045         unsigned short usedVertexA      : 1;
00046         unsigned short usedVertexB      : 1;
00047         unsigned short usedVertexC      : 1;
00048         unsigned short usedVertexD      : 1;
00049         unsigned short unused1          : 1;
00050         unsigned short unused2          : 1;
00051         unsigned short unused3          : 1;
00052         unsigned short unused4          : 1;
00053 };
00054 
00055 
00056 struct  btSubSimplexClosestResult
00057 {
00058         btVector3       m_closestPointOnSimplex;
00059         //MASK for m_usedVertices
00060         //stores the simplex vertex-usage, using the MASK, 
00061         // if m_usedVertices & MASK then the related vertex is used
00062         btUsageBitfield m_usedVertices;
00063         btScalar        m_barycentricCoords[4];
00064         bool m_degenerate;
00065 
00066         void    reset()
00067         {
00068                 m_degenerate = false;
00069                 setBarycentricCoordinates();
00070                 m_usedVertices.reset();
00071         }
00072         bool    isValid()
00073         {
00074                 bool valid = (m_barycentricCoords[0] >= btScalar(0.)) &&
00075                         (m_barycentricCoords[1] >= btScalar(0.)) &&
00076                         (m_barycentricCoords[2] >= btScalar(0.)) &&
00077                         (m_barycentricCoords[3] >= btScalar(0.));
00078 
00079 
00080                 return valid;
00081         }
00082         void    setBarycentricCoordinates(btScalar a=btScalar(0.),btScalar b=btScalar(0.),btScalar c=btScalar(0.),btScalar d=btScalar(0.))
00083         {
00084                 m_barycentricCoords[0] = a;
00085                 m_barycentricCoords[1] = b;
00086                 m_barycentricCoords[2] = c;
00087                 m_barycentricCoords[3] = d;
00088         }
00089 
00090 };
00091 
00094 #ifdef NO_VIRTUAL_INTERFACE
00095 class btVoronoiSimplexSolver
00096 #else
00097 class btVoronoiSimplexSolver : public btSimplexSolverInterface
00098 #endif
00099 {
00100 public:
00101 
00102         int     m_numVertices;
00103 
00104         btVector3       m_simplexVectorW[VORONOI_SIMPLEX_MAX_VERTS];
00105         btVector3       m_simplexPointsP[VORONOI_SIMPLEX_MAX_VERTS];
00106         btVector3       m_simplexPointsQ[VORONOI_SIMPLEX_MAX_VERTS];
00107 
00108         
00109 
00110         btVector3       m_cachedP1;
00111         btVector3       m_cachedP2;
00112         btVector3       m_cachedV;
00113         btVector3       m_lastW;
00114         
00115         btScalar        m_equalVertexThreshold;
00116         bool            m_cachedValidClosest;
00117 
00118 
00119         btSubSimplexClosestResult m_cachedBC;
00120 
00121         bool    m_needsUpdate;
00122         
00123         void    removeVertex(int index);
00124         void    reduceVertices (const btUsageBitfield& usedVerts);
00125         bool    updateClosestVectorAndPoints();
00126 
00127         bool    closestPtPointTetrahedron(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& d, btSubSimplexClosestResult& finalResult);
00128         int             pointOutsideOfPlane(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c, const btVector3& d);
00129         bool    closestPtPointTriangle(const btVector3& p, const btVector3& a, const btVector3& b, const btVector3& c,btSubSimplexClosestResult& result);
00130 
00131 public:
00132 
00133         btVoronoiSimplexSolver()
00134                 :  m_equalVertexThreshold(VORONOI_DEFAULT_EQUAL_VERTEX_THRESHOLD)
00135         {
00136         }
00137          void reset();
00138 
00139          void addVertex(const btVector3& w, const btVector3& p, const btVector3& q);
00140 
00141          void   setEqualVertexThreshold(btScalar threshold)
00142          {
00143                  m_equalVertexThreshold = threshold;
00144          }
00145 
00146          btScalar       getEqualVertexThreshold() const
00147          {
00148                  return m_equalVertexThreshold;
00149          }
00150 
00151          bool closest(btVector3& v);
00152 
00153          btScalar maxVertex();
00154 
00155          bool fullSimplex() const
00156          {
00157                  return (m_numVertices == 4);
00158          }
00159 
00160          int getSimplex(btVector3 *pBuf, btVector3 *qBuf, btVector3 *yBuf) const;
00161 
00162          bool inSimplex(const btVector3& w);
00163         
00164          void backup_closest(btVector3& v) ;
00165 
00166          bool emptySimplex() const ;
00167 
00168          void compute_points(btVector3& p1, btVector3& p2) ;
00169 
00170          int numVertices() const 
00171          {
00172                  return m_numVertices;
00173          }
00174 
00175 
00176 };
00177 
00178 #endif //BT_VORONOI_SIMPLEX_SOLVER_H
00179 
 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