Re-introduce GPU parallel Jacobi solver, called btGpuJacobiContactSolver. There are still some issues, but for basic scene's it works.
To avoid confusion, rename GPU contact solver to btGpuContactSolver, and constraint (non-contact) solver to btPgsConstraintSolver.
This commit is contained in:
@@ -2815,6 +2815,7 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT( b3OpenCLArray<b3Int4>*
|
||||
}
|
||||
|
||||
b3AlignedObjectArray<b3Contact4> oldHostContacts;
|
||||
|
||||
if (oldContacts->size())
|
||||
{
|
||||
oldContacts->copyToHost(oldHostContacts);
|
||||
@@ -2897,11 +2898,11 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT( b3OpenCLArray<b3Int4>*
|
||||
hostCollidables[collidableIndexB].m_shapeType == SHAPE_CONVEX_HULL)
|
||||
{
|
||||
//printf("hostPairs[i].z=%d\n",hostPairs[i].z);
|
||||
int contactIndex = computeContactConvexConvex2(i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf,
|
||||
hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts);
|
||||
//int contactIndex = computeContactConvexConvex(hostPairs,i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf,
|
||||
// hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,
|
||||
// oldHostContacts);
|
||||
//int contactIndex = computeContactConvexConvex2(i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf,
|
||||
// hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,oldHostContacts);
|
||||
int contactIndex = computeContactConvexConvex(hostPairs,i,bodyIndexA,bodyIndexB,collidableIndexA,collidableIndexB,hostBodyBuf,
|
||||
hostCollidables,hostConvexData,hostVertices,hostUniqueEdges,hostIndices,hostFaces,hostContacts,nContacts,maxContactCapacity,
|
||||
oldHostContacts);
|
||||
|
||||
|
||||
if (contactIndex>=0)
|
||||
@@ -2926,6 +2927,9 @@ void GpuSatCollision::computeConvexConvexContactsGPUSAT( b3OpenCLArray<b3Int4>*
|
||||
{
|
||||
|
||||
contactOut->copyFromHost(hostContacts);
|
||||
} else
|
||||
{
|
||||
contactOut->resize(0);
|
||||
}
|
||||
|
||||
return;
|
||||
|
||||
1381
src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.cpp
Normal file
1381
src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.cpp
Normal file
File diff suppressed because it is too large
Load Diff
62
src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.h
Normal file
62
src/Bullet3OpenCL/RigidBody/b3GpuJacobiContactSolver.h
Normal file
@@ -0,0 +1,62 @@
|
||||
|
||||
#ifndef B3_GPU_JACOBI_CONTACT_SOLVER_H
|
||||
#define B3_GPU_JACOBI_CONTACT_SOLVER_H
|
||||
#include "Bullet3OpenCL/Initialize/b3OpenCLInclude.h"
|
||||
//#include "Bullet3Collision/NarrowPhaseCollision/shared/b3RigidBodyData.h"
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3RigidBodyCL.h"
|
||||
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/shared/b3Contact4Data.h"
|
||||
#include "Bullet3OpenCL/ParallelPrimitives/b3OpenCLArray.h"
|
||||
|
||||
|
||||
//struct b3InertiaCL;
|
||||
//b3InertiaData
|
||||
|
||||
class b3TypedConstraint;
|
||||
|
||||
struct b3JacobiSolverInfo
|
||||
{
|
||||
int m_fixedBodyIndex;
|
||||
|
||||
float m_deltaTime;
|
||||
float m_positionDrift;
|
||||
float m_positionConstraintCoeff;
|
||||
int m_numIterations;
|
||||
|
||||
b3JacobiSolverInfo()
|
||||
:m_fixedBodyIndex(0),
|
||||
m_deltaTime(1./60.f),
|
||||
m_positionDrift( 0.005f ),
|
||||
m_positionConstraintCoeff( 0.99f ),
|
||||
m_numIterations(7)
|
||||
{
|
||||
}
|
||||
};
|
||||
class b3GpuJacobiContactSolver
|
||||
{
|
||||
protected:
|
||||
|
||||
struct b3GpuJacobiSolverInternalData* m_data;
|
||||
|
||||
cl_context m_context;
|
||||
cl_device_id m_device;
|
||||
cl_command_queue m_queue;
|
||||
|
||||
public:
|
||||
|
||||
b3GpuJacobiContactSolver(cl_context ctx, cl_device_id device, cl_command_queue queue, int pairCapacity);
|
||||
virtual ~b3GpuJacobiContactSolver();
|
||||
|
||||
|
||||
void solveContacts(int numBodies, cl_mem bodyBuf, cl_mem inertiaBuf, int numContacts, cl_mem contactBuf, const struct b3Config& config, int static0Index);
|
||||
void solveGroupHost(b3RigidBodyCL* bodies,b3InertiaCL* inertias,int numBodies,struct b3Contact4* manifoldPtr, int numManifolds,const b3JacobiSolverInfo& solverInfo);
|
||||
//void solveGroupHost(btRigidBodyCL* bodies,b3InertiaData* inertias,int numBodies,btContact4* manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btJacobiSolverInfo& solverInfo);
|
||||
|
||||
//b3Scalar solveGroup(b3OpenCLArray<b3RigidBodyCL>* gpuBodies,b3OpenCLArray<b3InertiaCL>* gpuInertias, int numBodies,b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints,int numConstraints,const b3ContactSolverInfo& infoGlobal);
|
||||
|
||||
//void solveGroup(btOpenCLArray<btRigidBodyCL>* bodies,btOpenCLArray<btInertiaCL>* inertias,btOpenCLArray<btContact4>* manifoldPtr,const btJacobiSolverInfo& solverInfo);
|
||||
//void solveGroupMixed(btOpenCLArray<btRigidBodyCL>* bodies,btOpenCLArray<btInertiaCL>* inertias,btOpenCLArray<btContact4>* manifoldPtr,const btJacobiSolverInfo& solverInfo);
|
||||
|
||||
};
|
||||
#endif //B3_GPU_JACOBI_CONTACT_SOLVER_H
|
||||
|
||||
@@ -22,7 +22,7 @@ bool useGpuSolveJointConstraintRows=true;
|
||||
bool useGpuWriteBackVelocities = true;
|
||||
bool gpuBreakConstraints = true;
|
||||
|
||||
#include "b3GpuPgsJacobiSolver.h"
|
||||
#include "b3GpuPgsConstraintSolver.h"
|
||||
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3RigidBodyCL.h"
|
||||
|
||||
@@ -119,7 +119,7 @@ b3Vector3 getVelocityInLocalPoint(b3RigidBodyCL* rb, const b3Vector3& rel_pos)
|
||||
|
||||
|
||||
|
||||
b3GpuPgsJacobiSolver::b3GpuPgsJacobiSolver (cl_context ctx, cl_device_id device, cl_command_queue queue,bool usePgs)
|
||||
b3GpuPgsConstraintSolver::b3GpuPgsConstraintSolver (cl_context ctx, cl_device_id device, cl_command_queue queue,bool usePgs)
|
||||
{
|
||||
m_usePgs = usePgs;
|
||||
m_gpuData = new b3GpuPgsJacobiSolverInternalData();
|
||||
@@ -165,7 +165,7 @@ b3GpuPgsJacobiSolver::b3GpuPgsJacobiSolver (cl_context ctx, cl_device_id device,
|
||||
|
||||
}
|
||||
|
||||
b3GpuPgsJacobiSolver::~b3GpuPgsJacobiSolver ()
|
||||
b3GpuPgsConstraintSolver::~b3GpuPgsConstraintSolver ()
|
||||
{
|
||||
clReleaseKernel(m_gpuData->m_solveJointConstraintRowsKernels);
|
||||
clReleaseKernel(m_gpuData->m_initSolverBodiesKernel);
|
||||
@@ -196,7 +196,7 @@ struct b3BatchConstraint
|
||||
static b3AlignedObjectArray<b3BatchConstraint> batchConstraints;
|
||||
static b3AlignedObjectArray<int> batches;
|
||||
|
||||
void b3GpuPgsJacobiSolver::recomputeBatches()
|
||||
void b3GpuPgsConstraintSolver::recomputeBatches()
|
||||
{
|
||||
batches.clear();
|
||||
}
|
||||
@@ -204,7 +204,7 @@ void b3GpuPgsJacobiSolver::recomputeBatches()
|
||||
|
||||
|
||||
|
||||
b3Scalar b3GpuPgsJacobiSolver::solveGroupCacheFriendlySetup(b3OpenCLArray<b3RigidBodyCL>* gpuBodies, b3OpenCLArray<b3InertiaCL>* gpuInertias, int numBodies, b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints,int numConstraints,const b3ContactSolverInfo& infoGlobal)
|
||||
b3Scalar b3GpuPgsConstraintSolver::solveGroupCacheFriendlySetup(b3OpenCLArray<b3RigidBodyCL>* gpuBodies, b3OpenCLArray<b3InertiaCL>* gpuInertias, int numBodies, b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints,int numConstraints,const b3ContactSolverInfo& infoGlobal)
|
||||
{
|
||||
B3_PROFILE("GPU solveGroupCacheFriendlySetup");
|
||||
batchConstraints.resize(numConstraints);
|
||||
@@ -655,7 +655,7 @@ void resolveSingleConstraintRowGeneric2( b3GpuSolverBody* body1, b3GpuSolverBod
|
||||
|
||||
|
||||
|
||||
void b3GpuPgsJacobiSolver::initSolverBody(int bodyIndex, b3GpuSolverBody* solverBody, b3RigidBodyCL* rb)
|
||||
void b3GpuPgsConstraintSolver::initSolverBody(int bodyIndex, b3GpuSolverBody* solverBody, b3RigidBodyCL* rb)
|
||||
{
|
||||
|
||||
solverBody->m_deltaLinearVelocity.setValue(0.f,0.f,0.f);
|
||||
@@ -674,12 +674,12 @@ void b3GpuPgsJacobiSolver::initSolverBody(int bodyIndex, b3GpuSolverBody* solver
|
||||
}
|
||||
|
||||
|
||||
void b3GpuPgsJacobiSolver::averageVelocities()
|
||||
void b3GpuPgsConstraintSolver::averageVelocities()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
b3Scalar b3GpuPgsJacobiSolver::solveGroupCacheFriendlyIterations(b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints1,int numConstraints,const b3ContactSolverInfo& infoGlobal)
|
||||
b3Scalar b3GpuPgsConstraintSolver::solveGroupCacheFriendlyIterations(b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints1,int numConstraints,const b3ContactSolverInfo& infoGlobal)
|
||||
{
|
||||
//only create the batches once.
|
||||
//@todo: incrementally update batches when constraints are added/activated and/or removed/deactivated
|
||||
@@ -856,7 +856,7 @@ static b3AlignedObjectArray<int> curUsed;
|
||||
|
||||
|
||||
|
||||
inline int b3GpuPgsJacobiSolver::sortConstraintByBatch3( b3BatchConstraint* cs, int numConstraints, int simdWidth , int staticIdx, int numBodies)
|
||||
inline int b3GpuPgsConstraintSolver::sortConstraintByBatch3( b3BatchConstraint* cs, int numConstraints, int simdWidth , int staticIdx, int numBodies)
|
||||
{
|
||||
int sz = sizeof(b3BatchConstraint);
|
||||
|
||||
@@ -991,7 +991,7 @@ inline int b3GpuPgsJacobiSolver::sortConstraintByBatch3( b3BatchConstraint* cs,
|
||||
|
||||
|
||||
/// b3PgsJacobiSolver Sequentially applies impulses
|
||||
b3Scalar b3GpuPgsJacobiSolver::solveGroup(b3OpenCLArray<b3RigidBodyCL>* gpuBodies, b3OpenCLArray<b3InertiaCL>* gpuInertias,
|
||||
b3Scalar b3GpuPgsConstraintSolver::solveGroup(b3OpenCLArray<b3RigidBodyCL>* gpuBodies, b3OpenCLArray<b3InertiaCL>* gpuInertias,
|
||||
int numBodies, b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints,int numConstraints, const b3ContactSolverInfo& infoGlobal)
|
||||
{
|
||||
|
||||
@@ -1007,7 +1007,7 @@ b3Scalar b3GpuPgsJacobiSolver::solveGroup(b3OpenCLArray<b3RigidBodyCL>* gpuBodie
|
||||
return 0.f;
|
||||
}
|
||||
|
||||
void b3GpuPgsJacobiSolver::solveJoints(int numBodies, b3OpenCLArray<b3RigidBodyCL>* gpuBodies, b3OpenCLArray<b3InertiaCL>* gpuInertias,
|
||||
void b3GpuPgsConstraintSolver::solveJoints(int numBodies, b3OpenCLArray<b3RigidBodyCL>* gpuBodies, b3OpenCLArray<b3InertiaCL>* gpuInertias,
|
||||
int numConstraints, b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints)
|
||||
{
|
||||
b3ContactSolverInfo infoGlobal;
|
||||
@@ -1029,7 +1029,7 @@ void b3GpuPgsJacobiSolver::solveJoints(int numBodies, b3OpenCLArray<b3RigidBodyC
|
||||
//b3AlignedObjectArray<b3RigidBodyCL> testBodies;
|
||||
|
||||
|
||||
b3Scalar b3GpuPgsJacobiSolver::solveGroupCacheFriendlyFinish(b3OpenCLArray<b3RigidBodyCL>* gpuBodies,b3OpenCLArray<b3InertiaCL>* gpuInertias,int numBodies,b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints,int numConstraints,const b3ContactSolverInfo& infoGlobal)
|
||||
b3Scalar b3GpuPgsConstraintSolver::solveGroupCacheFriendlyFinish(b3OpenCLArray<b3RigidBodyCL>* gpuBodies,b3OpenCLArray<b3InertiaCL>* gpuInertias,int numBodies,b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints,int numConstraints,const b3ContactSolverInfo& infoGlobal)
|
||||
{
|
||||
B3_PROFILE("solveGroupCacheFriendlyFinish");
|
||||
int numPoolConstraints = m_tmpSolverContactConstraintPool.size();
|
||||
@@ -13,8 +13,8 @@ subject to the following restrictions:
|
||||
*/
|
||||
//Originally written by Erwin Coumans
|
||||
|
||||
#ifndef B3_GPU_PGS_JACOBI_SOLVER_H
|
||||
#define B3_GPU_PGS_JACOBI_SOLVER_H
|
||||
#ifndef B3_GPU_PGS_CONSTRAINT_SOLVER_H
|
||||
#define B3_GPU_PGS_CONSTRAINT_SOLVER_H
|
||||
|
||||
struct b3Contact4;
|
||||
struct b3ContactPoint;
|
||||
@@ -33,7 +33,7 @@ struct b3InertiaCL;
|
||||
#include "Bullet3OpenCL/Initialize/b3OpenCLInclude.h"
|
||||
#include "b3GpuGenericConstraint.h"
|
||||
|
||||
class b3GpuPgsJacobiSolver
|
||||
class b3GpuPgsConstraintSolver
|
||||
{
|
||||
protected:
|
||||
int m_staticIdx;
|
||||
@@ -59,8 +59,8 @@ protected:
|
||||
void initSolverBody(int bodyIndex, b3GpuSolverBody* solverBody, b3RigidBodyCL* rb);
|
||||
|
||||
public:
|
||||
b3GpuPgsJacobiSolver (cl_context ctx, cl_device_id device, cl_command_queue queue,bool usePgs);
|
||||
virtual~b3GpuPgsJacobiSolver ();
|
||||
b3GpuPgsConstraintSolver (cl_context ctx, cl_device_id device, cl_command_queue queue,bool usePgs);
|
||||
virtual~b3GpuPgsConstraintSolver ();
|
||||
|
||||
virtual b3Scalar solveGroupCacheFriendlyIterations(b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints1,int numConstraints,const b3ContactSolverInfo& infoGlobal);
|
||||
virtual b3Scalar solveGroupCacheFriendlySetup(b3OpenCLArray<b3RigidBodyCL>* gpuBodies, b3OpenCLArray<b3InertiaCL>* gpuInertias, int numBodies,b3OpenCLArray<b3GpuGenericConstraint>* gpuConstraints,int numConstraints,const b3ContactSolverInfo& infoGlobal);
|
||||
@@ -75,4 +75,4 @@ public:
|
||||
void recomputeBatches();
|
||||
};
|
||||
|
||||
#endif //B3_GPU_PGS_JACOBI_SOLVER_H
|
||||
#endif //B3_GPU_PGS_CONSTRAINT_SOLVER_H
|
||||
@@ -28,7 +28,7 @@
|
||||
|
||||
#endif
|
||||
|
||||
#include "b3GpuBatchingPgsSolver.h"
|
||||
#include "b3GpuPgsContactSolver.h"
|
||||
#include "Bullet3OpenCL/ParallelPrimitives/b3RadixSort32CL.h"
|
||||
|
||||
#include "Bullet3OpenCL/ParallelPrimitives/b3LauncherCL.h"
|
||||
@@ -111,7 +111,7 @@ struct b3GpuBatchingPgsSolverInternalData
|
||||
|
||||
|
||||
|
||||
b3GpuBatchingPgsSolver::b3GpuBatchingPgsSolver(cl_context ctx,cl_device_id device, cl_command_queue q,int pairCapacity)
|
||||
b3GpuPgsContactSolver::b3GpuPgsContactSolver(cl_context ctx,cl_device_id device, cl_command_queue q,int pairCapacity)
|
||||
{
|
||||
m_debugOutput=0;
|
||||
m_data = new b3GpuBatchingPgsSolverInternalData;
|
||||
@@ -237,7 +237,7 @@ b3GpuBatchingPgsSolver::b3GpuBatchingPgsSolver(cl_context ctx,cl_device_id devic
|
||||
|
||||
}
|
||||
|
||||
b3GpuBatchingPgsSolver::~b3GpuBatchingPgsSolver()
|
||||
b3GpuPgsContactSolver::~b3GpuPgsContactSolver()
|
||||
{
|
||||
delete m_data->m_bodyBufferGPU;
|
||||
delete m_data->m_inertiaBufferGPU;
|
||||
@@ -296,7 +296,7 @@ struct b3ConstraintCfg
|
||||
|
||||
|
||||
|
||||
void b3GpuBatchingPgsSolver::solveContactConstraint( const b3OpenCLArray<b3RigidBodyCL>* bodyBuf, const b3OpenCLArray<b3InertiaCL>* shapeBuf,
|
||||
void b3GpuPgsContactSolver::solveContactConstraint( const b3OpenCLArray<b3RigidBodyCL>* bodyBuf, const b3OpenCLArray<b3InertiaCL>* shapeBuf,
|
||||
b3OpenCLArray<b3GpuConstraint4>* constraint, void* additionalData, int n ,int maxNumBatches,int numIterations)
|
||||
{
|
||||
|
||||
@@ -589,7 +589,7 @@ void SetSortDataCPU(b3Contact4* gContact, b3RigidBodyCL* gBodies, b3SortData* gS
|
||||
|
||||
|
||||
|
||||
void b3GpuBatchingPgsSolver::solveContacts(int numBodies, cl_mem bodyBuf, cl_mem inertiaBuf, int numContacts, cl_mem contactBuf, const b3Config& config, int static0Index)
|
||||
void b3GpuPgsContactSolver::solveContacts(int numBodies, cl_mem bodyBuf, cl_mem inertiaBuf, int numContacts, cl_mem contactBuf, const b3Config& config, int static0Index)
|
||||
{
|
||||
B3_PROFILE("solveContacts");
|
||||
m_data->m_bodyBufferGPU->setFromOpenCLBuffer(bodyBuf,numBodies);
|
||||
@@ -1120,7 +1120,7 @@ void b3GpuBatchingPgsSolver::solveContacts(int numBodies, cl_mem bodyBuf, cl_mem
|
||||
}
|
||||
|
||||
|
||||
void b3GpuBatchingPgsSolver::batchContacts( b3OpenCLArray<b3Contact4>* contacts, int nContacts, b3OpenCLArray<unsigned int>* n, b3OpenCLArray<unsigned int>* offsets, int staticIdx )
|
||||
void b3GpuPgsContactSolver::batchContacts( b3OpenCLArray<b3Contact4>* contacts, int nContacts, b3OpenCLArray<unsigned int>* n, b3OpenCLArray<unsigned int>* offsets, int staticIdx )
|
||||
{
|
||||
}
|
||||
|
||||
@@ -1139,7 +1139,7 @@ b3AlignedObjectArray<b3SortData> sortData;
|
||||
b3AlignedObjectArray<b3Contact4> old;
|
||||
|
||||
|
||||
inline int b3GpuBatchingPgsSolver::sortConstraintByBatch( b3Contact4* cs, int n, int simdWidth , int staticIdx, int numBodies)
|
||||
inline int b3GpuPgsContactSolver::sortConstraintByBatch( b3Contact4* cs, int n, int simdWidth , int staticIdx, int numBodies)
|
||||
{
|
||||
|
||||
B3_PROFILE("sortConstraintByBatch");
|
||||
@@ -1267,7 +1267,7 @@ inline int b3GpuBatchingPgsSolver::sortConstraintByBatch( b3Contact4* cs, int n,
|
||||
|
||||
b3AlignedObjectArray<int> bodyUsed2;
|
||||
|
||||
inline int b3GpuBatchingPgsSolver::sortConstraintByBatch2( b3Contact4* cs, int numConstraints, int simdWidth , int staticIdx, int numBodies)
|
||||
inline int b3GpuPgsContactSolver::sortConstraintByBatch2( b3Contact4* cs, int numConstraints, int simdWidth , int staticIdx, int numBodies)
|
||||
{
|
||||
|
||||
B3_PROFILE("sortConstraintByBatch2");
|
||||
@@ -1426,7 +1426,7 @@ b3AlignedObjectArray<int> bodyUsed;
|
||||
b3AlignedObjectArray<int> curUsed;
|
||||
|
||||
|
||||
inline int b3GpuBatchingPgsSolver::sortConstraintByBatch3( b3Contact4* cs, int numConstraints, int simdWidth , int staticIdx, int numBodies)
|
||||
inline int b3GpuPgsContactSolver::sortConstraintByBatch3( b3Contact4* cs, int numConstraints, int simdWidth , int staticIdx, int numBodies)
|
||||
{
|
||||
|
||||
B3_PROFILE("sortConstraintByBatch3");
|
||||
@@ -8,7 +8,7 @@
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3Contact4.h"
|
||||
#include "b3GpuConstraint4.h"
|
||||
|
||||
class b3GpuBatchingPgsSolver
|
||||
class b3GpuPgsContactSolver
|
||||
{
|
||||
protected:
|
||||
|
||||
@@ -29,8 +29,8 @@ protected:
|
||||
|
||||
public:
|
||||
|
||||
b3GpuBatchingPgsSolver(cl_context ctx,cl_device_id device, cl_command_queue q,int pairCapacity);
|
||||
virtual ~b3GpuBatchingPgsSolver();
|
||||
b3GpuPgsContactSolver(cl_context ctx,cl_device_id device, cl_command_queue q,int pairCapacity);
|
||||
virtual ~b3GpuPgsContactSolver();
|
||||
|
||||
void solveContacts(int numBodies, cl_mem bodyBuf, cl_mem inertiaBuf, int numContacts, cl_mem contactBuf, const struct b3Config& config, int static0Index);
|
||||
|
||||
@@ -33,6 +33,9 @@ subject to the following restrictions:
|
||||
#define B3_RIGIDBODY_INTEGRATE_PATH "src/Bullet3OpenCL/RigidBody/kernels/integrateKernel.cl"
|
||||
#define B3_RIGIDBODY_UPDATEAABB_PATH "src/Bullet3OpenCL/RigidBody/kernels/updateAabbsKernel.cl"
|
||||
|
||||
//choice of contact solver
|
||||
bool useJacobi = false;
|
||||
|
||||
//#define USE_CPU
|
||||
#ifdef USE_CPU
|
||||
bool useDbvt = true;
|
||||
@@ -52,15 +55,16 @@ subject to the following restrictions:
|
||||
|
||||
#endif
|
||||
|
||||
#define TEST_OTHER_GPU_SOLVER 1
|
||||
#ifdef TEST_OTHER_GPU_SOLVER
|
||||
#include "b3GpuJacobiSolver.h"
|
||||
#include "b3GpuJacobiContactSolver.h"
|
||||
#endif //TEST_OTHER_GPU_SOLVER
|
||||
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3RigidBodyCL.h"
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3Contact4.h"
|
||||
#include "Bullet3OpenCL/RigidBody/b3GpuPgsJacobiSolver.h"
|
||||
#include "Bullet3OpenCL/RigidBody/b3GpuPgsConstraintSolver.h"
|
||||
|
||||
#include "b3GpuBatchingPgsSolver.h"
|
||||
#include "b3GpuPgsContactSolver.h"
|
||||
#include "b3Solver.h"
|
||||
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3Config.h"
|
||||
@@ -80,17 +84,17 @@ b3GpuRigidBodyPipeline::b3GpuRigidBodyPipeline(cl_context ctx,cl_device_id devic
|
||||
m_data->m_queue = q;
|
||||
|
||||
m_data->m_solver = new b3PgsJacobiSolver(true);//new b3PgsJacobiSolver(true);
|
||||
m_data->m_gpuSolver = new b3GpuPgsJacobiSolver(ctx,device,q,true);//new b3PgsJacobiSolver(true);
|
||||
m_data->m_gpuSolver = new b3GpuPgsConstraintSolver(ctx,device,q,true);//new b3PgsJacobiSolver(true);
|
||||
|
||||
m_data->m_allAabbsGPU = new b3OpenCLArray<b3SapAabb>(ctx,q,config.m_maxConvexBodies);
|
||||
m_data->m_overlappingPairsGPU = new b3OpenCLArray<b3BroadphasePair>(ctx,q,config.m_maxBroadphasePairs);
|
||||
|
||||
m_data->m_gpuConstraints = new b3OpenCLArray<b3GpuGenericConstraint>(ctx,q);
|
||||
#ifdef TEST_OTHER_GPU_SOLVER
|
||||
m_data->m_solver3 = new b3GpuJacobiSolver(ctx,device,q,config.m_maxBroadphasePairs);
|
||||
m_data->m_solver3 = new b3GpuJacobiContactSolver(ctx,device,q,config.m_maxBroadphasePairs);
|
||||
#endif // TEST_OTHER_GPU_SOLVER
|
||||
|
||||
m_data->m_solver2 = new b3GpuBatchingPgsSolver(ctx,device,q,config.m_maxBroadphasePairs);
|
||||
m_data->m_solver2 = new b3GpuPgsContactSolver(ctx,device,q,config.m_maxBroadphasePairs);
|
||||
|
||||
m_data->m_raycaster = new b3GpuRaycast(ctx,device,q);
|
||||
|
||||
@@ -364,11 +368,13 @@ void b3GpuRigidBodyPipeline::stepSimulation(float deltaTime)
|
||||
{
|
||||
|
||||
#ifdef TEST_OTHER_GPU_SOLVER
|
||||
|
||||
if (useJacobi)
|
||||
{
|
||||
bool useGpu = true;
|
||||
if (useGpu)
|
||||
{
|
||||
|
||||
bool forceHost = false;
|
||||
if (forceHost)
|
||||
{
|
||||
@@ -385,7 +391,7 @@ void b3GpuRigidBodyPipeline::stepSimulation(float deltaTime)
|
||||
|
||||
{
|
||||
b3JacobiSolverInfo solverInfo;
|
||||
m_data->m_solver3->solveGroupHost(&hostBodies[0], &hostInertias[0], hostBodies.size(),&hostContacts[0],hostContacts.size(),0,0,solverInfo);
|
||||
m_data->m_solver3->solveGroupHost(&hostBodies[0], &hostInertias[0], hostBodies.size(),&hostContacts[0],hostContacts.size(),solverInfo);
|
||||
|
||||
|
||||
}
|
||||
@@ -394,9 +400,14 @@ void b3GpuRigidBodyPipeline::stepSimulation(float deltaTime)
|
||||
gpuBodies.copyFromHost(hostBodies);
|
||||
}
|
||||
} else
|
||||
|
||||
|
||||
{
|
||||
int static0Index = m_data->m_narrowphase->getStatic0Index();
|
||||
b3JacobiSolverInfo solverInfo;
|
||||
m_data->m_solver3->solveGroup(&gpuBodies, &gpuInertias, &gpuContacts,solverInfo);
|
||||
//m_data->m_solver3->solveContacts( >solveGroup(&gpuBodies, &gpuInertias, &gpuContacts,solverInfo);
|
||||
//m_data->m_solver3->solveContacts(m_data->m_narrowphase->getNumBodiesGpu(),&hostBodies[0],&hostInertias[0],numContacts,&hostContacts[0]);
|
||||
m_data->m_solver3->solveContacts(numBodies, gpuBodies.getBufferCL(),gpuInertias.getBufferCL(),numContacts, gpuContacts.getBufferCL(),m_data->m_config, static0Index);
|
||||
}
|
||||
} else
|
||||
{
|
||||
@@ -407,7 +418,7 @@ void b3GpuRigidBodyPipeline::stepSimulation(float deltaTime)
|
||||
b3AlignedObjectArray<b3Contact4> hostContacts;
|
||||
gpuContacts.copyToHost(hostContacts);
|
||||
{
|
||||
m_data->m_solver->solveContacts(m_data->m_narrowphase->getNumBodiesGpu(),&hostBodies[0],&hostInertias[0],numContacts,&hostContacts[0]);
|
||||
//m_data->m_solver->solveContacts(m_data->m_narrowphase->getNumBodiesGpu(),&hostBodies[0],&hostInertias[0],numContacts,&hostContacts[0]);
|
||||
}
|
||||
gpuBodies.copyFromHost(hostBodies);
|
||||
}
|
||||
|
||||
@@ -44,10 +44,10 @@ struct b3GpuRigidBodyPipelineInternalData
|
||||
|
||||
class b3PgsJacobiSolver* m_solver;
|
||||
|
||||
class b3GpuPgsJacobiSolver* m_gpuSolver;
|
||||
class b3GpuPgsConstraintSolver* m_gpuSolver;
|
||||
|
||||
class b3GpuBatchingPgsSolver* m_solver2;
|
||||
class b3GpuJacobiSolver* m_solver3;
|
||||
class b3GpuPgsContactSolver* m_solver2;
|
||||
class b3GpuJacobiContactSolver* m_solver3;
|
||||
class b3GpuRaycast* m_raycaster;
|
||||
|
||||
class b3GpuBroadphaseInterface* m_broadphaseSap;
|
||||
|
||||
@@ -17,7 +17,7 @@ subject to the following restrictions:
|
||||
#ifndef B3_GPU_SOLVER_BODY_H
|
||||
#define B3_GPU_SOLVER_BODY_H
|
||||
|
||||
class b3RigidBody;
|
||||
|
||||
#include "Bullet3Common/b3Vector3.h"
|
||||
#include "Bullet3Common/b3Matrix3x3.h"
|
||||
|
||||
|
||||
@@ -17,7 +17,7 @@ subject to the following restrictions:
|
||||
#ifndef B3_GPU_SOLVER_CONSTRAINT_H
|
||||
#define B3_GPU_SOLVER_CONSTRAINT_H
|
||||
|
||||
class b3RigidBody;
|
||||
|
||||
#include "Bullet3Common/b3Vector3.h"
|
||||
#include "Bullet3Common/b3Matrix3x3.h"
|
||||
//#include "b3JacobianEntry.h"
|
||||
|
||||
@@ -358,6 +358,8 @@ typedef struct
|
||||
float m_frictionCoeff;
|
||||
} Body;
|
||||
|
||||
|
||||
|
||||
typedef struct
|
||||
{
|
||||
Matrix3x3 m_invInertia;
|
||||
@@ -385,6 +387,8 @@ typedef struct
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
__kernel void CountBodiesKernel(__global struct b3Contact4Data* manifoldPtr, __global unsigned int* bodyCount, __global int2* contactConstraintOffsets, int numContactManifolds, int fixedBodyIndex)
|
||||
{
|
||||
int i = GET_GLOBAL_IDX;
|
||||
@@ -527,7 +531,7 @@ void solveContact(__global Constraint4* cs,
|
||||
float4 angular0, angular1, linear;
|
||||
float4 r0 = cs->m_worldPos[ic] - posA;
|
||||
float4 r1 = cs->m_worldPos[ic] - posB;
|
||||
setLinearAndAngular( -cs->m_linear, r0, r1, &linear, &angular0, &angular1 );
|
||||
setLinearAndAngular( cs->m_linear, r0, r1, &linear, &angular0, &angular1 );
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -506,7 +506,7 @@ static const char* solverUtilsCL= \
|
||||
" float4 angular0, angular1, linear;\n"
|
||||
" float4 r0 = cs->m_worldPos[ic] - posA;\n"
|
||||
" float4 r1 = cs->m_worldPos[ic] - posB;\n"
|
||||
" setLinearAndAngular( -cs->m_linear, r0, r1, &linear, &angular0, &angular1 );\n"
|
||||
" setLinearAndAngular( cs->m_linear, r0, r1, &linear, &angular0, &angular1 );\n"
|
||||
" \n"
|
||||
" float rambdaDt = calcRelVel( cs->m_linear, -cs->m_linear, angular0, angular1, \n"
|
||||
" *linVelA+*dLinVelA, *angVelA+*dAngVelA, *linVelB+*dLinVelB, *angVelB+*dAngVelB ) + cs->m_b[ic];\n"
|
||||
|
||||
Reference in New Issue
Block a user