more work towards CPU version
This commit is contained in:
122
src/Bullet3Dynamics/b3CpuRigidBodyPipeline.cpp
Normal file
122
src/Bullet3Dynamics/b3CpuRigidBodyPipeline.cpp
Normal file
@@ -0,0 +1,122 @@
|
||||
#include "b3CpuRigidBodyPipeline.h"
|
||||
|
||||
#include "Bullet3Dynamics/shared/b3IntegrateTransforms.h"
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/shared/b3RigidBodyData.h"
|
||||
#include "Bullet3Collision/BroadPhaseCollision/b3DynamicBvhBroadphase.h"
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3Config.h"
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/b3CpuNarrowPhase.h"
|
||||
|
||||
|
||||
struct b3CpuRigidBodyPipelineInternalData
|
||||
{
|
||||
b3AlignedObjectArray<b3RigidBodyData> m_rigidBodies;
|
||||
b3DynamicBvhBroadphase* m_bp;
|
||||
b3CpuNarrowPhase* m_np;
|
||||
b3Config m_config;
|
||||
};
|
||||
|
||||
|
||||
b3CpuRigidBodyPipeline::b3CpuRigidBodyPipeline(class b3CpuNarrowPhase* narrowphase, struct b3DynamicBvhBroadphase* broadphaseDbvt, const b3Config& config)
|
||||
{
|
||||
m_data = new b3CpuRigidBodyPipelineInternalData;
|
||||
m_data->m_np = narrowphase;
|
||||
m_data->m_bp = broadphaseDbvt;
|
||||
m_data->m_config = config;
|
||||
}
|
||||
|
||||
b3CpuRigidBodyPipeline::~b3CpuRigidBodyPipeline()
|
||||
{
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
void b3CpuRigidBodyPipeline::updateAabbWorldSpace()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void b3CpuRigidBodyPipeline::computeOverlappingPairs()
|
||||
{
|
||||
int numPairs = m_data->m_bp->getOverlappingPairCache()->getNumOverlappingPairs();
|
||||
m_data->m_bp->calculateOverlappingPairs();
|
||||
numPairs = m_data->m_bp->getOverlappingPairCache()->getNumOverlappingPairs();
|
||||
}
|
||||
|
||||
void b3CpuRigidBodyPipeline::computeContactPoints()
|
||||
{
|
||||
b3AlignedObjectArray<b3Aabb> aabbWorldSpace;
|
||||
b3AlignedObjectArray<b3Int4> pairs;
|
||||
|
||||
|
||||
m_data->m_np->computeContacts(&pairs,&aabbWorldSpace);
|
||||
|
||||
}
|
||||
void b3CpuRigidBodyPipeline::stepSimulation(float deltaTime)
|
||||
{
|
||||
|
||||
//update world space aabb's
|
||||
updateAabbWorldSpace();
|
||||
|
||||
//compute overlapping pairs
|
||||
computeOverlappingPairs();
|
||||
|
||||
//compute contacts
|
||||
computeContactPoints();
|
||||
|
||||
//solve contacts
|
||||
|
||||
//update transforms
|
||||
integrate(deltaTime);
|
||||
|
||||
|
||||
}
|
||||
|
||||
|
||||
void b3CpuRigidBodyPipeline::integrate(float deltaTime)
|
||||
{
|
||||
float angDamping=0.f;
|
||||
b3Vector3 gravityAcceleration=b3MakeVector3(0,-9,0);
|
||||
|
||||
//integrate transforms (external forces/gravity should be moved into constraint solver)
|
||||
for (int i=0;i<m_data->m_rigidBodies.size();i++)
|
||||
{
|
||||
b3IntegrateTransform(&m_data->m_rigidBodies[i],deltaTime,angDamping,gravityAcceleration);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
int b3CpuRigidBodyPipeline::registerPhysicsInstance(float mass, const float* position, const float* orientation, int collidableIndex, int userData)
|
||||
{
|
||||
b3RigidBodyData body;
|
||||
int index = m_data->m_rigidBodies.size();
|
||||
body.m_invMass = mass ? 1.f/mass : 0.f;
|
||||
body.m_angVel.setValue(0,0,0);
|
||||
body.m_collidableIdx = collidableIndex;
|
||||
body.m_frictionCoeff = 0.3f;
|
||||
body.m_linVel.setValue(0,0,0);
|
||||
body.m_pos.setValue(position[0],position[1],position[2]);
|
||||
body.m_quat.setValue(orientation[0],orientation[1],orientation[2],orientation[3]);
|
||||
body.m_restituitionCoeff = 0.f;
|
||||
|
||||
m_data->m_rigidBodies.push_back(body);
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
return index;
|
||||
}
|
||||
|
||||
|
||||
const struct b3RigidBodyData* b3CpuRigidBodyPipeline::getBodyBuffer() const
|
||||
{
|
||||
return m_data->m_rigidBodies.size() ? &m_data->m_rigidBodies[0] : 0;
|
||||
}
|
||||
|
||||
int b3CpuRigidBodyPipeline::getNumBodies() const
|
||||
{
|
||||
return m_data->m_rigidBodies.size();
|
||||
}
|
||||
66
src/Bullet3Dynamics/b3CpuRigidBodyPipeline.h
Normal file
66
src/Bullet3Dynamics/b3CpuRigidBodyPipeline.h
Normal file
@@ -0,0 +1,66 @@
|
||||
/*
|
||||
Copyright (c) 2013 Advanced Micro Devices, Inc.
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
|
||||
3. This notice may not be removed or altered from any source distribution.
|
||||
*/
|
||||
//Originally written by Erwin Coumans
|
||||
|
||||
#ifndef B3_CPU_RIGIDBODY_PIPELINE_H
|
||||
#define B3_CPU_RIGIDBODY_PIPELINE_H
|
||||
|
||||
|
||||
|
||||
#include "Bullet3Common/b3AlignedObjectArray.h"
|
||||
#include "Bullet3OpenCL/Raycast/b3RaycastInfo.h"
|
||||
|
||||
class b3CpuRigidBodyPipeline
|
||||
{
|
||||
protected:
|
||||
struct b3CpuRigidBodyPipelineInternalData* m_data;
|
||||
|
||||
int allocateCollidable();
|
||||
|
||||
public:
|
||||
|
||||
|
||||
b3CpuRigidBodyPipeline(class b3CpuNarrowPhase* narrowphase, struct b3DynamicBvhBroadphase* broadphaseDbvt, const struct b3Config& config);
|
||||
virtual ~b3CpuRigidBodyPipeline();
|
||||
|
||||
virtual void stepSimulation(float deltaTime);
|
||||
virtual void integrate(float timeStep);
|
||||
virtual void updateAabbWorldSpace();
|
||||
virtual void computeOverlappingPairs();
|
||||
virtual void computeContactPoints();
|
||||
|
||||
int registerConvexPolyhedron(class b3ConvexUtility* convex);
|
||||
|
||||
int registerPhysicsInstance(float mass, const float* position, const float* orientation, int collisionShapeIndex, int userData);
|
||||
void writeAllInstancesToGpu();
|
||||
void copyConstraintsToHost();
|
||||
void setGravity(const float* grav);
|
||||
void reset();
|
||||
|
||||
int createPoint2PointConstraint(int bodyA, int bodyB, const float* pivotInA, const float* pivotInB,float breakingThreshold);
|
||||
int createFixedConstraint(int bodyA, int bodyB, const float* pivotInA, const float* pivotInB, const float* relTargetAB, float breakingThreshold);
|
||||
void removeConstraintByUid(int uid);
|
||||
|
||||
void addConstraint(class b3TypedConstraint* constraint);
|
||||
void removeConstraint(b3TypedConstraint* constraint);
|
||||
|
||||
void castRays(const b3AlignedObjectArray<b3RayInfo>& rays, b3AlignedObjectArray<b3RayHit>& hitResults);
|
||||
|
||||
const struct b3RigidBodyData* getBodyBuffer() const;
|
||||
|
||||
int getNumBodies() const;
|
||||
|
||||
};
|
||||
|
||||
#endif //B3_CPU_RIGIDBODY_PIPELINE_H
|
||||
56
src/Bullet3Dynamics/shared/b3IntegrateTransforms.h
Normal file
56
src/Bullet3Dynamics/shared/b3IntegrateTransforms.h
Normal file
@@ -0,0 +1,56 @@
|
||||
|
||||
|
||||
#include "Bullet3Collision/NarrowPhaseCollision/shared/b3RigidBodyData.h"
|
||||
|
||||
|
||||
inline void b3IntegrateTransform( b3RigidBodyData* body, float timeStep, float angularDamping, b3Float4ConstArg gravityAcceleration)
|
||||
{
|
||||
float BT_GPU_ANGULAR_MOTION_THRESHOLD = (0.25f * 3.14159254f);
|
||||
|
||||
if( (body->m_invMass != 0.f))
|
||||
{
|
||||
//angular velocity
|
||||
{
|
||||
b3Float4 axis;
|
||||
//add some hardcoded angular damping
|
||||
body->m_angVel.x *= angularDamping;
|
||||
body->m_angVel.y *= angularDamping;
|
||||
body->m_angVel.z *= angularDamping;
|
||||
|
||||
b3Float4 angvel = body->m_angVel;
|
||||
float fAngle = b3Sqrt(b3Dot(angvel, angvel));
|
||||
//limit the angular motion
|
||||
if(fAngle*timeStep > BT_GPU_ANGULAR_MOTION_THRESHOLD)
|
||||
{
|
||||
fAngle = BT_GPU_ANGULAR_MOTION_THRESHOLD / timeStep;
|
||||
}
|
||||
if(fAngle < 0.001f)
|
||||
{
|
||||
// use Taylor's expansions of sync function
|
||||
axis = angvel * (0.5f*timeStep-(timeStep*timeStep*timeStep)*0.020833333333f * fAngle * fAngle);
|
||||
}
|
||||
else
|
||||
{
|
||||
// sync(fAngle) = sin(c*fAngle)/t
|
||||
axis = angvel * ( b3Sin(0.5f * fAngle * timeStep) / fAngle);
|
||||
}
|
||||
b3Quat dorn;
|
||||
dorn.x = axis.x;
|
||||
dorn.y = axis.y;
|
||||
dorn.z = axis.z;
|
||||
dorn.w = b3Cos(fAngle * timeStep * 0.5f);
|
||||
b3Quat orn0 = body->m_quat;
|
||||
|
||||
b3Quat predictedOrn = b3QuatMul(dorn, orn0);
|
||||
predictedOrn = b3QuatNormalized(predictedOrn);
|
||||
body->m_quat=predictedOrn;
|
||||
}
|
||||
|
||||
//apply gravity
|
||||
body->m_linVel += gravityAcceleration * timeStep;
|
||||
|
||||
//linear velocity
|
||||
body->m_pos += body->m_linVel * timeStep;
|
||||
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user