btPersistentManifold.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 #ifndef BT_PERSISTENT_MANIFOLD_H
00017 #define BT_PERSISTENT_MANIFOLD_H
00018 
00019 
00020 #include "LinearMath/btVector3.h"
00021 #include "LinearMath/btTransform.h"
00022 #include "btManifoldPoint.h"
00023 #include "LinearMath/btAlignedAllocator.h"
00024 
00025 struct btCollisionResult;
00026 
00028 extern btScalar gContactBreakingThreshold;
00029 
00030 typedef bool (*ContactDestroyedCallback)(void* userPersistentData);
00031 typedef bool (*ContactProcessedCallback)(btManifoldPoint& cp,void* body0,void* body1);
00032 extern ContactDestroyedCallback gContactDestroyedCallback;
00033 extern ContactProcessedCallback gContactProcessedCallback;
00034 
00035 //the enum starts at 1024 to avoid type conflicts with btTypedConstraint
00036 enum btContactManifoldTypes
00037 {
00038         MIN_CONTACT_MANIFOLD_TYPE = 1024,
00039         BT_PERSISTENT_MANIFOLD_TYPE
00040 };
00041 
00042 #define MANIFOLD_CACHE_SIZE 4
00043 
00051 
00052 
00053 ATTRIBUTE_ALIGNED128( class) btPersistentManifold : public btTypedObject
00054 //ATTRIBUTE_ALIGNED16( class) btPersistentManifold : public btTypedObject
00055 {
00056 
00057         btManifoldPoint m_pointCache[MANIFOLD_CACHE_SIZE];
00058 
00061         void* m_body0;
00062         void* m_body1;
00063 
00064         int     m_cachedPoints;
00065 
00066         btScalar        m_contactBreakingThreshold;
00067         btScalar        m_contactProcessingThreshold;
00068 
00069         
00071         int     sortCachedPoints(const btManifoldPoint& pt);
00072 
00073         int             findContactPoint(const btManifoldPoint* unUsed, int numUnused,const btManifoldPoint& pt);
00074 
00075 public:
00076 
00077         BT_DECLARE_ALIGNED_ALLOCATOR();
00078 
00079         int     m_companionIdA;
00080         int     m_companionIdB;
00081 
00082         int m_index1a;
00083 
00084         btPersistentManifold();
00085 
00086         btPersistentManifold(void* body0,void* body1,int , btScalar contactBreakingThreshold,btScalar contactProcessingThreshold)
00087                 : btTypedObject(BT_PERSISTENT_MANIFOLD_TYPE),
00088         m_body0(body0),m_body1(body1),m_cachedPoints(0),
00089                 m_contactBreakingThreshold(contactBreakingThreshold),
00090                 m_contactProcessingThreshold(contactProcessingThreshold)
00091         {
00092         }
00093 
00094         SIMD_FORCE_INLINE void* getBody0() { return m_body0;}
00095         SIMD_FORCE_INLINE void* getBody1() { return m_body1;}
00096 
00097         SIMD_FORCE_INLINE const void* getBody0() const { return m_body0;}
00098         SIMD_FORCE_INLINE const void* getBody1() const { return m_body1;}
00099 
00100         void    setBodies(void* body0,void* body1)
00101         {
00102                 m_body0 = body0;
00103                 m_body1 = body1;
00104         }
00105 
00106         void clearUserCache(btManifoldPoint& pt);
00107 
00108 #ifdef DEBUG_PERSISTENCY
00109         void    DebugPersistency();
00110 #endif //
00111         
00112         SIMD_FORCE_INLINE int   getNumContacts() const { return m_cachedPoints;}
00113 
00114         SIMD_FORCE_INLINE const btManifoldPoint& getContactPoint(int index) const
00115         {
00116                 btAssert(index < m_cachedPoints);
00117                 return m_pointCache[index];
00118         }
00119 
00120         SIMD_FORCE_INLINE btManifoldPoint& getContactPoint(int index)
00121         {
00122                 btAssert(index < m_cachedPoints);
00123                 return m_pointCache[index];
00124         }
00125 
00127         btScalar        getContactBreakingThreshold() const;
00128 
00129         btScalar        getContactProcessingThreshold() const
00130         {
00131                 return m_contactProcessingThreshold;
00132         }
00133         
00134         int getCacheEntry(const btManifoldPoint& newPoint) const;
00135 
00136         int addManifoldPoint( const btManifoldPoint& newPoint);
00137 
00138         void removeContactPoint (int index)
00139         {
00140                 clearUserCache(m_pointCache[index]);
00141 
00142                 int lastUsedIndex = getNumContacts() - 1;
00143 //              m_pointCache[index] = m_pointCache[lastUsedIndex];
00144                 if(index != lastUsedIndex) 
00145                 {
00146                         m_pointCache[index] = m_pointCache[lastUsedIndex]; 
00147                         //get rid of duplicated userPersistentData pointer
00148                         m_pointCache[lastUsedIndex].m_userPersistentData = 0;
00149                         m_pointCache[lastUsedIndex].mConstraintRow[0].m_accumImpulse = 0.f;
00150                         m_pointCache[lastUsedIndex].mConstraintRow[1].m_accumImpulse = 0.f;
00151                         m_pointCache[lastUsedIndex].mConstraintRow[2].m_accumImpulse = 0.f;
00152 
00153                         m_pointCache[lastUsedIndex].m_appliedImpulse = 0.f;
00154                         m_pointCache[lastUsedIndex].m_lateralFrictionInitialized = false;
00155                         m_pointCache[lastUsedIndex].m_appliedImpulseLateral1 = 0.f;
00156                         m_pointCache[lastUsedIndex].m_appliedImpulseLateral2 = 0.f;
00157                         m_pointCache[lastUsedIndex].m_lifeTime = 0;
00158                 }
00159 
00160                 btAssert(m_pointCache[lastUsedIndex].m_userPersistentData==0);
00161                 m_cachedPoints--;
00162         }
00163         void replaceContactPoint(const btManifoldPoint& newPoint,int insertIndex)
00164         {
00165                 btAssert(validContactDistance(newPoint));
00166 
00167 #define MAINTAIN_PERSISTENCY 1
00168 #ifdef MAINTAIN_PERSISTENCY
00169                 int     lifeTime = m_pointCache[insertIndex].getLifeTime();
00170                 btScalar        appliedImpulse = m_pointCache[insertIndex].mConstraintRow[0].m_accumImpulse;
00171                 btScalar        appliedLateralImpulse1 = m_pointCache[insertIndex].mConstraintRow[1].m_accumImpulse;
00172                 btScalar        appliedLateralImpulse2 = m_pointCache[insertIndex].mConstraintRow[2].m_accumImpulse;
00173 //              bool isLateralFrictionInitialized = m_pointCache[insertIndex].m_lateralFrictionInitialized;
00174                 
00175                 
00176                         
00177                 btAssert(lifeTime>=0);
00178                 void* cache = m_pointCache[insertIndex].m_userPersistentData;
00179                 
00180                 m_pointCache[insertIndex] = newPoint;
00181 
00182                 m_pointCache[insertIndex].m_userPersistentData = cache;
00183                 m_pointCache[insertIndex].m_appliedImpulse = appliedImpulse;
00184                 m_pointCache[insertIndex].m_appliedImpulseLateral1 = appliedLateralImpulse1;
00185                 m_pointCache[insertIndex].m_appliedImpulseLateral2 = appliedLateralImpulse2;
00186                 
00187                 m_pointCache[insertIndex].mConstraintRow[0].m_accumImpulse =  appliedImpulse;
00188                 m_pointCache[insertIndex].mConstraintRow[1].m_accumImpulse = appliedLateralImpulse1;
00189                 m_pointCache[insertIndex].mConstraintRow[2].m_accumImpulse = appliedLateralImpulse2;
00190 
00191 
00192                 m_pointCache[insertIndex].m_lifeTime = lifeTime;
00193 #else
00194                 clearUserCache(m_pointCache[insertIndex]);
00195                 m_pointCache[insertIndex] = newPoint;
00196         
00197 #endif
00198         }
00199 
00200         
00201         bool validContactDistance(const btManifoldPoint& pt) const
00202         {
00203                 return pt.m_distance1 <= getContactBreakingThreshold();
00204         }
00206         void    refreshContactPoints(  const btTransform& trA,const btTransform& trB);
00207 
00208         
00209         SIMD_FORCE_INLINE       void    clearManifold()
00210         {
00211                 int i;
00212                 for (i=0;i<m_cachedPoints;i++)
00213                 {
00214                         clearUserCache(m_pointCache[i]);
00215                 }
00216                 m_cachedPoints = 0;
00217         }
00218 
00219 
00220 
00221 }
00222 ;
00223 
00224 
00225 
00226 
00227 
00228 #endif //BT_PERSISTENT_MANIFOLD_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