btSolverBody.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_SOLVER_BODY_H
00017 #define BT_SOLVER_BODY_H
00018 
00019 class   btRigidBody;
00020 #include "LinearMath/btVector3.h"
00021 #include "LinearMath/btMatrix3x3.h"
00022 #include "BulletDynamics/Dynamics/btRigidBody.h"
00023 #include "LinearMath/btAlignedAllocator.h"
00024 #include "LinearMath/btTransformUtil.h"
00025 
00027 #ifdef BT_USE_SSE
00028 #define USE_SIMD 1
00029 #endif //
00030 
00031 
00032 #ifdef USE_SIMD
00033 
00034 struct  btSimdScalar
00035 {
00036         SIMD_FORCE_INLINE       btSimdScalar()
00037         {
00038 
00039         }
00040 
00041         SIMD_FORCE_INLINE       btSimdScalar(float      fl)
00042         :m_vec128 (_mm_set1_ps(fl))
00043         {
00044         }
00045 
00046         SIMD_FORCE_INLINE       btSimdScalar(__m128 v128)
00047                 :m_vec128(v128)
00048         {
00049         }
00050         union
00051         {
00052                 __m128          m_vec128;
00053                 float           m_floats[4];
00054                 int                     m_ints[4];
00055                 btScalar        m_unusedPadding;
00056         };
00057         SIMD_FORCE_INLINE       __m128  get128()
00058         {
00059                 return m_vec128;
00060         }
00061 
00062         SIMD_FORCE_INLINE       const __m128    get128() const
00063         {
00064                 return m_vec128;
00065         }
00066 
00067         SIMD_FORCE_INLINE       void    set128(__m128 v128)
00068         {
00069                 m_vec128 = v128;
00070         }
00071 
00072         SIMD_FORCE_INLINE       operator       __m128()       
00073         { 
00074                 return m_vec128; 
00075         }
00076         SIMD_FORCE_INLINE       operator const __m128() const 
00077         { 
00078                 return m_vec128; 
00079         }
00080         
00081         SIMD_FORCE_INLINE       operator float() const 
00082         { 
00083                 return m_floats[0]; 
00084         }
00085 
00086 };
00087 
00089 SIMD_FORCE_INLINE btSimdScalar 
00090 operator*(const btSimdScalar& v1, const btSimdScalar& v2) 
00091 {
00092         return btSimdScalar(_mm_mul_ps(v1.get128(),v2.get128()));
00093 }
00094 
00096 SIMD_FORCE_INLINE btSimdScalar 
00097 operator+(const btSimdScalar& v1, const btSimdScalar& v2) 
00098 {
00099         return btSimdScalar(_mm_add_ps(v1.get128(),v2.get128()));
00100 }
00101 
00102 
00103 #else
00104 #define btSimdScalar btScalar
00105 #endif
00106 
00108 ATTRIBUTE_ALIGNED64 (struct)    btSolverBodyObsolete
00109 {
00110         BT_DECLARE_ALIGNED_ALLOCATOR();
00111         btVector3               m_deltaLinearVelocity;
00112         btVector3               m_deltaAngularVelocity;
00113         btVector3               m_angularFactor;
00114         btVector3               m_invMass;
00115         btRigidBody*    m_originalBody;
00116         btVector3               m_pushVelocity;
00117         btVector3               m_turnVelocity;
00118 
00119         
00120         SIMD_FORCE_INLINE void  getVelocityInLocalPointObsolete(const btVector3& rel_pos, btVector3& velocity ) const
00121         {
00122                 if (m_originalBody)
00123                         velocity = m_originalBody->getLinearVelocity()+m_deltaLinearVelocity + (m_originalBody->getAngularVelocity()+m_deltaAngularVelocity).cross(rel_pos);
00124                 else
00125                         velocity.setValue(0,0,0);
00126         }
00127 
00128         SIMD_FORCE_INLINE void  getAngularVelocity(btVector3& angVel) const
00129         {
00130                 if (m_originalBody)
00131                         angVel = m_originalBody->getAngularVelocity()+m_deltaAngularVelocity;
00132                 else
00133                         angVel.setValue(0,0,0);
00134         }
00135 
00136 
00137         //Optimization for the iterative solver: avoid calculating constant terms involving inertia, normal, relative position
00138         SIMD_FORCE_INLINE void applyImpulse(const btVector3& linearComponent, const btVector3& angularComponent,const btScalar impulseMagnitude)
00139         {
00140                 //if (m_invMass)
00141                 {
00142                         m_deltaLinearVelocity += linearComponent*impulseMagnitude;
00143                         m_deltaAngularVelocity += angularComponent*(impulseMagnitude*m_angularFactor);
00144                 }
00145         }
00146 
00147         SIMD_FORCE_INLINE void internalApplyPushImpulse(const btVector3& linearComponent, const btVector3& angularComponent,btScalar impulseMagnitude)
00148         {
00149                 if (m_originalBody)
00150                 {
00151                         m_pushVelocity += linearComponent*impulseMagnitude;
00152                         m_turnVelocity += angularComponent*(impulseMagnitude*m_angularFactor);
00153                 }
00154         }
00155         
00156         void    writebackVelocity()
00157         {
00158                 if (m_originalBody)
00159                 {
00160                         m_originalBody->setLinearVelocity(m_originalBody->getLinearVelocity()+ m_deltaLinearVelocity);
00161                         m_originalBody->setAngularVelocity(m_originalBody->getAngularVelocity()+m_deltaAngularVelocity);
00162                         
00163                         //m_originalBody->setCompanionId(-1);
00164                 }
00165         }
00166 
00167 
00168         void    writebackVelocity(btScalar timeStep)
00169         {
00170         (void) timeStep;
00171                 if (m_originalBody)
00172                 {
00173                         m_originalBody->setLinearVelocity(m_originalBody->getLinearVelocity()+ m_deltaLinearVelocity);
00174                         m_originalBody->setAngularVelocity(m_originalBody->getAngularVelocity()+m_deltaAngularVelocity);
00175                         
00176                         //correct the position/orientation based on push/turn recovery
00177                         btTransform newTransform;
00178                         btTransformUtil::integrateTransform(m_originalBody->getWorldTransform(),m_pushVelocity,m_turnVelocity,timeStep,newTransform);
00179                         m_originalBody->setWorldTransform(newTransform);
00180                         
00181                         //m_originalBody->setCompanionId(-1);
00182                 }
00183         }
00184         
00185 
00186 
00187 };
00188 
00189 #endif //BT_SOLVER_BODY_H
00190 
00191 
 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