btSoftBodySolvers.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_SOFT_BODY_SOLVERS_H
00017 #define BT_SOFT_BODY_SOLVERS_H
00018 
00019 #include "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h"
00020 
00021 
00022 class btSoftBodyTriangleData;
00023 class btSoftBodyLinkData;
00024 class btSoftBodyVertexData;
00025 class btVertexBufferDescriptor;
00026 class btCollisionObject;
00027 class btSoftBody;
00028 
00029 
00030 class btSoftBodySolver
00031 {
00032 public:
00033         enum SolverTypes
00034         {
00035                 DEFAULT_SOLVER,
00036                 CPU_SOLVER,
00037                 CL_SOLVER,
00038                 CL_SIMD_SOLVER,
00039                 DX_SOLVER,
00040                 DX_SIMD_SOLVER
00041         };
00042 
00043 
00044 protected:
00045         int m_numberOfPositionIterations;
00046         int m_numberOfVelocityIterations;
00047         // Simulation timescale
00048         float m_timeScale;
00049         
00050 public:
00051         btSoftBodySolver() :
00052                 m_numberOfPositionIterations( 10 ),
00053                 m_timeScale( 1 )
00054         {
00055                 m_numberOfVelocityIterations = 0;
00056                 m_numberOfPositionIterations = 5;
00057         }
00058 
00059         virtual ~btSoftBodySolver()
00060         {
00061         }
00062         
00066         virtual SolverTypes getSolverType() const = 0;
00067 
00068 
00070         virtual bool checkInitialized() = 0;
00071 
00073         virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies , bool forceUpdate=false) = 0;
00074 
00076         virtual void copyBackToSoftBodies() = 0;
00077 
00079         virtual void predictMotion( float solverdt ) = 0;
00080 
00082         virtual void solveConstraints( float solverdt ) = 0;
00083 
00085         virtual void updateSoftBodies() = 0;
00086 
00088         virtual void processCollision( btSoftBody *, btCollisionObject* ) = 0;
00089 
00091         virtual void processCollision( btSoftBody*, btSoftBody* ) = 0;
00092 
00094         virtual void setNumberOfPositionIterations( int iterations )
00095         {
00096                 m_numberOfPositionIterations = iterations;
00097         }
00098 
00100         virtual int getNumberOfPositionIterations()
00101         {
00102                 return m_numberOfPositionIterations;
00103         }
00104 
00106         virtual void setNumberOfVelocityIterations( int iterations )
00107         {
00108                 m_numberOfVelocityIterations = iterations;
00109         }
00110 
00112         virtual int getNumberOfVelocityIterations()
00113         {
00114                 return m_numberOfVelocityIterations;
00115         }
00116 
00118         float getTimeScale()
00119         {
00120                 return m_timeScale;
00121         }
00122 
00123 #if 0
00124 
00127         virtual void addCollisionObjectForSoftBody( int clothIdentifier, btCollisionObject *collisionObject ) = 0;
00128 #endif
00129 };
00130 
00135 class btSoftBodySolverOutput
00136 {
00137 protected:
00138 
00139 public:
00140         btSoftBodySolverOutput()
00141         {
00142         }
00143 
00144         virtual ~btSoftBodySolverOutput()
00145         {
00146         }
00147 
00148 
00150         virtual void copySoftBodyToVertexBuffer( const btSoftBody * const softBody, btVertexBufferDescriptor *vertexBuffer ) = 0;
00151 };
00152 
00153 
00154 #endif // #ifndef BT_SOFT_BODY_SOLVERS_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