Merge pull request #1874 from John3/readmeUpdate
[Torque-3d.git] / Engine / lib / bullet / src / BulletMultiThreaded / GpuSoftBodySolvers / DX11 / btSoftBodySolver_DX11.h
blob0f50ecf7936ac263e521b3ab0ac46aeb44e69de7
1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
5 This software is provided 'as-is', without any express or implied warranty.
6 In no event will the authors be held liable for any damages arising from the use of this software.
7 Permission is granted to anyone to use this software for any purpose,
8 including commercial applications, and to alter it and redistribute it freely,
9 subject to the following restrictions:
11 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.
12 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13 3. This notice may not be removed or altered from any source distribution.
16 #ifndef BT_ACCELERATED_SOFT_BODY_DX11_SOLVER_H
17 #define BT_ACCELERATED_SOFT_BODY_DX11_SOLVER_H
20 #include "vectormath/vmInclude.h"
21 #include "BulletSoftBody/btSoftBodySolvers.h"
22 #include "btSoftBodySolverVertexBuffer_DX11.h"
23 #include "btSoftBodySolverLinkData_DX11.h"
24 #include "btSoftBodySolverVertexData_DX11.h"
25 #include "btSoftBodySolverTriangleData_DX11.h"
29 class DXFunctions
31 public:
33 typedef HRESULT (WINAPI * CompileFromMemoryFunc)(LPCSTR,SIZE_T,LPCSTR,const D3D10_SHADER_MACRO*,LPD3D10INCLUDE,LPCSTR,LPCSTR,UINT,UINT,ID3DX11ThreadPump*,ID3D10Blob**,ID3D10Blob**,HRESULT*);
35 ID3D11Device * m_dx11Device;
36 ID3D11DeviceContext* m_dx11Context;
37 CompileFromMemoryFunc m_dx11CompileFromMemory;
39 DXFunctions(ID3D11Device *dx11Device, ID3D11DeviceContext* dx11Context, CompileFromMemoryFunc dx11CompileFromMemory) :
40 m_dx11Device( dx11Device ),
41 m_dx11Context( dx11Context ),
42 m_dx11CompileFromMemory( dx11CompileFromMemory )
47 class KernelDesc
49 protected:
52 public:
53 ID3D11ComputeShader* kernel;
54 ID3D11Buffer* constBuffer;
56 KernelDesc()
58 kernel = 0;
59 constBuffer = 0;
62 virtual ~KernelDesc()
64 // TODO: this should probably destroy its kernel but we need to be careful
65 // in case KernelDescs are copied
67 };
69 /**
70 * Compile a compute shader kernel from a string and return the appropriate KernelDesc object.
72 KernelDesc compileComputeShaderFromString( const char* shaderString, const char* shaderName, int constBufferSize, D3D10_SHADER_MACRO *compileMacros = 0 );
76 class btDX11SoftBodySolver : public btSoftBodySolver
78 protected:
79 /**
80 * Entry in the collision shape array.
81 * Specifies the shape type, the transform matrix and the necessary details of the collisionShape.
83 struct CollisionShapeDescription
85 Vectormath::Aos::Transform3 shapeTransform;
86 Vectormath::Aos::Vector3 linearVelocity;
87 Vectormath::Aos::Vector3 angularVelocity;
89 int softBodyIdentifier;
90 int collisionShapeType;
92 // Both needed for capsule
93 float radius;
94 float halfHeight;
96 float margin;
97 float friction;
99 CollisionShapeDescription()
101 collisionShapeType = 0;
102 margin = 0;
103 friction = 0;
107 struct UIntVector3
109 UIntVector3()
111 x = 0;
112 y = 0;
113 z = 0;
114 _padding = 0;
117 UIntVector3( unsigned int x_, unsigned int y_, unsigned int z_ )
119 x = x_;
120 y = y_;
121 z = z_;
122 _padding = 0;
125 unsigned int x;
126 unsigned int y;
127 unsigned int z;
128 unsigned int _padding;
133 public:
135 * SoftBody class to maintain information about a soft body instance
136 * within a solver.
137 * This data addresses the main solver arrays.
139 class btAcceleratedSoftBodyInterface
141 protected:
142 /** Current number of vertices that are part of this cloth */
143 int m_numVertices;
144 /** Maximum number of vertices allocated to be part of this cloth */
145 int m_maxVertices;
146 /** Current number of triangles that are part of this cloth */
147 int m_numTriangles;
148 /** Maximum number of triangles allocated to be part of this cloth */
149 int m_maxTriangles;
150 /** Index of first vertex in the world allocated to this cloth */
151 int m_firstVertex;
152 /** Index of first triangle in the world allocated to this cloth */
153 int m_firstTriangle;
154 /** Index of first link in the world allocated to this cloth */
155 int m_firstLink;
156 /** Maximum number of links allocated to this cloth */
157 int m_maxLinks;
158 /** Current number of links allocated to this cloth */
159 int m_numLinks;
161 /** The actual soft body this data represents */
162 btSoftBody *m_softBody;
165 public:
166 btAcceleratedSoftBodyInterface( btSoftBody *softBody ) :
167 m_softBody( softBody )
169 m_numVertices = 0;
170 m_maxVertices = 0;
171 m_numTriangles = 0;
172 m_maxTriangles = 0;
173 m_firstVertex = 0;
174 m_firstTriangle = 0;
175 m_firstLink = 0;
176 m_maxLinks = 0;
177 m_numLinks = 0;
179 int getNumVertices() const
181 return m_numVertices;
184 int getNumTriangles() const
186 return m_numTriangles;
189 int getMaxVertices() const
191 return m_maxVertices;
194 int getMaxTriangles() const
196 return m_maxTriangles;
199 int getFirstVertex() const
201 return m_firstVertex;
204 int getFirstTriangle() const
206 return m_firstTriangle;
211 * Update the bounds in the btSoftBody object
213 void updateBounds( const btVector3 &lowerBound, const btVector3 &upperBound );
216 // TODO: All of these set functions will have to do checks and
217 // update the world because restructuring of the arrays will be necessary
218 // Reasonable use of "friend"?
219 void setNumVertices( int numVertices )
221 m_numVertices = numVertices;
224 void setNumTriangles( int numTriangles )
226 m_numTriangles = numTriangles;
229 void setMaxVertices( int maxVertices )
231 m_maxVertices = maxVertices;
234 void setMaxTriangles( int maxTriangles )
236 m_maxTriangles = maxTriangles;
239 void setFirstVertex( int firstVertex )
241 m_firstVertex = firstVertex;
244 void setFirstTriangle( int firstTriangle )
246 m_firstTriangle = firstTriangle;
249 void setMaxLinks( int maxLinks )
251 m_maxLinks = maxLinks;
254 void setNumLinks( int numLinks )
256 m_numLinks = numLinks;
259 void setFirstLink( int firstLink )
261 m_firstLink = firstLink;
264 int getMaxLinks()
266 return m_maxLinks;
269 int getNumLinks()
271 return m_numLinks;
274 int getFirstLink()
276 return m_firstLink;
279 btSoftBody* getSoftBody()
281 return m_softBody;
287 struct CollisionObjectIndices
289 CollisionObjectIndices( int f, int e )
291 firstObject = f;
292 endObject = e;
295 int firstObject;
296 int endObject;
303 struct PrepareLinksCB
305 int numLinks;
306 int padding0;
307 int padding1;
308 int padding2;
311 struct SolvePositionsFromLinksKernelCB
313 int startLink;
314 int numLinks;
315 float kst;
316 float ti;
319 struct IntegrateCB
321 int numNodes;
322 float solverdt;
323 int padding1;
324 int padding2;
327 struct UpdatePositionsFromVelocitiesCB
329 int numNodes;
330 float solverSDT;
331 int padding1;
332 int padding2;
335 struct UpdateVelocitiesFromPositionsWithoutVelocitiesCB
337 int numNodes;
338 float isolverdt;
339 int padding1;
340 int padding2;
343 struct UpdateVelocitiesFromPositionsWithVelocitiesCB
345 int numNodes;
346 float isolverdt;
347 int padding1;
348 int padding2;
351 struct UpdateSoftBodiesCB
353 int numNodes;
354 int startFace;
355 int numFaces;
356 float epsilon;
360 struct ApplyForcesCB
362 unsigned int numNodes;
363 float solverdt;
364 float epsilon;
365 int padding3;
368 struct AddVelocityCB
370 int startNode;
371 int lastNode;
372 float velocityX;
373 float velocityY;
374 float velocityZ;
375 int padding1;
376 int padding2;
377 int padding3;
380 struct VSolveLinksCB
382 int startLink;
383 int numLinks;
384 float kst;
385 int padding;
388 struct ComputeBoundsCB
390 int numNodes;
391 int numSoftBodies;
392 int padding1;
393 int padding2;
396 struct SolveCollisionsAndUpdateVelocitiesCB
398 unsigned int numNodes;
399 float isolverdt;
400 int padding0;
401 int padding1;
407 protected:
408 ID3D11Device * m_dx11Device;
409 ID3D11DeviceContext* m_dx11Context;
411 DXFunctions dxFunctions;
412 public:
413 /** Link data for all cloths. Note that this will be sorted batch-wise for efficient computation and m_linkAddresses will maintain the addressing. */
414 btSoftBodyLinkDataDX11 m_linkData;
415 btSoftBodyVertexDataDX11 m_vertexData;
416 btSoftBodyTriangleDataDX11 m_triangleData;
418 protected:
420 /** Variable to define whether we need to update solver constants on the next iteration */
421 bool m_updateSolverConstants;
423 bool m_shadersInitialized;
425 /**
426 * Cloths owned by this solver.
427 * Only our cloths are in this array.
429 btAlignedObjectArray< btAcceleratedSoftBodyInterface * > m_softBodySet;
431 /** Acceleration value to be applied to all non-static vertices in the solver.
432 * Index n is cloth n, array sized by number of cloths in the world not the solver.
434 btAlignedObjectArray< Vectormath::Aos::Vector3 > m_perClothAcceleration;
435 btDX11Buffer<Vectormath::Aos::Vector3> m_dx11PerClothAcceleration;
437 /** Wind velocity to be applied normal to all non-static vertices in the solver.
438 * Index n is cloth n, array sized by number of cloths in the world not the solver.
440 btAlignedObjectArray< Vectormath::Aos::Vector3 > m_perClothWindVelocity;
441 btDX11Buffer<Vectormath::Aos::Vector3> m_dx11PerClothWindVelocity;
443 /** Velocity damping factor */
444 btAlignedObjectArray< float > m_perClothDampingFactor;
445 btDX11Buffer<float> m_dx11PerClothDampingFactor;
447 /** Velocity correction coefficient */
448 btAlignedObjectArray< float > m_perClothVelocityCorrectionCoefficient;
449 btDX11Buffer<float> m_dx11PerClothVelocityCorrectionCoefficient;
451 /** Lift parameter for wind effect on cloth. */
452 btAlignedObjectArray< float > m_perClothLiftFactor;
453 btDX11Buffer<float> m_dx11PerClothLiftFactor;
455 /** Drag parameter for wind effect on cloth. */
456 btAlignedObjectArray< float > m_perClothDragFactor;
457 btDX11Buffer<float> m_dx11PerClothDragFactor;
459 /** Density of the medium in which each cloth sits */
460 btAlignedObjectArray< float > m_perClothMediumDensity;
461 btDX11Buffer<float> m_dx11PerClothMediumDensity;
464 /**
465 * Collision shape details: pair of index of first collision shape for the cloth and number of collision objects.
467 btAlignedObjectArray< CollisionObjectIndices > m_perClothCollisionObjects;
468 btDX11Buffer<CollisionObjectIndices> m_dx11PerClothCollisionObjects;
470 /**
471 * Collision shapes being passed across to the cloths in this solver.
473 btAlignedObjectArray< CollisionShapeDescription > m_collisionObjectDetails;
474 btDX11Buffer< CollisionShapeDescription > m_dx11CollisionObjectDetails;
476 /**
477 * Minimum bounds for each cloth.
478 * Updated by GPU and returned for use by broad phase.
479 * These are int vectors as a reminder that they store the int representation of a float, not a float.
480 * Bit 31 is inverted - is floats are stored with int-sortable values.
482 btAlignedObjectArray< UIntVector3 > m_perClothMinBounds;
483 btDX11Buffer< UIntVector3 > m_dx11PerClothMinBounds;
485 /**
486 * Maximum bounds for each cloth.
487 * Updated by GPU and returned for use by broad phase.
488 * These are int vectors as a reminder that they store the int representation of a float, not a float.
489 * Bit 31 is inverted - is floats are stored with int-sortable values.
491 btAlignedObjectArray< UIntVector3 > m_perClothMaxBounds;
492 btDX11Buffer< UIntVector3 > m_dx11PerClothMaxBounds;
495 /**
496 * Friction coefficient for each cloth
498 btAlignedObjectArray< float > m_perClothFriction;
499 btDX11Buffer< float > m_dx11PerClothFriction;
501 DXFunctions::KernelDesc prepareLinksKernel;
502 DXFunctions::KernelDesc solvePositionsFromLinksKernel;
503 DXFunctions::KernelDesc vSolveLinksKernel;
504 DXFunctions::KernelDesc integrateKernel;
505 DXFunctions::KernelDesc addVelocityKernel;
506 DXFunctions::KernelDesc updatePositionsFromVelocitiesKernel;
507 DXFunctions::KernelDesc updateVelocitiesFromPositionsWithoutVelocitiesKernel;
508 DXFunctions::KernelDesc updateVelocitiesFromPositionsWithVelocitiesKernel;
509 DXFunctions::KernelDesc solveCollisionsAndUpdateVelocitiesKernel;
510 DXFunctions::KernelDesc resetNormalsAndAreasKernel;
511 DXFunctions::KernelDesc normalizeNormalsAndAreasKernel;
512 DXFunctions::KernelDesc computeBoundsKernel;
513 DXFunctions::KernelDesc updateSoftBodiesKernel;
515 DXFunctions::KernelDesc applyForcesKernel;
517 bool m_enableUpdateBounds;
520 * Integrate motion on the solver.
522 virtual void integrate( float solverdt );
523 float computeTriangleArea(
524 const Vectormath::Aos::Point3 &vertex0,
525 const Vectormath::Aos::Point3 &vertex1,
526 const Vectormath::Aos::Point3 &vertex2 );
529 virtual bool buildShaders();
531 void resetNormalsAndAreas( int numVertices );
533 void normalizeNormalsAndAreas( int numVertices );
535 void executeUpdateSoftBodies( int firstTriangle, int numTriangles );
537 void prepareCollisionConstraints();
539 Vectormath::Aos::Vector3 ProjectOnAxis( const Vectormath::Aos::Vector3 &v, const Vectormath::Aos::Vector3 &a );
541 void ApplyClampedForce( float solverdt, const Vectormath::Aos::Vector3 &force, const Vectormath::Aos::Vector3 &vertexVelocity, float inverseMass, Vectormath::Aos::Vector3 &vertexForce );
543 virtual void applyForces( float solverdt );
545 virtual void updateConstants( float timeStep );
546 int findSoftBodyIndex( const btSoftBody* const softBody );
548 //////////////////////////////////////
549 // Kernel dispatches
550 virtual void prepareLinks();
552 void updatePositionsFromVelocities( float solverdt );
553 void solveLinksForPosition( int startLink, int numLinks, float kst, float ti );
554 void solveLinksForVelocity( int startLink, int numLinks, float kst );
556 void updateVelocitiesFromPositionsWithVelocities( float isolverdt );
557 void updateVelocitiesFromPositionsWithoutVelocities( float isolverdt );
558 void computeBounds( );
559 void solveCollisionsAndUpdateVelocities( float isolverdt );
561 // End kernel dispatches
562 /////////////////////////////////////
564 void updateBounds();
567 void releaseKernels();
569 public:
570 btDX11SoftBodySolver(ID3D11Device * dx11Device, ID3D11DeviceContext* dx11Context, DXFunctions::CompileFromMemoryFunc dx11CompileFromMemory = &D3DX11CompileFromMemory);
572 virtual ~btDX11SoftBodySolver();
575 virtual SolverTypes getSolverType() const
577 return DX_SOLVER;
580 void setEnableUpdateBounds(bool enableBounds)
582 m_enableUpdateBounds = enableBounds;
584 bool getEnableUpdateBounds() const
586 return m_enableUpdateBounds;
591 virtual btSoftBodyLinkData &getLinkData();
593 virtual btSoftBodyVertexData &getVertexData();
595 virtual btSoftBodyTriangleData &getTriangleData();
601 btAcceleratedSoftBodyInterface *findSoftBodyInterface( const btSoftBody* const softBody );
602 const btAcceleratedSoftBodyInterface * const findSoftBodyInterface( const btSoftBody* const softBody ) const;
604 virtual bool checkInitialized();
606 virtual void updateSoftBodies( );
608 virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies , bool forceUpdate=false);
610 virtual void copyBackToSoftBodies(bool bMove = true);
612 virtual void solveConstraints( float solverdt );
614 virtual void predictMotion( float solverdt );
617 virtual void processCollision( btSoftBody *, const btCollisionObjectWrapper* );
619 virtual void processCollision( btSoftBody*, btSoftBody* );
625 /**
626 * Class to manage movement of data from a solver to a given target.
627 * This version is the DX to CPU version.
629 class btSoftBodySolverOutputDXtoCPU : public btSoftBodySolverOutput
631 protected:
633 public:
634 btSoftBodySolverOutputDXtoCPU()
638 /** Output current computed vertex data to the vertex buffers for all cloths in the solver. */
639 virtual void copySoftBodyToVertexBuffer( const btSoftBody * const softBody, btVertexBufferDescriptor *vertexBuffer );
642 /**
643 * Class to manage movement of data from a solver to a given target.
644 * This version is the DX to DX version and subclasses DX to CPU so that it works for that too.
646 class btSoftBodySolverOutputDXtoDX : public btSoftBodySolverOutputDXtoCPU
648 protected:
649 struct OutputToVertexArrayCB
651 int startNode;
652 int numNodes;
653 int positionOffset;
654 int positionStride;
656 int normalOffset;
657 int normalStride;
658 int padding1;
659 int padding2;
662 DXFunctions dxFunctions;
663 DXFunctions::KernelDesc outputToVertexArrayWithNormalsKernel;
664 DXFunctions::KernelDesc outputToVertexArrayWithoutNormalsKernel;
667 bool m_shadersInitialized;
669 bool checkInitialized();
670 bool buildShaders();
671 void releaseKernels();
673 public:
674 btSoftBodySolverOutputDXtoDX(ID3D11Device *dx11Device, ID3D11DeviceContext* dx11Context, DXFunctions::CompileFromMemoryFunc dx11CompileFromMemory = &D3DX11CompileFromMemory) :
675 dxFunctions( dx11Device, dx11Context, dx11CompileFromMemory )
677 m_shadersInitialized = false;
680 ~btSoftBodySolverOutputDXtoDX()
682 releaseKernels();
685 /** Output current computed vertex data to the vertex buffers for all cloths in the solver. */
686 virtual void copySoftBodyToVertexBuffer( const btSoftBody * const softBody, btVertexBufferDescriptor *vertexBuffer );
689 #endif // #ifndef BT_ACCELERATED_SOFT_BODY_DX11_SOLVER_H