btPoint2PointConstraint.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_POINT2POINTCONSTRAINT_H
00017 #define BT_POINT2POINTCONSTRAINT_H
00018 
00019 #include "LinearMath/btVector3.h"
00020 #include "btJacobianEntry.h"
00021 #include "btTypedConstraint.h"
00022 
00023 class btRigidBody;
00024 
00025 
00026 #ifdef BT_USE_DOUBLE_PRECISION
00027 #define btPoint2PointConstraintData     btPoint2PointConstraintDoubleData
00028 #define btPoint2PointConstraintDataName "btPoint2PointConstraintDoubleData"
00029 #else
00030 #define btPoint2PointConstraintData     btPoint2PointConstraintFloatData
00031 #define btPoint2PointConstraintDataName "btPoint2PointConstraintFloatData"
00032 #endif //BT_USE_DOUBLE_PRECISION
00033 
00034 struct  btConstraintSetting
00035 {
00036         btConstraintSetting()   :
00037                 m_tau(btScalar(0.3)),
00038                 m_damping(btScalar(1.)),
00039                 m_impulseClamp(btScalar(0.))
00040         {
00041         }
00042         btScalar                m_tau;
00043         btScalar                m_damping;
00044         btScalar                m_impulseClamp;
00045 };
00046 
00047 enum btPoint2PointFlags
00048 {
00049         BT_P2P_FLAGS_ERP = 1,
00050         BT_P2P_FLAGS_CFM = 2
00051 };
00052 
00054 ATTRIBUTE_ALIGNED16(class) btPoint2PointConstraint : public btTypedConstraint
00055 {
00056 #ifdef IN_PARALLELL_SOLVER
00057 public:
00058 #endif
00059         btJacobianEntry m_jac[3]; //3 orthogonal linear constraints
00060         
00061         btVector3       m_pivotInA;
00062         btVector3       m_pivotInB;
00063         
00064         int                     m_flags;
00065         btScalar        m_erp;
00066         btScalar        m_cfm;
00067         
00068 public:
00069 
00071         bool            m_useSolveConstraintObsolete;
00072 
00073         btConstraintSetting     m_setting;
00074 
00075         btPoint2PointConstraint(btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB);
00076 
00077         btPoint2PointConstraint(btRigidBody& rbA,const btVector3& pivotInA);
00078 
00079 
00080         virtual void    buildJacobian();
00081 
00082         virtual void getInfo1 (btConstraintInfo1* info);
00083 
00084         void getInfo1NonVirtual (btConstraintInfo1* info);
00085 
00086         virtual void getInfo2 (btConstraintInfo2* info);
00087 
00088         void getInfo2NonVirtual (btConstraintInfo2* info, const btTransform& body0_trans, const btTransform& body1_trans);
00089 
00090         void    updateRHS(btScalar      timeStep);
00091 
00092         void    setPivotA(const btVector3& pivotA)
00093         {
00094                 m_pivotInA = pivotA;
00095         }
00096 
00097         void    setPivotB(const btVector3& pivotB)
00098         {
00099                 m_pivotInB = pivotB;
00100         }
00101 
00102         const btVector3& getPivotInA() const
00103         {
00104                 return m_pivotInA;
00105         }
00106 
00107         const btVector3& getPivotInB() const
00108         {
00109                 return m_pivotInB;
00110         }
00111 
00114         virtual void    setParam(int num, btScalar value, int axis = -1);
00116         virtual btScalar getParam(int num, int axis = -1) const;
00117 
00118         virtual int     calculateSerializeBufferSize() const;
00119 
00121         virtual const char*     serialize(void* dataBuffer, btSerializer* serializer) const;
00122 
00123 
00124 };
00125 
00127 struct  btPoint2PointConstraintFloatData
00128 {
00129         btTypedConstraintData   m_typeConstraintData;
00130         btVector3FloatData      m_pivotInA;
00131         btVector3FloatData      m_pivotInB;
00132 };
00133 
00135 struct  btPoint2PointConstraintDoubleData
00136 {
00137         btTypedConstraintData   m_typeConstraintData;
00138         btVector3DoubleData     m_pivotInA;
00139         btVector3DoubleData     m_pivotInB;
00140 };
00141 
00142 
00143 SIMD_FORCE_INLINE       int     btPoint2PointConstraint::calculateSerializeBufferSize() const
00144 {
00145         return sizeof(btPoint2PointConstraintData);
00146 
00147 }
00148 
00150 SIMD_FORCE_INLINE       const char*     btPoint2PointConstraint::serialize(void* dataBuffer, btSerializer* serializer) const
00151 {
00152         btPoint2PointConstraintData* p2pData = (btPoint2PointConstraintData*)dataBuffer;
00153 
00154         btTypedConstraint::serialize(&p2pData->m_typeConstraintData,serializer);
00155         m_pivotInA.serialize(p2pData->m_pivotInA);
00156         m_pivotInB.serialize(p2pData->m_pivotInB);
00157 
00158         return btPoint2PointConstraintDataName;
00159 }
00160 
00161 #endif //BT_POINT2POINTCONSTRAINT_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