btDbvtBroadphase.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 
00017 #ifndef BT_DBVT_BROADPHASE_H
00018 #define BT_DBVT_BROADPHASE_H
00019 
00020 #include "BulletCollision/BroadphaseCollision/btDbvt.h"
00021 #include "BulletCollision/BroadphaseCollision/btOverlappingPairCache.h"
00022 
00023 //
00024 // Compile time config
00025 //
00026 
00027 #define DBVT_BP_PROFILE                                 0
00028 //#define DBVT_BP_SORTPAIRS                             1
00029 #define DBVT_BP_PREVENTFALSEUPDATE              0
00030 #define DBVT_BP_ACCURATESLEEPING                0
00031 #define DBVT_BP_ENABLE_BENCHMARK                0
00032 #define DBVT_BP_MARGIN                                  (btScalar)0.05
00033 
00034 #if DBVT_BP_PROFILE
00035 #define DBVT_BP_PROFILING_RATE  256
00036 #include "LinearMath/btQuickprof.h"
00037 #endif
00038 
00039 //
00040 // btDbvtProxy
00041 //
00042 struct btDbvtProxy : btBroadphaseProxy
00043 {
00044         /* Fields               */ 
00045         //btDbvtAabbMm  aabb;
00046         btDbvtNode*             leaf;
00047         btDbvtProxy*    links[2];
00048         int                             stage;
00049         /* ctor                 */ 
00050         btDbvtProxy(const btVector3& aabbMin,const btVector3& aabbMax,void* userPtr,short int collisionFilterGroup, short int collisionFilterMask) :
00051         btBroadphaseProxy(aabbMin,aabbMax,userPtr,collisionFilterGroup,collisionFilterMask)
00052         {
00053                 links[0]=links[1]=0;
00054         }
00055 };
00056 
00057 typedef btAlignedObjectArray<btDbvtProxy*>      btDbvtProxyArray;
00058 
00062 struct  btDbvtBroadphase : btBroadphaseInterface
00063 {
00064         /* Config               */ 
00065         enum    {
00066                 DYNAMIC_SET                     =       0,      /* Dynamic set index    */ 
00067                 FIXED_SET                       =       1,      /* Fixed set index              */ 
00068                 STAGECOUNT                      =       2       /* Number of stages             */ 
00069         };
00070         /* Fields               */ 
00071         btDbvt                                  m_sets[2];                                      // Dbvt sets
00072         btDbvtProxy*                    m_stageRoots[STAGECOUNT+1];     // Stages list
00073         btOverlappingPairCache* m_paircache;                            // Pair cache
00074         btScalar                                m_prediction;                           // Velocity prediction
00075         int                                             m_stageCurrent;                         // Current stage
00076         int                                             m_fupdates;                                     // % of fixed updates per frame
00077         int                                             m_dupdates;                                     // % of dynamic updates per frame
00078         int                                             m_cupdates;                                     // % of cleanup updates per frame
00079         int                                             m_newpairs;                                     // Number of pairs created
00080         int                                             m_fixedleft;                            // Fixed optimization left
00081         unsigned                                m_updates_call;                         // Number of updates call
00082         unsigned                                m_updates_done;                         // Number of updates done
00083         btScalar                                m_updates_ratio;                        // m_updates_done/m_updates_call
00084         int                                             m_pid;                                          // Parse id
00085         int                                             m_cid;                                          // Cleanup index
00086         int                                             m_gid;                                          // Gen id
00087         bool                                    m_releasepaircache;                     // Release pair cache on delete
00088         bool                                    m_deferedcollide;                       // Defere dynamic/static collision to collide call
00089         bool                                    m_needcleanup;                          // Need to run cleanup?
00090 #if DBVT_BP_PROFILE
00091         btClock                                 m_clock;
00092         struct  {
00093                 unsigned long           m_total;
00094                 unsigned long           m_ddcollide;
00095                 unsigned long           m_fdcollide;
00096                 unsigned long           m_cleanup;
00097                 unsigned long           m_jobcount;
00098         }                               m_profiling;
00099 #endif
00100         /* Methods              */ 
00101         btDbvtBroadphase(btOverlappingPairCache* paircache=0);
00102         ~btDbvtBroadphase();
00103         void                                                    collide(btDispatcher* dispatcher);
00104         void                                                    optimize();
00105         
00106         /* btBroadphaseInterface Implementation */
00107         btBroadphaseProxy*                              createProxy(const btVector3& aabbMin,const btVector3& aabbMax,int shapeType,void* userPtr,short int collisionFilterGroup,short int collisionFilterMask,btDispatcher* dispatcher,void* multiSapProxy);
00108         virtual void                                    destroyProxy(btBroadphaseProxy* proxy,btDispatcher* dispatcher);
00109         virtual void                                    setAabb(btBroadphaseProxy* proxy,const btVector3& aabbMin,const btVector3& aabbMax,btDispatcher* dispatcher);
00110         virtual void                                    rayTest(const btVector3& rayFrom,const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin=btVector3(0,0,0), const btVector3& aabbMax = btVector3(0,0,0));
00111         virtual void                                    aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback);
00112 
00113         virtual void                                    getAabb(btBroadphaseProxy* proxy,btVector3& aabbMin, btVector3& aabbMax ) const;
00114         virtual void                                    calculateOverlappingPairs(btDispatcher* dispatcher);
00115         virtual btOverlappingPairCache* getOverlappingPairCache();
00116         virtual const btOverlappingPairCache*   getOverlappingPairCache() const;
00117         virtual void                                    getBroadphaseAabb(btVector3& aabbMin,btVector3& aabbMax) const;
00118         virtual void                                    printStats();
00119 
00120 
00122         virtual void resetPool(btDispatcher* dispatcher);
00123 
00124         void    performDeferredRemoval(btDispatcher* dispatcher);
00125         
00126         void    setVelocityPrediction(btScalar prediction)
00127         {
00128                 m_prediction = prediction;
00129         }
00130         btScalar getVelocityPrediction() const
00131         {
00132                 return m_prediction;
00133         }
00134 
00139         void                                                    setAabbForceUpdate(             btBroadphaseProxy* absproxy,const btVector3& aabbMin,const btVector3& aabbMax,btDispatcher* /*dispatcher*/);
00140 
00141         static void                                             benchmark(btBroadphaseInterface*);
00142 
00143 
00144 };
00145 
00146 #endif
 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