30 #define BT_SUPPRESS_OPENCL_ASSERTS
36 #include <OpenCL/OpenCL.h>
42 #define BT_DEFAULT_WORKGROUPSIZE 64
45 #define RELEASE_CL_KERNEL(kernelName) {if( kernelName ){ clReleaseKernel( kernelName ); kernelName = 0; }}
51 #define MSTRINGIFY(A) #A
53 #include "OpenCLC10/PrepareLinks.cl"
55 #include "OpenCLC10/UpdatePositionsFromVelocities.cl"
56 static const char* SolvePositionsCLString =
57 #include "OpenCLC10/SolvePositions.cl"
58 static const char* UpdateNodesCLString =
59 #include "OpenCLC10/UpdateNodes.cl"
60 static const char* UpdatePositionsCLString =
61 #include "OpenCLC10/UpdatePositions.cl"
62 static const char* UpdateConstantsCLString =
63 #include "OpenCLC10/UpdateConstants.cl"
64 static const char* IntegrateCLString =
65 #include "OpenCLC10/Integrate.cl"
66 static const char* ApplyForcesCLString =
67 #include "OpenCLC10/ApplyForces.cl"
68 static const char* UpdateFixedVertexPositionsCLString =
69 #include "OpenCLC10/UpdateFixedVertexPositions.cl"
70 static const char* UpdateNormalsCLString =
71 #include "OpenCLC10/UpdateNormals.cl"
72 static const char* VSolveLinksCLString =
73 #include "OpenCLC10/VSolveLinks.cl"
74 static const char* SolveCollisionsAndUpdateVelocitiesCLString =
75 #include "OpenCLC10/SolveCollisionsAndUpdateVelocities.cl"
165 :m_cqCommandQue(queue),
166 m_clLinks( queue, ctx, &m_links, false ),
170 m_clLinksCLength( queue, ctx, &m_linksCLength, false ),
171 m_clLinksLengthRatio( queue, ctx, &m_linksLengthRatio, false ),
191 int newSize = previousSize + numLinks;
265 batchValues.
resize( numLinks, 0 );
269 for(
int linkIndex = 0; linkIndex < numLinks; ++linkIndex )
273 if( vertex0 > maxVertex )
275 if( vertex1 > maxVertex )
278 int numVertices = maxVertex + 1;
284 vertexConnectedColourLists.
resize(numVertices);
289 for(
int linkIndex = 0; linkIndex < numLinks; ++linkIndex )
310 batchValues[linkIndex] = colour;
315 for(
int i = 0; i < numLinks; ++i )
317 int batch = batchValues[i];
318 if( batch >= batchCounts.
size() )
321 ++(batchCounts[batch]);
331 for(
int batchIndex = 0; batchIndex < batchCounts.
size(); ++batchIndex )
335 sum += batchCounts[batchIndex];
353 for(
int batch = 0; batch < batchCounts.
size(); ++batch )
354 batchCounts[batch] = 0;
357 for(
int linkIndex = 0; linkIndex < numLinks; ++linkIndex )
368 int batch = batchValues[linkIndex];
371 batchCounts[batch] = batchCounts[batch] + 1;
372 m_links[newLocation] = m_links_Backup[linkLocation];
374 m_linkStrength[newLocation] = m_linkStrength_Backup[linkLocation];
375 m_linksMassLSC[newLocation] = m_linksMassLSC_Backup[linkLocation];
394 m_clVertexIndices( queue, ctx, &m_vertexIndices, false ),
395 m_clArea( queue, ctx, &m_area, false ),
396 m_clNormal( queue, ctx, &m_normal, false )
408 int newSize = previousSize + numTriangles;
464 if( numTriangles == 0 )
469 batchValues.
resize( numTriangles );
473 for(
int triangleIndex = 0; triangleIndex < numTriangles; ++triangleIndex )
479 if( vertex0 > maxVertex )
481 if( vertex1 > maxVertex )
483 if( vertex2 > maxVertex )
486 int numVertices = maxVertex + 1;
492 vertexConnectedColourLists.
resize(numVertices);
499 for(
int triangleIndex = 0; triangleIndex < numTriangles; ++triangleIndex )
532 batchValues[triangleIndex] = colour;
538 for(
int i = 0; i < numTriangles; ++i )
540 int batch = batchValues[i];
541 if( batch >= batchCounts.
size() )
544 ++(batchCounts[batch]);
553 for(
int batchIndex = 0; batchIndex < batchCounts.
size(); ++batchIndex )
557 sum += batchCounts[batchIndex];
569 for(
int batch = 0; batch < batchCounts.
size(); ++batch )
570 batchCounts[batch] = 0;
573 for(
int triangleIndex = 0; triangleIndex < numTriangles; ++triangleIndex )
584 int batch = batchValues[triangleIndex];
587 batchCounts[batch] = batchCounts[batch] + 1;
588 m_vertexIndices[newLocation] = m_vertexIndices_Backup[triangleLocation];
589 m_area[newLocation] = m_area_Backup[triangleLocation];
590 m_normal[newLocation] = m_normal_Backup[triangleLocation];
604 m_linkData(queue, ctx),
605 m_vertexData(queue, ctx),
606 m_triangleData(queue, ctx),
607 m_defaultCLFunctions(queue, ctx),
608 m_currentCLFunctions(&m_defaultCLFunctions),
609 m_clPerClothAcceleration(queue, ctx, &m_perClothAcceleration, true ),
610 m_clPerClothWindVelocity(queue, ctx, &m_perClothWindVelocity, true ),
611 m_clPerClothDampingFactor(queue,ctx, &m_perClothDampingFactor, true ),
612 m_clPerClothVelocityCorrectionCoefficient(queue, ctx,&m_perClothVelocityCorrectionCoefficient, true ),
613 m_clPerClothLiftFactor(queue, ctx,&m_perClothLiftFactor, true ),
614 m_clPerClothDragFactor(queue, ctx,&m_perClothDragFactor, true ),
615 m_clPerClothMediumDensity(queue, ctx,&m_perClothMediumDensity, true ),
616 m_clPerClothCollisionObjects( queue, ctx, &m_perClothCollisionObjects, true ),
617 m_clCollisionObjectDetails( queue, ctx, &m_collisionObjectDetails, true ),
618 m_clPerClothFriction( queue, ctx, &m_perClothFriction, false ),
619 m_clAnchorPosition( queue, ctx, &m_anchorPosition, true ),
620 m_clAnchorIndex( queue, ctx, &m_anchorIndex, true),
621 m_cqCommandQue( queue ),
622 m_cxMainContext(ctx),
624 m_bUpdateAnchoredNodePos(bUpdateAchchoredNodePos)
685 for(
int softBodyIndex = 0; softBodyIndex <
m_softBodySet.
size(); ++softBodyIndex )
694 for(
int vertex = 0; vertex < numVertices; ++vertex )
700 softBody->
m_nodes[vertex].m_x.setX( vertexPosition.getX() );
701 softBody->
m_nodes[vertex].m_x.setY( vertexPosition.getY() );
702 softBody->
m_nodes[vertex].m_x.setZ( vertexPosition.getZ() );
704 softBody->
m_nodes[vertex].m_n.setX( normal.getX() );
705 softBody->
m_nodes[vertex].m_n.setY( normal.getY() );
706 softBody->
m_nodes[vertex].m_n.setZ( normal.getZ() );
722 int maxPiterations = 0;
723 int maxViterations = 0;
725 for(
int softBodyIndex = 0; softBodyIndex < softBodies.
size(); ++softBodyIndex )
727 btSoftBody *softBody = softBodies[ softBodyIndex ];
749 int maxVertices = numVertices;
755 int maxTriangles = numTriangles;
759 for(
int vertex = 0; vertex < numVertices; ++vertex )
761 Point3 multPoint(softBody->
m_nodes[vertex].m_x.getX(), softBody->
m_nodes[vertex].m_x.getY(), softBody->
m_nodes[vertex].m_x.getZ());
769 float vertexInverseMass = softBody->
m_nodes[vertex].m_im;
770 desc.setInverseMass(vertexInverseMass);
778 for(
int triangle = 0; triangle < numTriangles; ++triangle )
782 int vertexIndex0 = (softBody->
m_faces[triangle].m_n[0] - &(softBody->
m_nodes[0]));
783 int vertexIndex1 = (softBody->
m_faces[triangle].m_n[1] - &(softBody->
m_nodes[0]));
784 int vertexIndex2 = (softBody->
m_faces[triangle].m_n[2] - &(softBody->
m_nodes[0]));
802 for(
int link = 0; link < numLinks; ++link )
804 int vertexIndex0 = softBody->
m_links[link].m_n[0] - &(softBody->
m_nodes[0]);
805 int vertexIndex1 = softBody->
m_links[link].m_n[1] - &(softBody->
m_nodes[0]);
824 if ( piterations > maxPiterations )
825 maxPiterations = piterations;
829 if ( viterations > maxViterations )
830 maxViterations = viterations;
833 for(
int vertex = 0; vertex < numVertices; ++vertex )
835 if ( softBody->
m_nodes[vertex].m_im == 0 )
846 if ( numVertices > 0 )
848 for (
int anchorIndex = 0; anchorIndex < softBody->
m_anchors.
size(); anchorIndex++ )
854 nodeInfo.
clVertexIndex = firstVertex + (int)(anchorNode - firstNode);
855 nodeInfo.
pNode = anchorNode;
881 for(
int softBodyIndex = 0; softBodyIndex <
m_softBodySet.
size(); ++softBodyIndex )
931 btAssert( 0 &&
"enqueueNDRangeKernel(m_resetNormalsAndAreasKernel)" );
951 btAssert( 0 &&
"enqueueNDRangeKernel(m_normalizeNormalsAndAreasKernel)");
973 btAssert( 0 &&
"enqueueNDRangeKernel(m_normalizeNormalsAndAreasKernel)");
980 using namespace Vectormath::Aos;
1015 float dtInverseMass = solverdt*inverseMass;
1020 vertexForce += force;
1044 btAssert( 0 &&
"enqueueNDRangeKernel(m_updateFixedVertexPositionsKernel)");
1064 float fl = FLT_EPSILON;
1084 btAssert( 0 &&
"enqueueNDRangeKernel(m_applyForcesKernel)");
1114 btAssert( 0 &&
"enqueueNDRangeKernel(m_integrateKernel)");
1128 float area =
length( crossProduct );
1135 for(
int softBodyIndex = 0; softBodyIndex <
m_softBodySet.
size(); ++softBodyIndex )
1137 btVector3 minBound(-1e30,-1e30,-1e30), maxBound(1e30,1e30,1e30);
1138 m_softBodySet[softBodyIndex]->updateBounds( minBound, maxBound );
1147 using namespace Vectormath::Aos;
1157 for(
int linkIndex = 0; linkIndex < numLinks; ++linkIndex )
1164 float massLSC = (invMass0 + invMass1)/linearStiffness;
1167 float restLengthSquared = restLength*restLength;
1210 int currentCloth = 0;
1215 if( nextCloth != currentCloth )
1221 currentCloth = nextCloth;
1222 startIndex = collisionObject;
1279 if( m_numberOfVelocityIterations > 0 )
1323 btAssert( 0 &&
"enqueueNDRangeKernel(m_prepareLinksKernel)");
1342 btAssert( 0 &&
"enqueueNDRangeKernel(m_updatePositionsFromVelocitiesKernel)");
1364 btAssert( 0 &&
"enqueueNDRangeKernel(m_solvePositionsFromLinksKernel)");
1386 btAssert( 0 &&
"enqueueNDRangeKernel(m_vSolveLinksKernel)");
1409 btAssert( 0 &&
"enqueueNDRangeKernel(m_updateVelocitiesFromPositionsWithVelocitiesKernel)");
1432 btAssert( 0 &&
"enqueueNDRangeKernel(m_updateVelocitiesFromPositionsWithoutVelocitiesKernel)");
1468 btAssert( 0 &&
"enqueueNDRangeKernel(m_updateVelocitiesFromPositionsWithoutVelocitiesKernel)");
1492 const int lastVertex = firstVertex + currentCloth->
getNumVertices();
1506 float *vertexPointer = basePointer + vertexOffset;
1508 for(
int vertexIndex = firstVertex; vertexIndex < lastVertex; ++vertexIndex )
1511 *(vertexPointer + 0) = position.
getX();
1512 *(vertexPointer + 1) = position.
getY();
1513 *(vertexPointer + 2) = position.
getZ();
1514 vertexPointer += vertexStride;
1521 float *normalPointer = basePointer + normalOffset;
1523 for(
int vertexIndex = firstVertex; vertexIndex < lastVertex; ++vertexIndex )
1526 *(normalPointer + 0) = normal.
getX();
1527 *(normalPointer + 1) = normal.
getY();
1528 *(normalPointer + 2) = normal.
getZ();
1529 normalPointer += normalStride;
1540 printf(
"compiling kernelName: %s ",kernelName);
1543 size_t program_length = strlen(kernelSource);
1552 char* flags =
"-cl-mad-enable -DMAC -DGUID_ARG";
1555 const char* flags =
"-DGUID_ARG= ";
1558 char* compileFlags =
new char[strlen(additionalMacros) + strlen(flags) + 5];
1559 sprintf(compileFlags,
"%s %s", flags, additionalMacros);
1560 ciErrNum =
clBuildProgram(m_cpProgram, 0, NULL, compileFlags, NULL, NULL);
1567 for(
int i = 0; i < 2; ++i )
1570 size_t ret_val_size;
1572 build_log =
new char[ret_val_size+1];
1577 build_log[ret_val_size] =
'\0';
1580 printf(
"Error in clBuildProgram, Line %u in file %s, Log: \n%s\n !!!\n\n", __LINE__, __FILE__, build_log);
1583 #ifndef BT_SUPPRESS_OPENCL_ASSERTS
1585 #endif //BT_SUPPRESS_OPENCL_ASSERTS
1586 m_kernelCompilationFailures++;
1595 const char* msg =
"";
1599 msg =
"Program is not a valid program object.";
1602 msg =
"There is no successfully built executable for program.";
1605 msg =
"kernel_name is not found in program.";
1608 msg =
"the function definition for __kernel function given by kernel_name such as the number of arguments, the argument types are not the same for all devices for which the program executable has been built.";
1611 msg =
"kernel_name is NULL.";
1614 msg =
"Failure to allocate resources required by the OpenCL implementation on the host.";
1621 printf(
"Error in clCreateKernel for kernel '%s', error is \"%s\", Line %u in file %s !!!\n\n", kernelName, msg, __LINE__, __FILE__);
1623 #ifndef BT_SUPPRESS_OPENCL_ASSERTS
1625 #endif //BT_SUPPRESS_OPENCL_ASSERTS
1626 m_kernelCompilationFailures++;
1630 printf(
"ready. \n");
1631 delete [] compileFlags;
1633 m_kernelCompilationFailures++;
1693 return outTransform;
1698 float scalarMargin = (float)getSoftBody()->getCollisionShape()->getMargin();
1699 btVector3 vectorMargin( scalarMargin, scalarMargin, scalarMargin );
1700 m_softBody->m_bounds[0] = lowerBound - vectorMargin;
1701 m_softBody->m_bounds[1] = upperBound + vectorMargin;
1714 if( softBodyIndex >= 0 )
1728 newCollisionShapeDescription.
radius = capsule->getRadius();
1729 newCollisionShapeDescription.
halfHeight = capsule->getHalfHeight();
1730 newCollisionShapeDescription.
margin = capsule->getMargin();
1731 newCollisionShapeDescription.
upAxis = capsule->getUpAxis();
1732 newCollisionShapeDescription.
friction = friction;
1741 printf(
"Unsupported collision shape type\n");
1746 btAssert(0 &&
"Unknown soft body");
1756 for(
int softBodyIndex = 0; softBodyIndex <
m_softBodySet.
size(); ++softBodyIndex )
1759 if( softBodyInterface->
getSoftBody() == softBody )
1760 return softBodyInterface;
1768 for(
int softBodyIndex = 0; softBodyIndex <
m_softBodySet.
size(); ++softBodyIndex )
1771 if( softBodyInterface->
getSoftBody() == softBody )
1772 return softBodyIndex;
1791 const char* additionalMacros=
"";
void setFirstTriangle(int firstTriangle)
static T sum(const btAlignedObjectArray< T > &items)
struct _cl_device_id * cl_device_id
btOpenCLBuffer< Vectormath::Aos::Point3 > m_clAnchorPosition
virtual void setTriangleAt(const TriangleDescription &triangle, int triangleIndex)
btOpenCLBuffer< Vectormath::Aos::Point3 > m_clVertexPosition
btAlignedObjectArray< int > m_linkAddresses
Link addressing information for each cloth.
btScalar length(const btQuaternion &q)
Return the length of a quaternion.
void createVertices(int numVertices, int clothIdentifier, int maxVertices=0)
Create numVertices new vertices for cloth clothIdentifier maxVertices allows a buffer zone of extra v...
btAlignedObjectArray< float > m_perClothDragFactor
Drag parameter for wind effect on cloth.
void push_back(const T &_Val)
virtual void solveCollisionsAndUpdateVelocities(float isolverdt)
struct _cl_context * cl_context
btOpenCLBuffer< float > m_clPerClothLiftFactor
virtual void setNumberOfPositionIterations(int iterations)
Set the number of velocity constraint solver iterations this solver uses.
#define CL_INVALID_KERNEL_NAME
CL_API_ENTRY cl_kernel CL_API_CALL clCreateKernel(cl_program, const char *, cl_int *) CL_API_SUFFIX__VERSION_1_0
static const char m_clVertexInverseMass(queue, ctx,&m_vertexInverseMass, false)
btOpenCLBuffer< Vectormath::Aos::Vector3 > m_clNormal
Vectormath::Aos::Vector3 linearVelocity
virtual void createTriangles(int numTriangles)
btOpenCLBuffer< Vectormath::Aos::Vector3 > m_clLinksCLength
cl_kernel m_normalizeNormalsAndAreasKernel
void setPosition(const Vectormath::Aos::Point3 &position)
virtual void applyForces(float solverdt)
virtual bool hasVertexPositions() const
virtual void setLinkAt(const LinkDescription &link, int linkIndex)
Insert the link described into the correct data structures assuming space has already been allocated ...
btOpenCLBuffer< Vectormath::Aos::Point3 > m_clVertexPreviousPosition
virtual bool onAccelerator()
Return true if data is on the accelerator.
btAlignedObjectArray< Vectormath::Aos::Vector3 > m_normal
CL_API_ENTRY cl_program CL_API_CALL clCreateProgramWithSource(cl_context, cl_uint, const char **, const size_t *, cl_int *) CL_API_SUFFIX__VERSION_1_0
static Vectormath::Aos::Vector3 toVector3(const btVector3 &vec)
btAlignedObjectArray< TriangleNodeSet > m_vertexIndices
virtual void predictMotion(float solverdt)
Predict motion of soft bodies into next timestep.
cl_kernel m_solvePositionsFromLinksKernel
virtual bool onAccelerator()
Return true if data is on the accelerator.
virtual ~btSoftBodyLinkDataOpenCL()
btOpenCLBuffer< float > m_clPerClothFriction
#define CL_PROGRAM_BUILD_LOG
cl_command_queue m_cqCommandQue
virtual BufferTypes getBufferType() const =0
Return the type of the vertex buffer descriptor.
float computeTriangleArea(const Vectormath::Aos::Point3 &vertex0, const Vectormath::Aos::Point3 &vertex1, const Vectormath::Aos::Point3 &vertex2)
btOpenCLBuffer< Vectormath::Aos::Vector3 > m_clVertexForceAccumulator
float & getRestLengthSquared(int linkIndex)
Return reference to rest length squared for link linkIndex as stored on the host. ...
#define RELEASE_CL_KERNEL(kernelName)
void solveLinksForVelocity(int startLink, int numLinks, float kst)
#define CL_PROGRAM_DEVICES
btOpenCLBuffer< float > m_clLinkStrength
virtual bool moveToAccelerator()
Move data from host memory to the accelerator.
void generateBatches()
Generate (and later update) the batching for the entire triangle set.
void setMaxTriangles(int maxTriangles)
The btCapsuleShape represents a capsule around the Y axis, there is also the btCapsuleShapeX aligned ...
CLFunctions * m_currentCLFunctions
btAlignedObjectArray< CollisionObjectIndices > m_perClothCollisionObjects
Collision shape details: pair of index of first collision shape for the cloth and number of collision...
int & getTriangleCount(int vertexIndex)
Get access to the array of how many triangles touch each vertex.
virtual void copySoftBodyToVertexBuffer(const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer)
Output current computed vertex data to the vertex buffers for all cloths in the solver.
void resetNormalsAndAreas(int numVertices)
virtual bool moveFromAccelerator(bool bCopy=false, bool bCopyMinimum=true)
Move data to host memory from the accelerator if bCopy is false.
btOpenCLBuffer< float > m_clVertexInverseMass
btSoftBodyLinkDataOpenCL m_linkData
The btCollisionShape class provides an interface for collision shapes that can be shared among btColl...
virtual cl_kernel compileCLKernelFromString(const char *kernelSource, const char *kernelName, const char *additionalMacros, const char *srcFileNameForCaching)
Compile a compute shader kernel from a string and return the appropriate cl_kernel object...
btOpenCLBuffer< float > m_clLinksLengthRatio
static const char * PrepareLinksCLString
SoftBody class to maintain information about a soft body instance within a solver.
virtual bool moveFromAccelerator()
Move data from host memory from the accelerator.
btOpenCLBuffer< float > m_clLinksRestLength
float & getLinearStiffnessCoefficient(int linkIndex)
Return reference to linear stiffness coefficient for link linkIndex as stored on the host...
#define BT_DEFAULT_WORKGROUPSIZE
LinkNodePair & getVertexPair(int linkIndex)
Return reference to the vertex index pair for link linkIndex as stored on the host.
void ApplyClampedForce(float solverdt, const Vectormath::Aos::Vector3 &force, const Vectormath::Aos::Vector3 &vertexVelocity, float inverseMass, Vectormath::Aos::Vector3 &vertexForce)
static const char m_clVertexPosition(queue, ctx,&m_vertexPosition, false)
CL_API_ENTRY cl_int CL_API_CALL clEnqueueNDRangeKernel(cl_command_queue, cl_kernel, cl_uint, const size_t *, const size_t *, const size_t *, cl_uint, const cl_event *, cl_event *) CL_API_SUFFIX__VERSION_1_0
Start and length values for computation batches over link data.
virtual bool checkInitialized()
Ensure that this solver is initialized.
Class describing a vertex for input into the system.
btVector3 getColumn(int i) const
Get a column of the matrix as a vector.
void normalizeNormalsAndAreas(int numVertices)
btAlignedObjectArray< Vectormath::Aos::Vector3 > m_linksCLength
int getKernelCompilationFailures() const
cl_kernel m_updateVelocitiesFromPositionsWithVelocitiesKernel
virtual void setTriangleAt(const btSoftBodyTriangleData::TriangleDescription &triangle, int triangleIndex)
Insert the link described into the correct data structures assuming space has already been allocated ...
btSoftBodyTriangleDataOpenCL(cl_command_queue queue, cl_context ctx)
btOpenCLBuffer< float > m_clVertexArea
virtual bool moveToAccelerator()
Move data from host memory to the accelerator.
btOpenCLBuffer< float > m_clLinksMassLSC
bool m_shadersInitialized
cl_kernel m_integrateKernel
CL_API_ENTRY cl_int CL_API_CALL clGetProgramBuildInfo(cl_program, cl_device_id, cl_program_build_info, size_t, void *, size_t *) CL_API_SUFFIX__VERSION_1_0
static const char * UpdatePositionsFromVelocitiesCLString
btSoftBodyTriangleDataOpenCL m_triangleData
int findSoftBodyIndex(const btSoftBody *const softBody)
TriangleNodeSet getVertexSet() const
btAlignedObjectArray< btOpenCLAcceleratedSoftBodyInterface * > m_softBodySet
Cloths owned by this solver.
static float4 normalize(const float4 &a)
const btScalar & getZ() const
Return the z value.
btAlignedObjectArray< Vectormath::Aos::Vector3 > m_perClothWindVelocity
Wind velocity to be applied normal to all non-static vertices in the solver.
btOpenCLBuffer< CollisionShapeDescription > m_clCollisionObjectDetails
void clear()
clear the array, deallocated memory. Generally it is better to use array.resize(0), to reduce performance overhead of run-time memory (de)allocations.
btOpenCLBuffer< Vectormath::Aos::Vector3 > m_clPerClothAcceleration
btAlignedObjectArray< float > m_linkStrength
float & getMassLSC(int linkIndex)
Return reference to the MassLSC value for link linkIndex as stored on the host.
static const char m_clVertexNormal(queue, ctx,&m_vertexNormal, false)
virtual void copyBackToSoftBodies(bool bMove=true)
Copy necessary data back to the original soft body source objects.
float lengthSqr(const Vector3 &vec)
btSoftBodyWorldInfo * getWorldInfo()
void updateFixedVertexPositions()
btAlignedObjectArray< Vectormath::Aos::Vector3 > m_perClothAcceleration
Acceleration value to be applied to all non-static vertices in the solver.
static const char m_clVertexTriangleCount(queue, ctx,&m_vertexTriangleCount, false)
btAlignedObjectArray< AnchorNodeInfoCL > m_anchorNodeInfoArray
Vectormath::Aos::Transform3 shapeTransform
btOpenCLBuffer< btSoftBodyTriangleData::TriangleNodeSet > m_clVertexIndices
btOpenCLSoftBodySolver(cl_command_queue queue, cl_context ctx, bool bUpdateAchchoredNodePos=false)
int size() const
return the number of elements in the array
btSoftBodyLinkDataOpenCL(cl_command_queue queue, cl_context ctx)
virtual btSoftBodyLinkData & getLinkData()
const btVector3 & getWindVelocity()
Return the wind velocity for interaction with the air.
Entry in the collision shape array.
virtual SolverTypes getSolverType() const =0
Return the type of the solver.
cl_kernel m_resetNormalsAndAreasKernel
#define CL_INVALID_KERNEL_DEFINITION
struct _cl_kernel * cl_kernel
btAlignedObjectArray< Vectormath::Aos::Point3 > & getVertexPositions()
btAlignedObjectArray< LinkNodePair > m_links
bool m_bUpdateAnchoredNodePos
cl_kernel m_prepareLinksKernel
void setFirstVertex(int firstVertex)
Class representing a link as a set of three indices into the vertex array.
virtual bool buildShaders()
btSoftBodyVertexDataOpenCL(cl_command_queue queue, cl_context ctx)
cl_kernel m_applyForcesKernel
btSoftBodySolver * getSoftBodySolver()
const btVector3 & getAngularVelocity() const
btAlignedObjectArray< int > m_anchorIndex
const btScalar & getY() const
Return the y value.
const btTransform & getWorldTransform() const
cl_kernel m_updateSoftBodiesKernel
static const char m_clLinkStrength(queue, ctx,&m_linkStrength, false)
const btScalar & getX() const
Return the x value.
static const char m_clLinksRestLengthSquared(queue, ctx,&m_linksRestLengthSquared, false)
virtual void changedOnCPU()
The btRigidBody is the main class for rigid body objects.
virtual void integrate(float solverdt)
Integrate motion on the solver.
cl_context m_cxMainContext
void updateBounds(const btVector3 &lowerBound, const btVector3 &upperBound)
Update the bounds in the btSoftBody object.
float & getRestLength(int linkIndex)
Return reference to the rest length of link linkIndex as stored on the host.
btAlignedObjectArray< float > m_linksRestLengthSquared
btAlignedObjectArray< float > m_linksLengthRatio
btAlignedObjectArray< BatchPair > m_batchStartLengths
Start and length values for computation batches over link data.
cl_kernel m_vSolveLinksKernel
btAlignedObjectArray< float > m_linksMaterialLinearStiffnessCoefficient
virtual void processCollision(btSoftBody *, const btCollisionObjectWrapper *)
btAlignedObjectArray< float > m_perClothDampingFactor
Velocity damping factor.
CL_API_ENTRY cl_int CL_API_CALL clSetKernelArg(cl_kernel, cl_uint, size_t, const void *) CL_API_SUFFIX__VERSION_1_0
btAlignedObjectArray< float > m_perClothVelocityCorrectionCoefficient
Velocity correction coefficient.
virtual int getVertexStride() const
Return the vertex stride in number of floats between vertices.
btAlignedObjectArray< float > m_perClothFriction
Friction coefficient for each cloth.
static const char m_clVertexArea(queue, ctx,&m_vertexArea, false)
#define CL_INVALID_PROGRAM
const btCollisionShape * getCollisionShape() const
void updateVelocitiesFromPositionsWithVelocities(float isolverdt)
btOpenCLBuffer< Vectormath::Aos::Vector3 > m_clVertexVelocity
void generateBatches()
Generate (and later update) the batching for the entire link set.
btVector3 can be used to represent 3D points and vectors.
int m_numberOfVelocityIterations
void prepareCollisionConstraints()
Sort the collision object details array and generate indexing into it for the per-cloth collision obj...
virtual int getVertexOffset() const
Return the vertex offset in floats from the base pointer.
Vectormath::Aos::Vector3 ProjectOnAxis(const Vectormath::Aos::Vector3 &v, const Vectormath::Aos::Vector3 &a)
cl_kernel m_addVelocityKernel
btOpenCLBuffer< float > m_clLinksMaterialLinearStiffnessCoefficient
Class describing a link for input into the system.
void clearKernelCompilationFailures()
static const char m_clLinksRestLength(queue, ctx,&m_linksRestLength, false)
btOpenCLBuffer< float > m_clPerClothMediumDensity
Wrapper for vertex data information.
btOpenCLBuffer< float > m_clArea
btOpenCLBuffer< float > m_clLinksRestLengthSquared
CL_API_ENTRY cl_int CL_API_CALL clGetProgramInfo(cl_program, cl_program_info, size_t, void *, size_t *) CL_API_SUFFIX__VERSION_1_0
btOpenCLBuffer< float > m_clPerClothDampingFactor
virtual void solveLinksForPosition(int startLink, int numLinks, float kst, float ti)
void executeUpdateSoftBodies(int firstTriangle, int numTriangles)
Vectormath::Aos::Vector3 & getNormal(int vertexIndex)
Return a reference to the normal of vertex vertexIndex as stored on the host.
virtual void updateConstants(float timeStep)
btOpenCLAcceleratedSoftBodyInterface * findSoftBodyInterface(const btSoftBody *const softBody)
void resize(int newsize, const T &fillData=T())
btAlignedObjectArray< float > m_perClothLiftFactor
Lift parameter for wind effect on cloth.
void updateVelocitiesFromPositionsWithoutVelocities(float isolverdt)
Vectormath::Aos::Vector3 angularVelocity
btAlignedObjectArray< float > m_linksMassLSC
float & getInverseMass(int vertexIndex)
Return a reference to the inverse mass of vertex vertexIndex as stored on the host.
int findLinearSearch(const T &key) const
btAlignedObjectArray< btSomePair > m_batchStartLengths
virtual int getNormalOffset() const
Return the vertex offset in floats from the base pointer.
btOpenCLBuffer< int > m_clVertexTriangleCount
void setNumVertices(int numVertices)
Vectormath::Aos::Point3 & getPosition(int vertexIndex)
Return a reference to the position of vertex vertexIndex as stored on the host.
btScalar getFriction() const
virtual float * getBasePointer() const
Return the base pointer in memory to the first vertex.
virtual btSoftBodyVertexData & getVertexData()
static float4 cross(const float4 &a, const float4 &b)
btOpenCLBuffer< Vectormath::Aos::Vector3 > m_clVertexNormal
struct _cl_command_queue * cl_command_queue
void setMaxVertices(int maxVertices)
cl_kernel m_updateConstantsKernel
static const char m_clLinksMaterialLinearStiffnessCoefficient(queue, ctx,&m_linksMaterialLinearStiffnessCoefficient, false)
btOpenCLBuffer< Vectormath::Aos::Vector3 > m_clPerClothWindVelocity
void setNumLinks(int numLinks)
btAlignedObjectArray< float > m_area
static Vectormath::Aos::Transform3 toTransform3(const btTransform &transform)
static const char m_clLinksMassLSC(queue, ctx,&m_linksMassLSC, false)
void setFirstLink(int firstLink)
float getTimeScale()
Return the timescale that the simulation is using.
cl_kernel m_outputToVertexArrayKernel
virtual ~btOpenCLSoftBodySolver()
btAlignedObjectArray< float > m_linksRestLength
#define CL_OUT_OF_HOST_MEMORY
btAlignedObjectArray< CollisionShapeDescription > m_collisionObjectDetails
Collision shapes being passed across to the cloths in this solver.
void updatePositionsFromVelocities(float solverdt)
const btVector3 & getLinearVelocity() const
virtual void optimize(btAlignedObjectArray< btSoftBody * > &softBodies, bool forceUpdate=false)
Optimize soft bodies in this solver.
virtual ~btSoftBodyVertexDataOpenCL()
cl_kernel m_solveCollisionsAndUpdateVelocitiesKernel
virtual void updateSoftBodies()
Perform necessary per-step updates of soft bodies such as recomputing normals and bounding boxes...
cl_kernel m_updateFixedVertexPositionsKernel
const TriangleNodeSet & getVertexSet(int triangleIndex)
Return the vertex index set for triangle triangleIndex as stored on the host.
static const char m_clVertexForceAccumulator(queue, ctx,&m_vertexForceAccumulator, false)
struct _cl_program * cl_program
void setNumTriangles(int numTriangles)
btAlignedObjectArray< int > m_triangleAddresses
Link addressing information for each cloth.
btAlignedObjectArray< float > m_perClothMediumDensity
Density of the medium in which each cloth sits.
float dot(const Quat &quat0, const Quat &quat1)
virtual bool onAccelerator()
Return true if data is on the accelerator.
bool m_updateSolverConstants
Variable to define whether we need to update solver constants on the next iteration.
btOpenCLBuffer< float > m_clPerClothVelocityCorrectionCoefficient
void setLinkStrength(float strength)
CL_API_ENTRY cl_int CL_API_CALL clBuildProgram(cl_program, cl_uint, const cl_device_id *, const char *, void(*pfn_notify)(cl_program, void *), void *) CL_API_SUFFIX__VERSION_1_0
btOpenCLBuffer< float > m_clPerClothDragFactor
The btSoftBody is an class to simulate cloth and volumetric soft bodies.
virtual btSoftBodyTriangleData & getTriangleData()
virtual ~btSoftBodyTriangleDataOpenCL()
static const char m_clVertexVelocity(queue, ctx,&m_vertexVelocity, false)
virtual void setLinkAt(const LinkDescription &link, int linkIndex)
Insert the link described into the correct data structures assuming space has already been allocated ...
btSoftBodyVertexDataOpenCL m_vertexData
btOpenCLBuffer< int > m_clClothIdentifier
virtual void createTriangles(int numTriangles)
Allocate enough space in all link-related arrays to fit numLinks links.
btAlignedObjectArray< Vectormath::Aos::Point3 > m_anchorPosition
cl_kernel m_updatePositionsFromVelocitiesKernel
void setVertexAt(const VertexDescription &vertex, int vertexIndex)
virtual bool moveFromAccelerator()
Move data from host memory from the accelerator.
virtual bool moveToAccelerator()
Move data from host memory to the accelerator.
#define CL_INVALID_PROGRAM_EXECUTABLE
virtual void setNumberOfVelocityIterations(int iterations)
Set the number of velocity constraint solver iterations this solver uses.
btOpenCLBuffer< LinkNodePair > m_clLinks
cl_kernel m_updateVelocitiesFromPositionsWithoutVelocitiesKernel
static const char m_clClothIdentifier(queue, ctx,&m_clothIdentifier, false)
void quickSort(const L &CompareFunc)
virtual bool hasNormals() const
virtual int getNormalStride() const
Return the vertex stride in number of floats between vertices.
virtual void solveConstraints(float solverdt)
Solve constraints for a set of soft bodies.
btSoftBody * getSoftBody()
int m_numberOfPositionIterations
const btCollisionObject * getCollisionObject() const
virtual void createLinks(int numLinks)
Allocate enough space in all link-related arrays to fit numLinks links.
btOpenCLBuffer< CollisionObjectIndices > m_clPerClothCollisionObjects
virtual void createLinks(int numLinks)
Allocate enough space in all link-related arrays to fit numLinks links.
size_t m_defaultWorkGroupSize
btOpenCLBuffer< int > m_clAnchorIndex
static const char m_clVertexPreviousPosition(queue, ctx,&m_vertexPreviousPosition, false)