btManifoldPoint.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_MANIFOLD_CONTACT_POINT_H
00017 #define BT_MANIFOLD_CONTACT_POINT_H
00018 
00019 #include "LinearMath/btVector3.h"
00020 #include "LinearMath/btTransformUtil.h"
00021 
00022 #ifdef PFX_USE_FREE_VECTORMATH
00023         #include "physics_effects/base_level/solver/pfx_constraint_row.h"
00024 typedef sce::PhysicsEffects::PfxConstraintRow btConstraintRow;
00025 #else
00026         // Don't change following order of parameters
00027         ATTRIBUTE_ALIGNED16(struct) btConstraintRow {
00028                 btScalar m_normal[3];
00029                 btScalar m_rhs;
00030                 btScalar m_jacDiagInv;
00031                 btScalar m_lowerLimit;
00032                 btScalar m_upperLimit;
00033                 btScalar m_accumImpulse;
00034         };
00035         typedef btConstraintRow PfxConstraintRow;
00036 #endif //PFX_USE_FREE_VECTORMATH
00037 
00038 
00039 
00042 class btManifoldPoint
00043         {
00044                 public:
00045                         btManifoldPoint()
00046                                 :m_userPersistentData(0),
00047                                 m_appliedImpulse(0.f),
00048                                 m_lateralFrictionInitialized(false),
00049                                 m_appliedImpulseLateral1(0.f),
00050                                 m_appliedImpulseLateral2(0.f),
00051                                 m_contactMotion1(0.f),
00052                                 m_contactMotion2(0.f),
00053                                 m_contactCFM1(0.f),
00054                                 m_contactCFM2(0.f),
00055                                 m_lifeTime(0)
00056                         {
00057                         }
00058 
00059                         btManifoldPoint( const btVector3 &pointA, const btVector3 &pointB, 
00060                                         const btVector3 &normal, 
00061                                         btScalar distance ) :
00062                                         m_localPointA( pointA ), 
00063                                         m_localPointB( pointB ), 
00064                                         m_normalWorldOnB( normal ), 
00065                                         m_distance1( distance ),
00066                                         m_combinedFriction(btScalar(0.)),
00067                                         m_combinedRestitution(btScalar(0.)),
00068                                         m_userPersistentData(0),
00069                                         m_appliedImpulse(0.f),
00070                                         m_lateralFrictionInitialized(false),
00071                                         m_appliedImpulseLateral1(0.f),
00072                                         m_appliedImpulseLateral2(0.f),
00073                                         m_contactMotion1(0.f),
00074                                         m_contactMotion2(0.f),
00075                                         m_contactCFM1(0.f),
00076                                         m_contactCFM2(0.f),
00077                                         m_lifeTime(0)
00078                         {
00079                                 mConstraintRow[0].m_accumImpulse = 0.f;
00080                                 mConstraintRow[1].m_accumImpulse = 0.f;
00081                                 mConstraintRow[2].m_accumImpulse = 0.f;
00082                         }
00083 
00084                         
00085 
00086                         btVector3 m_localPointA;                        
00087                         btVector3 m_localPointB;                        
00088                         btVector3       m_positionWorldOnB;
00090                         btVector3       m_positionWorldOnA;
00091                         btVector3 m_normalWorldOnB;
00092                 
00093                         btScalar        m_distance1;
00094                         btScalar        m_combinedFriction;
00095                         btScalar        m_combinedRestitution;
00096 
00097          //BP mod, store contact triangles.
00098          int       m_partId0;
00099          int      m_partId1;
00100          int      m_index0;
00101          int      m_index1;
00102                                 
00103                         mutable void*   m_userPersistentData;
00104                         btScalar                m_appliedImpulse;
00105 
00106                         bool                    m_lateralFrictionInitialized;
00107                         btScalar                m_appliedImpulseLateral1;
00108                         btScalar                m_appliedImpulseLateral2;
00109                         btScalar                m_contactMotion1;
00110                         btScalar                m_contactMotion2;
00111                         btScalar                m_contactCFM1;
00112                         btScalar                m_contactCFM2;
00113 
00114                         int                             m_lifeTime;//lifetime of the contactpoint in frames
00115                         
00116                         btVector3               m_lateralFrictionDir1;
00117                         btVector3               m_lateralFrictionDir2;
00118 
00119 
00120 
00121                         btConstraintRow mConstraintRow[3];
00122 
00123 
00124                         btScalar getDistance() const
00125                         {
00126                                 return m_distance1;
00127                         }
00128                         int     getLifeTime() const
00129                         {
00130                                 return m_lifeTime;
00131                         }
00132 
00133                         const btVector3& getPositionWorldOnA() const {
00134                                 return m_positionWorldOnA;
00135 //                              return m_positionWorldOnB + m_normalWorldOnB * m_distance1;
00136                         }
00137 
00138                         const btVector3& getPositionWorldOnB() const
00139                         {
00140                                 return m_positionWorldOnB;
00141                         }
00142 
00143                         void    setDistance(btScalar dist)
00144                         {
00145                                 m_distance1 = dist;
00146                         }
00147                         
00149                         btScalar        getAppliedImpulse() const
00150                         {
00151                                 return m_appliedImpulse;
00152                         }
00153 
00154                         
00155 
00156         };
00157 
00158 #endif //BT_MANIFOLD_CONTACT_POINT_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