b3GpuDynamicsWorld improvements:
apply forces copy linear/angular velocity every frame at the CPU side, initial velocity works now hook up setGravity Note: the 'stepSimulation' for GPU only simulates a single simulation frame.
This commit is contained in:
@@ -427,7 +427,7 @@ void GpuRaytraceScene::renderScene()
|
||||
}
|
||||
|
||||
|
||||
m_raycaster->castRaysHost(rays, hits, this->m_data->m_np->getNumBodiesGpu(), 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());
|
||||
|
||||
{
|
||||
B3_PROFILE("write texels");
|
||||
|
||||
@@ -114,6 +114,11 @@ end
|
||||
"BulletDynamics", "BulletCollision", "LinearMath"},
|
||||
"NVIDIA")
|
||||
|
||||
createGpuDemos(localgpudemos,{"../src","../Demos/OpenGL"},{"OpenGLSupport",
|
||||
"Bullet3Dynamics","Bullet3Collision","Bullet3Geometry","Bullet3Common",
|
||||
"BulletDynamics", "BulletCollision", "LinearMath"},
|
||||
"clew")
|
||||
|
||||
createGpuDemos(localgpudemos,{"../src","../Demos/OpenGL"},{"OpenGLSupport",
|
||||
"Bullet3Dynamics","Bullet3Collision","Bullet3Geometry","Bullet3Common",
|
||||
"BulletDynamics", "BulletCollision", "LinearMath"},
|
||||
|
||||
@@ -14,7 +14,7 @@
|
||||
#include "Bullet3OpenCL/RigidBody/b3GpuNarrowPhase.h"
|
||||
#include "Bullet3OpenCL/RigidBody/b3GpuRigidBodyPipeline.h"
|
||||
|
||||
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3RigidBodyCL.h"
|
||||
|
||||
|
||||
#ifdef _WIN32
|
||||
@@ -22,6 +22,10 @@
|
||||
#endif
|
||||
|
||||
|
||||
//#if (BT_BULLET_VERSION >= 282)
|
||||
//#define BT_USE_BODY_UPDATE_REVISION
|
||||
//#endif
|
||||
|
||||
|
||||
b3GpuDynamicsWorld::b3GpuDynamicsWorld(class b3GpuSapBroadphase* bp,class b3GpuNarrowPhase* np, class b3GpuRigidBodyPipeline* rigidBodyPipeline)
|
||||
:btDynamicsWorld(0,0,0),
|
||||
@@ -29,7 +33,8 @@ b3GpuDynamicsWorld::b3GpuDynamicsWorld(class b3GpuSapBroadphase* bp,class b3GpuN
|
||||
m_cpuGpuSync(true),
|
||||
m_bp(bp),
|
||||
m_np(np),
|
||||
m_rigidBodyPipeline(rigidBodyPipeline)
|
||||
m_rigidBodyPipeline(rigidBodyPipeline),
|
||||
m_localTime(0.f)
|
||||
{
|
||||
|
||||
}
|
||||
@@ -42,8 +47,12 @@ b3GpuDynamicsWorld::~b3GpuDynamicsWorld()
|
||||
|
||||
|
||||
|
||||
int b3GpuDynamicsWorld::stepSimulation( btScalar timeStep, int maxSubSteps, btScalar fixedTimeStep)
|
||||
int b3GpuDynamicsWorld::stepSimulation( btScalar timeStepUnused, int maxSubStepsUnused, btScalar fixedTimeStep)
|
||||
{
|
||||
///Don't use more than 1 simulation step, it destroys the performance having to copy the data between CPU and GPU multiple times per frame
|
||||
///Please use the CPU version in btDiscreteDynamicsWorld if you don't like this
|
||||
|
||||
|
||||
#ifndef BT_NO_PROFILE
|
||||
CProfileManager::Reset();
|
||||
#endif //BT_NO_PROFILE
|
||||
@@ -51,7 +60,43 @@ int b3GpuDynamicsWorld::stepSimulation( btScalar timeStep, int maxSubSteps, btS
|
||||
|
||||
BT_PROFILE("stepSimulation");
|
||||
|
||||
//convert all shapes now, and if any change, reset all (todo)
|
||||
|
||||
// detect any change (very simple)
|
||||
{
|
||||
BT_PROFILE("body update revision detection (CPU)");
|
||||
#ifdef BT_USE_BODY_UPDATE_REVISION
|
||||
b3Assert(m_bodyUpdateRevisions.size() == m_collisionObjects.size());
|
||||
b3Assert(m_np->getNumRigidBodies() == m_bodyUpdateRevisions.size());
|
||||
#endif //BT_USE_BODY_UPDATE_REVISION
|
||||
|
||||
b3RigidBodyCL* bodiesCL = m_np->getBodiesCpu();
|
||||
for (int i=0;i<this->m_collisionObjects.size();i++)
|
||||
{
|
||||
#ifdef BT_USE_BODY_UPDATE_REVISION
|
||||
if (m_bodyUpdateRevisions[i] != m_collisionObjects[i]->getUpdateRevisionInternal())
|
||||
#endif//BT_USE_BODY_UPDATE_REVISION
|
||||
{
|
||||
m_cpuGpuSync = true;
|
||||
|
||||
#ifdef BT_USE_BODY_UPDATE_REVISION
|
||||
m_bodyUpdateRevisions[i] = m_collisionObjects[i]->getUpdateRevisionInternal();
|
||||
#endif
|
||||
|
||||
bodiesCL[i].m_pos = (const b3Vector3&)m_collisionObjects[i]->getWorldTransform().getOrigin();
|
||||
bodiesCL[i].m_quat = (const b3Quaternion&)m_collisionObjects[i]->getWorldTransform().getRotation();
|
||||
btRigidBody* body = btRigidBody::upcast(m_collisionObjects[i]);
|
||||
if (body)
|
||||
{
|
||||
body->integrateVelocities(fixedTimeStep);
|
||||
bodiesCL[i].m_linVel = (const b3Vector3&)body->getLinearVelocity();
|
||||
bodiesCL[i].m_angVel = (const b3Vector3&)body->getAngularVelocity();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
if (m_cpuGpuSync)
|
||||
@@ -62,55 +107,94 @@ int b3GpuDynamicsWorld::stepSimulation( btScalar timeStep, int maxSubSteps, btS
|
||||
m_rigidBodyPipeline->writeAllInstancesToGpu();
|
||||
}
|
||||
|
||||
|
||||
|
||||
//internalSingleStepSimulation(fixedTimeStep);
|
||||
// dispatch preTick callback
|
||||
if(0 != m_internalPreTickCallback) {
|
||||
if(0 != m_internalPreTickCallback)
|
||||
{
|
||||
BT_PROFILE("internalPreTickCallback");
|
||||
(*m_internalPreTickCallback)(this, fixedTimeStep);
|
||||
}
|
||||
|
||||
m_rigidBodyPipeline->stepSimulation(fixedTimeStep);
|
||||
{
|
||||
BT_PROFILE("m_rigidBodyPipeline->stepSimulation");
|
||||
m_rigidBodyPipeline->stepSimulation(fixedTimeStep);
|
||||
}
|
||||
|
||||
{
|
||||
BT_PROFILE("readbackBodiesToCpu");
|
||||
//now copy info back to rigid bodies....
|
||||
m_np->readbackAllBodiesToCpu();
|
||||
}
|
||||
|
||||
{
|
||||
BT_PROFILE("scatter transforms into rigidbody (CPU)");
|
||||
|
||||
const b3RigidBodyCL* bodiesCL = m_np->getBodiesCpu();
|
||||
|
||||
for (int i=0;i<this->m_collisionObjects.size();i++)
|
||||
{
|
||||
BT_PROFILE("readbackBodiesToCpu");
|
||||
//now copy info back to rigid bodies....
|
||||
m_np->readbackAllBodiesToCpu();
|
||||
btVector3 pos;
|
||||
btQuaternion orn;
|
||||
m_np->getObjectTransformFromCpu(&pos[0],&orn[0],i);
|
||||
btTransform newTrans;
|
||||
newTrans.setOrigin(pos);
|
||||
newTrans.setRotation(orn);
|
||||
|
||||
btCollisionObject* colObj = this->m_collisionObjects[i];
|
||||
colObj->setWorldTransform(newTrans);
|
||||
|
||||
btRigidBody* body = btRigidBody::upcast(m_collisionObjects[i]);
|
||||
if (body)
|
||||
{
|
||||
body->setLinearVelocity((btVector3&)bodiesCL[i].m_linVel);
|
||||
body->setAngularVelocity((btVector3&)bodiesCL[i].m_angVel);
|
||||
}
|
||||
|
||||
|
||||
#ifdef BT_USE_BODY_UPDATE_REVISION
|
||||
//ignore this revision update
|
||||
m_bodyUpdateRevisions[i] = m_collisionObjects[i]->getUpdateRevisionInternal();
|
||||
#endif //BT_USE_BODY_UPDATE_REVISION
|
||||
|
||||
}
|
||||
|
||||
{
|
||||
BT_PROFILE("scatter transforms into rigidbody (CPU)");
|
||||
for (int i=0;i<this->m_collisionObjects.size();i++)
|
||||
{
|
||||
btVector3 pos;
|
||||
btQuaternion orn;
|
||||
m_np->getObjectTransformFromCpu(&pos[0],&orn[0],i);
|
||||
btTransform newTrans;
|
||||
newTrans.setOrigin(pos);
|
||||
newTrans.setRotation(orn);
|
||||
|
||||
btCollisionObject* colObj = this->m_collisionObjects[i];
|
||||
colObj->setWorldTransform(newTrans);
|
||||
|
||||
// synchronize motionstate
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
this->synchronizeSingleMotionState(body);
|
||||
}
|
||||
BT_PROFILE("synchronizeMotionStates");
|
||||
synchronizeMotionStates();
|
||||
}
|
||||
}
|
||||
|
||||
clearForces();
|
||||
|
||||
|
||||
#ifndef B3_NO_PROFILE
|
||||
CProfileManager::Increment_Frame_Counter();
|
||||
#endif //B3_NO_PROFILE
|
||||
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
void b3GpuDynamicsWorld::clearForces()
|
||||
{
|
||||
///@todo: iterate over awake simulation islands!
|
||||
for ( int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btRigidBody* body = btRigidBody::upcast(m_collisionObjects[i]);
|
||||
//need to check if next line is ok
|
||||
//it might break backward compatibility (people applying forces on sleeping objects get never cleared and accumulate on wake-up
|
||||
if (body)
|
||||
body->clearForces();
|
||||
}
|
||||
}
|
||||
|
||||
void b3GpuDynamicsWorld::setGravity(const btVector3& gravity)
|
||||
{
|
||||
m_gravity = gravity;
|
||||
m_rigidBodyPipeline->setGravity(gravity);
|
||||
}
|
||||
|
||||
int b3GpuDynamicsWorld::findOrRegisterCollisionShape(const btCollisionShape* colShape)
|
||||
@@ -308,10 +392,43 @@ void b3GpuDynamicsWorld::addRigidBody(btRigidBody* body)
|
||||
}
|
||||
}
|
||||
|
||||
void b3GpuDynamicsWorld::removeRigidBody(btRigidBody* colObj)
|
||||
{
|
||||
m_cpuGpuSync = true;
|
||||
btDynamicsWorld::removeCollisionObject(colObj);
|
||||
|
||||
if (getNumCollisionObjects()==0)
|
||||
{
|
||||
m_uniqueShapes.resize(0);
|
||||
m_uniqueShapeMapping.resize(0);
|
||||
m_np->reset();
|
||||
m_bp->reset();
|
||||
m_rigidBodyPipeline->reset();
|
||||
#ifdef BT_USE_BODY_UPDATE_REVISION
|
||||
m_bodyUpdateRevisions.resize(0);
|
||||
#endif //BT_USE_BODY_UPDATE_REVISION
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
void b3GpuDynamicsWorld::removeCollisionObject(btCollisionObject* colObj)
|
||||
{
|
||||
m_cpuGpuSync = true;
|
||||
btDynamicsWorld::removeCollisionObject(colObj);
|
||||
if (getNumCollisionObjects()==0)
|
||||
{
|
||||
m_uniqueShapes.resize(0);
|
||||
m_uniqueShapeMapping.resize(0);
|
||||
m_np->reset();
|
||||
m_bp->reset();
|
||||
m_rigidBodyPipeline->reset();
|
||||
#ifdef BT_USE_BODY_UPDATE_REVISION
|
||||
m_bodyUpdateRevisions.resize(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void b3GpuDynamicsWorld::rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const
|
||||
@@ -319,6 +436,19 @@ void b3GpuDynamicsWorld::rayTest(const btVector3& rayFromWorld, const btVector3&
|
||||
|
||||
}
|
||||
|
||||
void b3GpuDynamicsWorld::synchronizeMotionStates()
|
||||
{
|
||||
//iterate over all collision objects
|
||||
for ( int i=0;i<m_collisionObjects.size();i++)
|
||||
{
|
||||
btCollisionObject* colObj = m_collisionObjects[i];
|
||||
btRigidBody* body = btRigidBody::upcast(colObj);
|
||||
if (body)
|
||||
synchronizeSingleMotionState(body);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void b3GpuDynamicsWorld::synchronizeSingleMotionState(btRigidBody* body)
|
||||
{
|
||||
btAssert(body);
|
||||
|
||||
@@ -27,7 +27,7 @@ class b3GpuDynamicsWorld : public btDynamicsWorld
|
||||
|
||||
btVector3 m_gravity;
|
||||
bool m_cpuGpuSync;
|
||||
|
||||
float m_localTime;
|
||||
|
||||
int findOrRegisterCollisionShape(const btCollisionShape* colShape);
|
||||
|
||||
@@ -39,10 +39,8 @@ public:
|
||||
|
||||
virtual int stepSimulation( btScalar timeStep,int maxSubSteps=1, btScalar fixedTimeStep=btScalar(1.)/btScalar(60.));
|
||||
|
||||
virtual void synchronizeMotionStates()
|
||||
{
|
||||
btAssert(0);
|
||||
}
|
||||
virtual void synchronizeMotionStates();
|
||||
|
||||
|
||||
void debugDrawWorld() {}
|
||||
|
||||
@@ -52,6 +50,8 @@ public:
|
||||
|
||||
void removeCollisionObject(btCollisionObject* colObj);
|
||||
|
||||
virtual void removeRigidBody(btRigidBody* body);
|
||||
|
||||
void rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const;
|
||||
|
||||
btAlignedObjectArray<class btCollisionObject*>& getCollisionObjectArray();
|
||||
@@ -69,10 +69,6 @@ public:
|
||||
addRigidBody(body);
|
||||
}
|
||||
|
||||
virtual void removeRigidBody(btRigidBody* body)
|
||||
{
|
||||
btAssert(0);
|
||||
}
|
||||
|
||||
|
||||
virtual void addAction(btActionInterface* action)
|
||||
@@ -97,10 +93,7 @@ public:
|
||||
}
|
||||
|
||||
|
||||
virtual void clearForces()
|
||||
{
|
||||
btAssert(0);
|
||||
}
|
||||
virtual void clearForces();
|
||||
|
||||
virtual btDynamicsWorldType getWorldType() const
|
||||
{
|
||||
|
||||
@@ -249,6 +249,19 @@ void b3GpuSapBroadphase::calculateOverlappingPairsHost()
|
||||
|
||||
}
|
||||
|
||||
void b3GpuSapBroadphase::reset()
|
||||
{
|
||||
m_allAabbsGPU.resize(0);
|
||||
m_allAabbsCPU.resize(0);
|
||||
|
||||
m_smallAabbsGPU.resize(0);
|
||||
m_smallAabbsCPU.resize(0);
|
||||
|
||||
m_largeAabbsGPU.resize(0);
|
||||
m_largeAabbsCPU.resize(0);
|
||||
}
|
||||
|
||||
|
||||
void b3GpuSapBroadphase::calculateOverlappingPairs()
|
||||
{
|
||||
int axis = 0;//todo on GPU for now hardcode
|
||||
|
||||
@@ -52,6 +52,8 @@ class b3GpuSapBroadphase
|
||||
void calculateOverlappingPairs();
|
||||
void calculateOverlappingPairsHost();
|
||||
|
||||
void reset();
|
||||
|
||||
void init3dSap();
|
||||
void calculateOverlappingPairsHostIncremental3Sap();
|
||||
|
||||
|
||||
@@ -19,7 +19,7 @@ struct b3Config
|
||||
int m_maxTriConvexPairCapacity;
|
||||
|
||||
b3Config()
|
||||
:m_maxConvexBodies(32*1024),
|
||||
:m_maxConvexBodies(64*1024),
|
||||
m_maxConvexShapes(8192),
|
||||
m_maxVerticesPerFace(64),
|
||||
m_maxFacesPerShape(64),
|
||||
|
||||
@@ -683,6 +683,12 @@ const struct b3RigidBodyCL* b3GpuNarrowPhase::getBodiesCpu() const
|
||||
return &m_data->m_bodyBufferCPU->at(0);
|
||||
};
|
||||
|
||||
struct b3RigidBodyCL* b3GpuNarrowPhase::getBodiesCpu()
|
||||
{
|
||||
return &m_data->m_bodyBufferCPU->at(0);
|
||||
};
|
||||
|
||||
|
||||
int b3GpuNarrowPhase::getNumBodiesGpu() const
|
||||
{
|
||||
return m_data->m_bodyBufferGPU->size();
|
||||
@@ -852,7 +858,7 @@ int b3GpuNarrowPhase::registerRigidBody(int collidableIndex, float mass, const f
|
||||
} else
|
||||
{
|
||||
|
||||
assert(body.m_collidableIdx>=0);
|
||||
b3Assert(body.m_collidableIdx>=0);
|
||||
|
||||
//approximate using the aabb of the shape
|
||||
|
||||
@@ -917,6 +923,28 @@ void b3GpuNarrowPhase::writeAllBodiesToGpu()
|
||||
|
||||
}
|
||||
|
||||
|
||||
void b3GpuNarrowPhase::reset()
|
||||
{
|
||||
m_data->m_numAcceleratedShapes = 0;
|
||||
m_data->m_numAcceleratedRigidBodies = 0;
|
||||
this->m_static0Index = -1;
|
||||
m_data->m_uniqueEdges.resize(0);
|
||||
m_data->m_convexVertices.resize(0);
|
||||
m_data->m_convexPolyhedra.resize(0);
|
||||
m_data->m_convexIndices.resize(0);
|
||||
m_data->m_cpuChildShapes.resize(0);
|
||||
m_data->m_convexFaces.resize(0);
|
||||
m_data->m_collidablesCPU.resize(0);
|
||||
m_data->m_localShapeAABBCPU->resize(0);
|
||||
m_data->m_bvhData.resize(0);
|
||||
m_data->m_treeNodesCPU.resize(0);
|
||||
m_data->m_subTreesCPU.resize(0);
|
||||
m_data->m_bvhInfoCPU.resize(0);
|
||||
|
||||
}
|
||||
|
||||
|
||||
void b3GpuNarrowPhase::readbackAllBodiesToCpu()
|
||||
{
|
||||
m_data->m_bodyBufferGPU->copyToHostPointer(&m_data->m_bodyBufferCPU->at(0),m_data->m_numAcceleratedRigidBodies);
|
||||
|
||||
@@ -48,7 +48,7 @@ public:
|
||||
void setObjectTransform(const float* position, const float* orientation , int bodyIndex);
|
||||
|
||||
void writeAllBodiesToGpu();
|
||||
|
||||
void reset();
|
||||
void readbackAllBodiesToCpu();
|
||||
void getObjectTransformFromCpu(float* position, float* orientation , int bodyIndex) const;
|
||||
|
||||
@@ -57,6 +57,7 @@ public:
|
||||
|
||||
cl_mem getBodiesGpu();
|
||||
const struct b3RigidBodyCL* getBodiesCpu() const;
|
||||
struct b3RigidBodyCL* getBodiesCpu();
|
||||
|
||||
int getNumBodiesGpu() const;
|
||||
|
||||
|
||||
@@ -59,6 +59,7 @@ b3GpuRigidBodyPipeline::b3GpuRigidBodyPipeline(cl_context ctx,cl_device_id devic
|
||||
m_data->m_broadphaseDbvt = broadphaseDbvt;
|
||||
m_data->m_broadphaseSap = broadphaseSap;
|
||||
m_data->m_narrowphase = narrowphase;
|
||||
m_data->m_gravity.setValue(0.f,-9.8f,0.f);
|
||||
|
||||
cl_int errNum=0;
|
||||
|
||||
@@ -98,6 +99,12 @@ b3GpuRigidBodyPipeline::~b3GpuRigidBodyPipeline()
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
void b3GpuRigidBodyPipeline::reset()
|
||||
{
|
||||
m_data->m_allAabbsGPU->resize(0);
|
||||
m_data->m_allAabbsCPU.resize(0);
|
||||
m_data->m_joints.resize(0);
|
||||
}
|
||||
|
||||
void b3GpuRigidBodyPipeline::addConstraint(b3TypedConstraint* constraint)
|
||||
{
|
||||
@@ -148,7 +155,7 @@ void b3GpuRigidBodyPipeline::stepSimulation(float deltaTime)
|
||||
int numContacts = 0;
|
||||
|
||||
|
||||
int numBodies = m_data->m_narrowphase->getNumBodiesGpu();
|
||||
int numBodies = m_data->m_narrowphase->getNumRigidBodies();
|
||||
|
||||
if (numPairs)
|
||||
{
|
||||
@@ -194,9 +201,9 @@ void b3GpuRigidBodyPipeline::stepSimulation(float deltaTime)
|
||||
//solve constraints
|
||||
|
||||
b3OpenCLArray<b3RigidBodyCL> gpuBodies(m_data->m_context,m_data->m_queue,0,true);
|
||||
gpuBodies.setFromOpenCLBuffer(m_data->m_narrowphase->getBodiesGpu(),m_data->m_narrowphase->getNumBodiesGpu());
|
||||
gpuBodies.setFromOpenCLBuffer(m_data->m_narrowphase->getBodiesGpu(),m_data->m_narrowphase->getNumRigidBodies());
|
||||
b3OpenCLArray<b3InertiaCL> gpuInertias(m_data->m_context,m_data->m_queue,0,true);
|
||||
gpuInertias.setFromOpenCLBuffer(m_data->m_narrowphase->getBodyInertiasGpu(),m_data->m_narrowphase->getNumBodiesGpu());
|
||||
gpuInertias.setFromOpenCLBuffer(m_data->m_narrowphase->getBodyInertiasGpu(),m_data->m_narrowphase->getNumRigidBodies());
|
||||
b3OpenCLArray<b3Contact4> gpuContacts(m_data->m_context,m_data->m_queue,0,true);
|
||||
gpuContacts.setFromOpenCLBuffer(m_data->m_narrowphase->getContactsGpu(),m_data->m_narrowphase->getNumContactsGpu());
|
||||
|
||||
@@ -214,7 +221,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],0,0,numJoints, joints);
|
||||
m_data->m_solver->solveContacts(m_data->m_narrowphase->getNumRigidBodies(),&hostBodies[0],&hostInertias[0],0,0,numJoints, joints);
|
||||
|
||||
}
|
||||
gpuBodies.copyFromHost(hostBodies);
|
||||
@@ -302,14 +309,14 @@ void b3GpuRigidBodyPipeline::integrate(float timeStep)
|
||||
|
||||
b3LauncherCL launcher(m_data->m_queue,m_data->m_integrateTransformsKernel);
|
||||
launcher.setBuffer(m_data->m_narrowphase->getBodiesGpu());
|
||||
int numBodies = m_data->m_narrowphase->getNumBodiesGpu();
|
||||
int numBodies = m_data->m_narrowphase->getNumRigidBodies();
|
||||
launcher.setConst(numBodies);
|
||||
launcher.setConst(timeStep);
|
||||
float angularDamp = 0.99f;
|
||||
launcher.setConst(angularDamp);
|
||||
|
||||
b3Vector3 gravity(0.f,-9.8f,0.f);
|
||||
launcher.setConst(gravity);
|
||||
|
||||
launcher.setConst(m_data->m_gravity);
|
||||
|
||||
launcher.launch1D(numBodies);
|
||||
}
|
||||
@@ -320,7 +327,7 @@ void b3GpuRigidBodyPipeline::setupGpuAabbsFull()
|
||||
{
|
||||
cl_int ciErrNum=0;
|
||||
|
||||
int numBodies = m_data->m_narrowphase->getNumBodiesGpu();
|
||||
int numBodies = m_data->m_narrowphase->getNumRigidBodies();
|
||||
if (!numBodies)
|
||||
return;
|
||||
|
||||
@@ -356,9 +363,13 @@ cl_mem b3GpuRigidBodyPipeline::getBodyBuffer()
|
||||
|
||||
int b3GpuRigidBodyPipeline::getNumBodies() const
|
||||
{
|
||||
return m_data->m_narrowphase->getNumBodiesGpu();
|
||||
return m_data->m_narrowphase->getNumRigidBodies();
|
||||
}
|
||||
|
||||
void b3GpuRigidBodyPipeline::setGravity(const float* grav)
|
||||
{
|
||||
m_data->m_gravity.setValue(grav[0],grav[1],grav[2]);
|
||||
}
|
||||
|
||||
void b3GpuRigidBodyPipeline::writeAllInstancesToGpu()
|
||||
{
|
||||
|
||||
@@ -33,6 +33,8 @@ public:
|
||||
int registerPhysicsInstance(float mass, const float* position, const float* orientation, int collisionShapeIndex, int userData, bool writeInstanceToGpu);
|
||||
//if you passed "writeInstanceToGpu" false in the registerPhysicsInstance method (for performance) you need to call writeAllInstancesToGpu after all instances are registered
|
||||
void writeAllInstancesToGpu();
|
||||
void setGravity(const float* grav);
|
||||
void reset();
|
||||
|
||||
void addConstraint(class b3TypedConstraint* constraint);
|
||||
|
||||
|
||||
@@ -37,6 +37,7 @@ struct b3GpuRigidBodyPipelineInternalData
|
||||
|
||||
b3AlignedObjectArray<b3TypedConstraint*> m_joints;
|
||||
class b3GpuNarrowPhase* m_narrowphase;
|
||||
b3Vector3 m_gravity;
|
||||
|
||||
};
|
||||
|
||||
|
||||
Reference in New Issue
Block a user