work-in-progress Bullet 3.x GPU raytest
work-in-progress P2P constraint for b3GpuDynamicsWorld
This commit is contained in:
@@ -15,9 +15,9 @@ subject to the following restrictions:
|
||||
|
||||
|
||||
///create 125 (5x5x5) dynamic object
|
||||
#define ARRAY_SIZE_X 25
|
||||
#define ARRAY_SIZE_Y 20
|
||||
#define ARRAY_SIZE_Z 25
|
||||
#define ARRAY_SIZE_X 1//25
|
||||
#define ARRAY_SIZE_Y 20//20
|
||||
#define ARRAY_SIZE_Z 1//25
|
||||
|
||||
//maximum number of objects (and allow user to shoot additional boxes)
|
||||
#define MAX_PROXIES (ARRAY_SIZE_X*ARRAY_SIZE_Y*ARRAY_SIZE_Z + 1024)
|
||||
@@ -283,8 +283,9 @@ void BasicGpuDemo::initPhysics()
|
||||
//create a few dynamic rigidbodies
|
||||
// Re-using the same collision is better for memory usage and performance
|
||||
|
||||
btBoxShape* colShape = new btBoxShape(btVector3(SCALING*1,SCALING*1,SCALING*1));
|
||||
//btCollisionShape* colShape = new btSphereShape(btScalar(1.));
|
||||
//btBoxShape* colShape = new btBoxShape(btVector3(SCALING*1,SCALING*1,SCALING*1));
|
||||
|
||||
btCollisionShape* colShape = new btSphereShape(btScalar(SCALING*1.f));
|
||||
m_collisionShapes.push_back(colShape);
|
||||
|
||||
/// Create Dynamic Objects
|
||||
|
||||
@@ -76,7 +76,7 @@ GpuDemo::CreateFunc* allDemos[]=
|
||||
// GpuConvexScene::MyCreateFunc,
|
||||
|
||||
//ConcaveSphereScene::MyCreateFunc,
|
||||
//GpuRaytraceScene::MyCreateFunc,
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -108,7 +108,7 @@ GpuDemo::CreateFunc* allDemos[]=
|
||||
|
||||
PairBench::MyCreateFunc,
|
||||
|
||||
|
||||
GpuRaytraceScene::MyCreateFunc,
|
||||
//GpuRigidBodyDemo::MyCreateFunc,
|
||||
|
||||
//BroadphaseBenchmark::CreateFunc,
|
||||
|
||||
@@ -235,8 +235,8 @@ GpuRaytraceScene::GpuRaytraceScene()
|
||||
m_raytraceData = new GpuRaytraceInternalData;
|
||||
|
||||
m_raytraceData->m_texId = new GLuint;
|
||||
m_raytraceData->textureWidth = 256;//1024;
|
||||
m_raytraceData->textureHeight = 256;
|
||||
m_raytraceData->textureWidth = 1024;//1024;
|
||||
m_raytraceData->textureHeight = 1024;
|
||||
|
||||
//create new texture
|
||||
glGenTextures(1, m_raytraceData->m_texId);
|
||||
@@ -354,7 +354,7 @@ b3AlignedObjectArray<b3RayInfo> rays;
|
||||
void GpuRaytraceScene::renderScene()
|
||||
{
|
||||
|
||||
GpuBoxPlaneScene::renderScene();
|
||||
//GpuBoxPlaneScene::renderScene();
|
||||
|
||||
B3_PROFILE("raytrace");
|
||||
//raytrace into the texels
|
||||
@@ -458,7 +458,10 @@ void GpuRaytraceScene::renderScene()
|
||||
}
|
||||
|
||||
|
||||
m_raycaster->castRaysHost(rays, hits, this->m_data->m_np->getNumRigidBodies(), m_data->m_np->getBodiesCpu(), m_data->m_np->getNumCollidablesGpu(), m_data->m_np->getCollidablesCpu());
|
||||
//m_raycaster->castRaysHost(rays, hits, this->m_data->m_np->getNumRigidBodies(), m_data->m_np->getBodiesCpu(), m_data->m_np->getNumCollidablesGpu(), m_data->m_np->getCollidablesCpu());
|
||||
m_raycaster->castRays(rays, hits, this->m_data->m_np->getNumRigidBodies(), m_data->m_np->getBodiesCpu(), m_data->m_np->getNumCollidablesGpu(), m_data->m_np->getCollidablesCpu());
|
||||
|
||||
|
||||
|
||||
{
|
||||
B3_PROFILE("write texels");
|
||||
|
||||
@@ -8,13 +8,16 @@
|
||||
#include "BulletCollision/CollisionShapes/btCompoundShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btSphereShape.h"
|
||||
#include "BulletCollision/CollisionShapes/btStaticPlaneShape.h"
|
||||
#include "BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h"
|
||||
|
||||
#include "LinearMath/btQuickprof.h"
|
||||
#include "Bullet3OpenCL/BroadphaseCollision/b3GpuSapBroadphase.h"
|
||||
#include "Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.h"
|
||||
#include "Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.h"
|
||||
#include "Bullet3Dynamics/ConstraintSolver/b3Point2PointConstraint.h"
|
||||
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3RigidBodyCL.h"
|
||||
#include "Bullet3Common/b3Logging.h"
|
||||
|
||||
|
||||
#ifdef _WIN32
|
||||
@@ -217,7 +220,10 @@ int b3GpuDynamicsWorld::findOrRegisterCollisionShape(const btCollisionShape* col
|
||||
const float scaling[4]={1,1,1,1};
|
||||
//bool noHeightField=true;
|
||||
|
||||
int gpuShapeIndex = m_np->registerConvexHullShape(&tmpVertices[0].getX(), strideInBytes, numVertices, scaling);
|
||||
//int gpuShapeIndex = m_np->registerConvexHullShape(&tmpVertices[0].getX(), strideInBytes, numVertices, scaling);
|
||||
const float* verts = numVertices? &tmpVertices[0].getX() : 0;
|
||||
|
||||
int gpuShapeIndex = m_np->registerConvexHullShape(verts,strideInBytes, numVertices, scaling);
|
||||
m_uniqueShapeMapping.push_back(gpuShapeIndex);
|
||||
} else
|
||||
{
|
||||
@@ -385,7 +391,9 @@ void b3GpuDynamicsWorld::addRigidBody(btRigidBody* body)
|
||||
btVector3 pos = body->getWorldTransform().getOrigin();
|
||||
btQuaternion orn = body->getWorldTransform().getRotation();
|
||||
|
||||
m_rigidBodyPipeline->registerPhysicsInstance(mass,&pos.getX(),&orn.getX(),gpuShapeIndex,m_collisionObjects.size(),false);
|
||||
int bodyIndex = m_rigidBodyPipeline->registerPhysicsInstance(mass,&pos.getX(),&orn.getX(),gpuShapeIndex,m_collisionObjects.size(),false);
|
||||
|
||||
body->setUserIndex(bodyIndex);
|
||||
|
||||
m_collisionObjects.push_back(body);
|
||||
//btDynamicsWorld::addCollisionObject(
|
||||
@@ -397,6 +405,8 @@ void b3GpuDynamicsWorld::removeRigidBody(btRigidBody* colObj)
|
||||
m_cpuGpuSync = true;
|
||||
btDynamicsWorld::removeCollisionObject(colObj);
|
||||
|
||||
int bodyIndex = colObj->getUserIndex();
|
||||
|
||||
if (getNumCollisionObjects()==0)
|
||||
{
|
||||
m_uniqueShapes.resize(0);
|
||||
@@ -433,6 +443,32 @@ void b3GpuDynamicsWorld::removeCollisionObject(btCollisionObject* colObj)
|
||||
|
||||
void b3GpuDynamicsWorld::rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const
|
||||
{
|
||||
b3AlignedObjectArray<b3RayInfo> rays;
|
||||
b3RayInfo ray;
|
||||
ray.m_from = (const b3Vector3&)rayFromWorld;
|
||||
ray.m_to = (const b3Vector3&)rayToWorld;
|
||||
rays.push_back(ray);
|
||||
|
||||
b3AlignedObjectArray<b3RayHit> hitResults;
|
||||
b3RayHit hit;
|
||||
hit.m_hitFraction = 1.f;
|
||||
|
||||
hitResults.push_back(hit);
|
||||
|
||||
m_rigidBodyPipeline->castRays(rays,hitResults);
|
||||
b3Printf("hit = %f\n", hitResults[0].m_hitFraction);
|
||||
if (hitResults[0].m_hitFraction<1.f)
|
||||
{
|
||||
b3Assert(hitResults[0].m_hitResult0 >=0);
|
||||
b3Assert(hitResults[0].m_hitResult0 < m_collisionObjects.size());
|
||||
b3Vector3 hitNormalLocal = hitResults[0].m_hitNormal;
|
||||
btCollisionObject* colObj = m_collisionObjects[hitResults[0].m_hitResult0];
|
||||
LocalRayResult rayResult(colObj,0,(btVector3&)hitNormalLocal,hitResults[0].m_hitFraction);
|
||||
rayResult.m_hitFraction = hitResults[0].m_hitFraction;
|
||||
|
||||
resultCallback.addSingleResult(rayResult,true);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -462,3 +498,41 @@ void b3GpuDynamicsWorld::synchronizeSingleMotionState(btRigidBody* body)
|
||||
}
|
||||
}
|
||||
|
||||
void b3GpuDynamicsWorld::addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies)
|
||||
{
|
||||
m_constraints.push_back(constraint);
|
||||
|
||||
switch (constraint->getConstraintType())
|
||||
{
|
||||
case POINT2POINT_CONSTRAINT_TYPE:
|
||||
{
|
||||
b3Assert(constraint->getUserConstraintId()==-1);
|
||||
btPoint2PointConstraint* p = (btPoint2PointConstraint*) constraint;
|
||||
|
||||
int rbA = p->getRigidBodyA().getUserIndex();
|
||||
int rbB = p->getRigidBodyB().getUserIndex();
|
||||
|
||||
b3Point2PointConstraint* p2p = new b3Point2PointConstraint(rbA,rbB, (const b3Vector3&)p->getPivotInA(),(const b3Vector3&)p->getPivotInB());
|
||||
constraint->setUserConstraintPtr(p2p);
|
||||
m_rigidBodyPipeline->addConstraint(p2p);
|
||||
break;
|
||||
}
|
||||
default:
|
||||
b3Warning("Warning: b3GpuDynamicsWorld::addConstraint with unsupported constraint type\n");
|
||||
};
|
||||
|
||||
|
||||
}
|
||||
|
||||
void b3GpuDynamicsWorld::removeConstraint(btTypedConstraint* constraint)
|
||||
{
|
||||
b3TypedConstraint* c = (b3TypedConstraint*) constraint->getUserConstraintPtr();
|
||||
|
||||
if (c)
|
||||
{
|
||||
this->m_rigidBodyPipeline->removeConstraint(c);
|
||||
delete c;
|
||||
}
|
||||
m_constraints.remove(constraint);
|
||||
}
|
||||
|
||||
|
||||
@@ -8,6 +8,7 @@ class btCollisionObject;
|
||||
struct b3GpuInternalData;//use this struct to avoid 'leaking' all OpenCL headers into clients code base
|
||||
class CLPhysicsDemo;
|
||||
class btActionInterface;
|
||||
class btTypedConstraint;
|
||||
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
#include "BulletDynamics/Dynamics/btDynamicsWorld.h"
|
||||
@@ -18,7 +19,7 @@ class b3GpuDynamicsWorld : public btDynamicsWorld
|
||||
|
||||
btAlignedObjectArray<const class btCollisionShape*> m_uniqueShapes;
|
||||
btAlignedObjectArray<int> m_uniqueShapeMapping;
|
||||
|
||||
btAlignedObjectArray<btTypedConstraint*> m_constraints;
|
||||
|
||||
class b3GpuRigidBodyPipeline* m_rigidBodyPipeline;
|
||||
class b3GpuNarrowPhase* m_np;
|
||||
@@ -52,6 +53,10 @@ public:
|
||||
|
||||
virtual void removeRigidBody(btRigidBody* body);
|
||||
|
||||
virtual void addConstraint(btTypedConstraint* constraint, bool disableCollisionsBetweenLinkedBodies=false);
|
||||
|
||||
virtual void removeConstraint(btTypedConstraint* constraint);
|
||||
|
||||
void rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const;
|
||||
|
||||
btAlignedObjectArray<class btCollisionObject*>& getCollisionObjectArray();
|
||||
|
||||
@@ -75,7 +75,7 @@ public:
|
||||
|
||||
b3Point2PointConstraint(int rbA,int rbB, const b3Vector3& pivotInA,const b3Vector3& pivotInB);
|
||||
|
||||
b3Point2PointConstraint(int rbA,const b3Vector3& pivotInA);
|
||||
//b3Point2PointConstraint(int rbA,const b3Vector3& pivotInA);
|
||||
|
||||
|
||||
virtual void buildJacobian();
|
||||
|
||||
@@ -192,9 +192,9 @@ B3_FORCE_INLINE void b3TransformAabb(const b3Vector3& halfExtents, b3Scalar marg
|
||||
|
||||
B3_FORCE_INLINE void b3TransformAabb(const b3Vector3& localAabbMin,const b3Vector3& localAabbMax, b3Scalar margin,const b3Transform& trans,b3Vector3& aabbMinOut,b3Vector3& aabbMaxOut)
|
||||
{
|
||||
b3Assert(localAabbMin.getX() <= localAabbMax.getX());
|
||||
b3Assert(localAabbMin.getY() <= localAabbMax.getY());
|
||||
b3Assert(localAabbMin.getZ() <= localAabbMax.getZ());
|
||||
//b3Assert(localAabbMin.getX() <= localAabbMax.getX());
|
||||
//b3Assert(localAabbMin.getY() <= localAabbMax.getY());
|
||||
//b3Assert(localAabbMin.getZ() <= localAabbMax.getZ());
|
||||
b3Vector3 localHalfExtents = b3Scalar(0.5)*(localAabbMax-localAabbMin);
|
||||
localHalfExtents+=b3Vector3(margin,margin,margin);
|
||||
|
||||
|
||||
@@ -325,14 +325,18 @@ class b3LauncherCL
|
||||
{
|
||||
int sz=sizeof(T);
|
||||
b3Assert(sz<=B3_CL_MAX_ARG_SIZE);
|
||||
b3KernelArgData kernelArg;
|
||||
kernelArg.m_argIndex = m_idx;
|
||||
kernelArg.m_isBuffer = 0;
|
||||
T* destArg = (T*)kernelArg.m_argData;
|
||||
*destArg = consts;
|
||||
kernelArg.m_argSizeInBytes = sizeof(T);
|
||||
m_kernelArguments.push_back(kernelArg);
|
||||
m_serializationSizeInBytes+=sizeof(b3KernelArgData);
|
||||
|
||||
if (m_enableSerialization)
|
||||
{
|
||||
b3KernelArgData kernelArg;
|
||||
kernelArg.m_argIndex = m_idx;
|
||||
kernelArg.m_isBuffer = 0;
|
||||
T* destArg = (T*)kernelArg.m_argData;
|
||||
*destArg = consts;
|
||||
kernelArg.m_argSizeInBytes = sizeof(T);
|
||||
m_kernelArguments.push_back(kernelArg);
|
||||
m_serializationSizeInBytes+=sizeof(b3KernelArgData);
|
||||
}
|
||||
|
||||
cl_int status = clSetKernelArg( m_kernel, m_idx++, sz, &consts );
|
||||
b3Assert( status == CL_SUCCESS );
|
||||
|
||||
@@ -49,23 +49,25 @@ b3GpuRaycast::~b3GpuRaycast()
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
bool sphere_intersect(const b3Vector3& spherePos, b3Scalar radius, const b3Vector3& rayFrom, const b3Vector3& rayTo)
|
||||
bool sphere_intersect(const b3Vector3& spherePos, b3Scalar radius, const b3Vector3& rayFrom, const b3Vector3& rayTo, float& hitFraction)
|
||||
{
|
||||
// rs = ray.org - sphere.center
|
||||
const b3Vector3& rs = rayFrom - spherePos;
|
||||
b3Vector3 rayDir = rayTo-rayFrom;//rayFrom-rayTo;
|
||||
rayDir.normalize();
|
||||
|
||||
b3Vector3 rs = rayFrom - spherePos;
|
||||
b3Vector3 rayDir = rayTo-rayFrom;
|
||||
|
||||
float A = b3Dot(rayDir,rayDir);
|
||||
float B = b3Dot(rs, rayDir);
|
||||
float C = b3Dot(rs, rs) - (radius * radius);
|
||||
float D = B * B - C;
|
||||
|
||||
float D = B * B - A*C;
|
||||
|
||||
if (D > 0.0)
|
||||
{
|
||||
float t = -B - sqrt(D);
|
||||
if ( (t > 0.0))// && (t < isect.t) )
|
||||
float t = (-B - sqrt(D))/A;
|
||||
|
||||
if ( (t >= 0.0f) && (t < hitFraction) )
|
||||
{
|
||||
return true;//isect.t = t;
|
||||
hitFraction = t;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
@@ -79,16 +81,15 @@ void b3GpuRaycast::castRaysHost(const b3AlignedObjectArray<b3RayInfo>& rays, b3A
|
||||
// return castRays(rays,hitResults,numBodies,bodies,numCollidables,collidables);
|
||||
|
||||
B3_PROFILE("castRaysHost");
|
||||
|
||||
for (int r=0;r<rays.size();r++)
|
||||
{
|
||||
b3Vector3 rayFrom = rays[r].m_from;
|
||||
b3Vector3 rayTo = rays[r].m_to;
|
||||
float hitFraction = hitResults[r].m_hitFraction;
|
||||
|
||||
//if there is a hit, color the pixels
|
||||
bool hits = false;
|
||||
int sphereHit = -1;
|
||||
|
||||
for (int b=0;b<numBodies && !hits;b++)
|
||||
for (int b=0;b<numBodies;b++)
|
||||
{
|
||||
|
||||
const b3Vector3& pos = bodies[b].m_pos;
|
||||
@@ -96,11 +97,19 @@ void b3GpuRaycast::castRaysHost(const b3AlignedObjectArray<b3RayInfo>& rays, b3A
|
||||
|
||||
b3Scalar radius = 1;
|
||||
|
||||
if (sphere_intersect(pos, radius, rayFrom, rayTo))
|
||||
hits = true;
|
||||
if (sphere_intersect(pos, radius, rayFrom, rayTo,hitFraction))
|
||||
{
|
||||
sphereHit = b;
|
||||
}
|
||||
}
|
||||
if (sphereHit>=0)
|
||||
{
|
||||
|
||||
hitResults[r].m_hitFraction = hitFraction;
|
||||
hitResults[r].m_hitPoint.setInterpolate3(rays[r].m_from, rays[r].m_to,hitFraction);
|
||||
hitResults[r].m_hitNormal = (hitResults[r].m_hitPoint-bodies[sphereHit].m_pos).normalize();
|
||||
hitResults[r].m_hitResult0 = sphereHit;
|
||||
}
|
||||
if (hits)
|
||||
hitResults[r].m_hitFraction = 0.f;
|
||||
|
||||
}
|
||||
}
|
||||
@@ -115,6 +124,7 @@ void b3GpuRaycast::castRays(const b3AlignedObjectArray<b3RayInfo>& rays, b3Align
|
||||
|
||||
b3OpenCLArray<b3RayHit> gpuHitResults(m_data->m_context,m_data->m_q);
|
||||
gpuHitResults.resize(hitResults.size());
|
||||
gpuHitResults.copyFromHost(hitResults);
|
||||
|
||||
b3OpenCLArray<b3RigidBodyCL> gpuBodies(m_data->m_context,m_data->m_q);
|
||||
gpuBodies.resize(numBodies);
|
||||
|
||||
@@ -5,22 +5,9 @@
|
||||
#include "Bullet3OpenCL/Initialize/b3OpenCLInclude.h"
|
||||
|
||||
#include "Bullet3Common/b3AlignedObjectArray.h"
|
||||
#include "b3RaycastInfo.h"
|
||||
|
||||
struct b3RayInfo
|
||||
{
|
||||
b3Vector3 m_from;
|
||||
b3Vector3 m_to;
|
||||
};
|
||||
|
||||
struct b3RayHit
|
||||
{
|
||||
b3Scalar m_hitFraction;
|
||||
int m_hitResult0;
|
||||
int m_hitResult1;
|
||||
int m_hitResult2;
|
||||
b3Vector3 m_hitPoint;
|
||||
b3Vector3 m_hitNormal;
|
||||
};
|
||||
|
||||
class b3GpuRaycast
|
||||
{
|
||||
|
||||
24
src/Bullet3OpenCL/Raycast/b3RaycastInfo.h
Normal file
24
src/Bullet3OpenCL/Raycast/b3RaycastInfo.h
Normal file
@@ -0,0 +1,24 @@
|
||||
|
||||
#ifndef B3_RAYCAST_INFO_H
|
||||
#define B3_RAYCAST_INFO_H
|
||||
|
||||
#include "Bullet3Common/b3Vector3.h"
|
||||
|
||||
B3_ATTRIBUTE_ALIGNED16(struct) b3RayInfo
|
||||
{
|
||||
b3Vector3 m_from;
|
||||
b3Vector3 m_to;
|
||||
};
|
||||
|
||||
B3_ATTRIBUTE_ALIGNED16(struct) b3RayHit
|
||||
{
|
||||
b3Scalar m_hitFraction;
|
||||
int m_hitResult0;
|
||||
int m_hitResult1;
|
||||
int m_hitResult2;
|
||||
b3Vector3 m_hitPoint;
|
||||
b3Vector3 m_hitNormal;
|
||||
};
|
||||
|
||||
#endif //B3_RAYCAST_INFO_H
|
||||
|
||||
@@ -33,7 +33,7 @@ bool dumpContactStats = false;
|
||||
|
||||
#include "Bullet3Common/b3Quickprof.h"
|
||||
#include "b3Config.h"
|
||||
|
||||
#include "Bullet3OpenCL/Raycast/b3GpuRaycast.h"
|
||||
|
||||
|
||||
|
||||
@@ -55,6 +55,8 @@ b3GpuRigidBodyPipeline::b3GpuRigidBodyPipeline(cl_context ctx,cl_device_id devic
|
||||
|
||||
m_data->m_solver2 = new b3GpuBatchingPgsSolver(ctx,device,q,config.m_maxBroadphasePairs);
|
||||
|
||||
m_data->m_raycaster = new b3GpuRaycast(ctx,device,q);
|
||||
|
||||
|
||||
m_data->m_broadphaseDbvt = broadphaseDbvt;
|
||||
m_data->m_broadphaseSap = broadphaseSap;
|
||||
@@ -85,6 +87,7 @@ b3GpuRigidBodyPipeline::~b3GpuRigidBodyPipeline()
|
||||
{
|
||||
clReleaseKernel(m_data->m_integrateTransformsKernel);
|
||||
|
||||
delete m_data->m_raycaster;
|
||||
delete m_data->m_solver;
|
||||
delete m_data->m_allAabbsGPU;
|
||||
delete m_data->m_overlappingPairsGPU;
|
||||
@@ -110,6 +113,14 @@ void b3GpuRigidBodyPipeline::addConstraint(b3TypedConstraint* constraint)
|
||||
{
|
||||
m_data->m_joints.push_back(constraint);
|
||||
}
|
||||
|
||||
void b3GpuRigidBodyPipeline::removeConstraint(b3TypedConstraint* constraint)
|
||||
{
|
||||
m_data->m_joints.remove(constraint);
|
||||
}
|
||||
|
||||
|
||||
|
||||
void b3GpuRigidBodyPipeline::stepSimulation(float deltaTime)
|
||||
{
|
||||
|
||||
@@ -220,7 +231,7 @@ void b3GpuRigidBodyPipeline::stepSimulation(float deltaTime)
|
||||
{
|
||||
b3TypedConstraint** joints = numJoints? &m_data->m_joints[0] : 0;
|
||||
b3Contact4* contacts = numContacts? &hostContacts[0]: 0;
|
||||
// m_data->m_solver->solveContacts(m_data->m_narrowphase->getNumBodiesGpu(),&hostBodies[0],&hostInertias[0],numContacts,contacts,numJoints, joints);
|
||||
//m_data->m_solver->solveContacts(m_data->m_narrowphase->getNumBodiesGpu(),&hostBodies[0],&hostInertias[0],numContacts,contacts,numJoints, joints);
|
||||
m_data->m_solver->solveContacts(m_data->m_narrowphase->getNumRigidBodies(),&hostBodies[0],&hostInertias[0],0,0,numJoints, joints);
|
||||
|
||||
}
|
||||
@@ -438,3 +449,9 @@ int b3GpuRigidBodyPipeline::registerPhysicsInstance(float mass, const float* po
|
||||
|
||||
return bodyIndex;
|
||||
}
|
||||
|
||||
void b3GpuRigidBodyPipeline::castRays(const b3AlignedObjectArray<b3RayInfo>& rays, b3AlignedObjectArray<b3RayHit>& hitResults)
|
||||
{
|
||||
this->m_data->m_raycaster->castRaysHost(rays,hitResults,getNumBodies(),this->m_data->m_narrowphase->getBodiesCpu(),m_data->m_narrowphase->getNumCollidablesGpu(), m_data->m_narrowphase->getCollidablesCpu());
|
||||
}
|
||||
|
||||
|
||||
@@ -4,6 +4,9 @@
|
||||
#include "Bullet3OpenCL/Initialize/b3OpenCLInclude.h"
|
||||
#include "b3Config.h"
|
||||
|
||||
#include "Bullet3Common/b3AlignedObjectArray.h"
|
||||
#include "Bullet3OpenCL/Raycast/b3RaycastInfo.h"
|
||||
|
||||
class b3GpuRigidBodyPipeline
|
||||
{
|
||||
protected:
|
||||
@@ -38,6 +41,9 @@ public:
|
||||
void reset();
|
||||
|
||||
void addConstraint(class b3TypedConstraint* constraint);
|
||||
void removeConstraint(b3TypedConstraint* constraint);
|
||||
|
||||
void castRays(const b3AlignedObjectArray<b3RayInfo>& rays, b3AlignedObjectArray<b3RayHit>& hitResults);
|
||||
|
||||
cl_mem getBodyBuffer();
|
||||
|
||||
|
||||
@@ -28,6 +28,7 @@ struct b3GpuRigidBodyPipelineInternalData
|
||||
class b3PgsJacobiSolver* m_solver;
|
||||
class b3GpuBatchingPgsSolver* m_solver2;
|
||||
class b3GpuJacobiSolver* m_solver3;
|
||||
class b3GpuRaycast* m_raycaster;
|
||||
|
||||
class b3GpuSapBroadphase* m_broadphaseSap;
|
||||
|
||||
|
||||
Reference in New Issue
Block a user