remove world dependency from btDeformableBodySolver,btDeformableBackwardEulerObjective, and btCGProjection; reduce invasion into multibody world, all chnages are cosmetic now
This commit is contained in:
@@ -122,7 +122,7 @@ void DeformableMultibody::initPhysics()
|
||||
m_solver = sol;
|
||||
|
||||
m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver);
|
||||
deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
// deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
btVector3 gravity = btVector3(0, -10, 0);
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity;
|
||||
|
||||
@@ -164,7 +164,7 @@ void DeformableRigid::initPhysics()
|
||||
m_solver = sol;
|
||||
|
||||
m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver);
|
||||
deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
// deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
// m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality
|
||||
btVector3 gravity = btVector3(0, -10, 0);
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
|
||||
@@ -190,7 +190,7 @@ void GraspDeformable::initPhysics()
|
||||
m_solver = sol;
|
||||
|
||||
m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver);
|
||||
deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
// deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
btVector3 gravity = btVector3(0, -9.81, 0);
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
getDeformableDynamicsWorld()->getWorldInfo().m_gravity = gravity;
|
||||
@@ -357,6 +357,7 @@ void GraspDeformable::initPhysics()
|
||||
|
||||
// linear damping
|
||||
getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(.5,0.04, true));
|
||||
// getDeformableDynamicsWorld()->addForce(psb, new btDeformableMassSpringForce(3,0.04, true));
|
||||
getDeformableDynamicsWorld()->addForce(psb, new btDeformableGravityForce(gravity));
|
||||
getDeformableDynamicsWorld()->addForce(psb, new btDeformableNeoHookeanForce(2,10));
|
||||
}
|
||||
|
||||
@@ -248,7 +248,7 @@ void Pinch::initPhysics()
|
||||
m_solver = sol;
|
||||
|
||||
m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver);
|
||||
deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
// deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
// m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality
|
||||
btVector3 gravity = btVector3(0, -10, 0);
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
|
||||
@@ -182,7 +182,7 @@ void VolumetricDeformable::initPhysics()
|
||||
m_solver = sol;
|
||||
|
||||
m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration, deformableBodySolver);
|
||||
deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
// deformableBodySolver->setWorld(getDeformableDynamicsWorld());
|
||||
// m_dynamicsWorld->getSolverInfo().m_singleAxisDeformableThreshold = 0.f;//faster but lower quality
|
||||
btVector3 gravity = btVector3(0, -10, 0);
|
||||
m_dynamicsWorld->setGravity(gravity);
|
||||
|
||||
@@ -57,9 +57,11 @@ public:
|
||||
};
|
||||
|
||||
void buildAndProcessIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback);
|
||||
void processIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback);
|
||||
|
||||
void buildIslands(btDispatcher* dispatcher, btCollisionWorld* colWorld);
|
||||
|
||||
void processIslands(btDispatcher* dispatcher, btCollisionWorld* collisionWorld, IslandCallback* callback);
|
||||
|
||||
bool getSplitIslands()
|
||||
{
|
||||
return m_splitIslands;
|
||||
|
||||
@@ -428,27 +428,41 @@ void btMultiBodyDynamicsWorld::forwardKinematics()
|
||||
void btMultiBodyDynamicsWorld::solveConstraints(btContactSolverInfo& solverInfo)
|
||||
{
|
||||
solveExternalForces(solverInfo);
|
||||
m_islandManager->buildAndProcessIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback);
|
||||
buildIslands();
|
||||
solveInternalConstraints(solverInfo);
|
||||
}
|
||||
|
||||
void btMultiBodyDynamicsWorld::buildIslands()
|
||||
{
|
||||
m_islandManager->buildIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld());
|
||||
}
|
||||
|
||||
void btMultiBodyDynamicsWorld::processIslands()
|
||||
{
|
||||
m_islandManager->processIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback);
|
||||
m_islandManager->buildAndProcessIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), m_solverMultiBodyIslandCallback);
|
||||
}
|
||||
|
||||
void btMultiBodyDynamicsWorld::solveInternalConstraints(btContactSolverInfo& solverInfo)
|
||||
{
|
||||
/// solve all the constraints for this island
|
||||
m_solverMultiBodyIslandCallback->processConstraints();
|
||||
|
||||
m_constraintSolver->allSolved(solverInfo, m_debugDrawer);
|
||||
calculateJointForce(solverInfo);
|
||||
processDeltaVee();
|
||||
}
|
||||
|
||||
void btMultiBodyDynamicsWorld::btMultiBodyDynamicsWorld::processConstraintsAndDeltaVee()
|
||||
{
|
||||
m_solverMultiBodyIslandCallback->processConstraints();
|
||||
processDeltaVee();
|
||||
}
|
||||
|
||||
void btMultiBodyDynamicsWorld::processDeltaVee()
|
||||
{
|
||||
for (int i = 0; i < this->m_multiBodies.size(); i++)
|
||||
{
|
||||
btMultiBody* bod = m_multiBodies[i];
|
||||
bod->processDeltaVeeMultiDof2();
|
||||
}
|
||||
}
|
||||
|
||||
void btMultiBodyDynamicsWorld::calculateJointForce(btContactSolverInfo& solverInfo)
|
||||
{
|
||||
{
|
||||
BT_PROFILE("btMultiBody stepVelocities");
|
||||
for (int i = 0; i < this->m_multiBodies.size(); i++)
|
||||
@@ -490,12 +504,6 @@ void btMultiBodyDynamicsWorld::solveInternalConstraints(btContactSolverInfo& sol
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
for (int i = 0; i < this->m_multiBodies.size(); i++)
|
||||
{
|
||||
btMultiBody* bod = m_multiBodies[i];
|
||||
bod->processDeltaVeeMultiDof2();
|
||||
}
|
||||
}
|
||||
|
||||
void btMultiBodyDynamicsWorld::solveExternalForces(btContactSolverInfo& solverInfo)
|
||||
@@ -1087,8 +1095,8 @@ void btMultiBodyDynamicsWorld::serializeMultiBodies(btSerializer* serializer)
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void btMultiBodyDynamicsWorld::setSplitIslands(bool split)
|
||||
{
|
||||
m_islandManager->setSplitIslands(split);
|
||||
}
|
||||
//
|
||||
//void btMultiBodyDynamicsWorld::setSplitIslands(bool split)
|
||||
//{
|
||||
// m_islandManager->setSplitIslands(split);
|
||||
//}
|
||||
|
||||
@@ -57,6 +57,7 @@ public:
|
||||
virtual ~btMultiBodyDynamicsWorld();
|
||||
|
||||
virtual void solveConstraints(btContactSolverInfo& solverInfo);
|
||||
|
||||
virtual void addMultiBody(btMultiBody* body, int group = btBroadphaseProxy::DefaultFilter, int mask = btBroadphaseProxy::AllFilter);
|
||||
|
||||
virtual void removeMultiBody(btMultiBody* body);
|
||||
@@ -118,8 +119,8 @@ public:
|
||||
virtual void solveExternalForces(btContactSolverInfo& solverInfo);
|
||||
virtual void solveInternalConstraints(btContactSolverInfo& solverInfo);
|
||||
void buildIslands();
|
||||
void processIslands();
|
||||
void setSplitIslands(bool split);
|
||||
|
||||
void calculateJointForce(btContactSolverInfo& solverInfo);
|
||||
void processDeltaVee();
|
||||
void processConstraintsAndDeltaVee();
|
||||
};
|
||||
#endif //BT_MULTIBODY_DYNAMICS_WORLD_H
|
||||
|
||||
@@ -20,7 +20,7 @@
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraint.h"
|
||||
|
||||
class btDeformableMultiBodyDynamicsWorld;
|
||||
//class btDeformableMultiBodyDynamicsWorld;
|
||||
|
||||
struct DeformableContactConstraint
|
||||
{
|
||||
@@ -62,7 +62,6 @@ public:
|
||||
typedef btAlignedObjectArray<btAlignedObjectArray<btVector3> > TVArrayStack;
|
||||
typedef btAlignedObjectArray<btAlignedObjectArray<btScalar> > TArrayStack;
|
||||
btAlignedObjectArray<btSoftBody *>& m_softBodies;
|
||||
btDeformableMultiBodyDynamicsWorld* m_world;
|
||||
const btScalar& m_dt;
|
||||
|
||||
btCGProjection(btAlignedObjectArray<btSoftBody *>& softBodies, const btScalar& dt)
|
||||
@@ -86,11 +85,6 @@ public:
|
||||
virtual void reinitialize(bool nodeUpdated)
|
||||
{
|
||||
}
|
||||
|
||||
virtual void setWorld(btDeformableMultiBodyDynamicsWorld* world)
|
||||
{
|
||||
m_world = world;
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
|
||||
@@ -151,10 +151,6 @@ void btDeformableBackwardEulerObjective::initialGuess(TVStack& dv, const TVStack
|
||||
//set constraints as projections
|
||||
void btDeformableBackwardEulerObjective::setConstraints()
|
||||
{
|
||||
// build islands for multibody solve
|
||||
m_world->btMultiBodyDynamicsWorld::buildIslands();
|
||||
// for repeated constraint solve, splitIslands has to be set to true
|
||||
m_world->setSplitIslands(true);
|
||||
projection.setConstraints();
|
||||
}
|
||||
|
||||
|
||||
@@ -26,13 +26,13 @@
|
||||
#include "btDeformableMultiBodyDynamicsWorld.h"
|
||||
#include "LinearMath/btQuickprof.h"
|
||||
|
||||
class btDeformableMultiBodyDynamicsWorld;
|
||||
//class btDeformableMultiBodyDynamicsWorld;
|
||||
class btDeformableBackwardEulerObjective
|
||||
{
|
||||
public:
|
||||
typedef btAlignedObjectArray<btVector3> TVStack;
|
||||
btScalar m_dt;
|
||||
btDeformableMultiBodyDynamicsWorld* m_world;
|
||||
// btDeformableMultiBodyDynamicsWorld* m_world;
|
||||
btAlignedObjectArray<btDeformableLagrangianForce*> m_lf;
|
||||
btAlignedObjectArray<btSoftBody *>& m_softBodies;
|
||||
Preconditioner* m_preconditioner;
|
||||
@@ -99,12 +99,6 @@ public:
|
||||
m_preconditioner->operator()(x,b);
|
||||
}
|
||||
|
||||
virtual void setWorld(btDeformableMultiBodyDynamicsWorld* world)
|
||||
{
|
||||
m_world = world;
|
||||
projection.setWorld(world);
|
||||
}
|
||||
|
||||
virtual void updateId()
|
||||
{
|
||||
size_t id = 0;
|
||||
|
||||
@@ -30,14 +30,14 @@ btDeformableBodySolver::~btDeformableBodySolver()
|
||||
delete m_objective;
|
||||
}
|
||||
|
||||
void btDeformableBodySolver::solveConstraints(float solverdt)
|
||||
void btDeformableBodySolver::solveDeformableConstraints(float solverdt)
|
||||
{
|
||||
BT_PROFILE("solveConstraints");
|
||||
// save v_{n+1}^* velocity after explicit forces
|
||||
backupVelocity();
|
||||
// backupVelocity();
|
||||
|
||||
// add constraints to the solver
|
||||
setConstraints();
|
||||
// setConstraints();
|
||||
m_objective->computeResidual(solverdt, m_residual);
|
||||
m_objective->applyDynamicFriction(m_residual);
|
||||
computeStep(m_dv, m_residual);
|
||||
@@ -47,7 +47,6 @@ void btDeformableBodySolver::solveConstraints(float solverdt)
|
||||
|
||||
void btDeformableBodySolver::computeStep(TVStack& dv, const TVStack& residual)
|
||||
{
|
||||
|
||||
btScalar tolerance = std::numeric_limits<float>::epsilon() * 16 * m_objective->computeNorm(residual);
|
||||
m_cg.solve(*m_objective, dv, residual, tolerance);
|
||||
}
|
||||
@@ -78,22 +77,16 @@ void btDeformableBodySolver::setConstraints()
|
||||
{
|
||||
BT_PROFILE("setConstraint");
|
||||
m_objective->setConstraints();
|
||||
// m_contact_iterations takes over m_numIterations
|
||||
m_contact_iterations = m_objective->m_world->getSolverInfo().m_numIterations;
|
||||
for (int i = 0; i < m_contact_iterations; ++i)
|
||||
{
|
||||
}
|
||||
|
||||
void btDeformableBodySolver::solveContactConstraints()
|
||||
{
|
||||
BT_PROFILE("setConstraint");
|
||||
m_objective->projection.update();
|
||||
m_objective->enforceConstraint(m_dv);
|
||||
m_objective->updateVelocity(m_dv);
|
||||
}
|
||||
// recover m_numIterations from m_contact_iterations
|
||||
m_objective->m_world->getSolverInfo().m_numIterations = m_contact_iterations;
|
||||
}
|
||||
|
||||
void btDeformableBodySolver::setWorld(btDeformableMultiBodyDynamicsWorld* world)
|
||||
{
|
||||
m_objective->setWorld(world);
|
||||
}
|
||||
|
||||
void btDeformableBodySolver::updateVelocity()
|
||||
{
|
||||
|
||||
@@ -61,7 +61,11 @@ public:
|
||||
|
||||
void extracted(float solverdt);
|
||||
|
||||
virtual void solveConstraints(float solverdt);
|
||||
virtual void solveDeformableConstraints(btScalar solverdt);
|
||||
|
||||
void solveContactConstraints();
|
||||
|
||||
virtual void solveConstraints(float dt){}
|
||||
|
||||
void reinitialize(const btAlignedObjectArray<btSoftBody *>& softBodies, btScalar dt);
|
||||
|
||||
@@ -77,7 +81,7 @@ public:
|
||||
|
||||
void computeStep(TVStack& dv, const TVStack& residual);
|
||||
|
||||
virtual void predictMotion(float solverdt);
|
||||
virtual void predictMotion(btScalar solverdt);
|
||||
|
||||
virtual void copySoftBodyToVertexBuffer(const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer) {}
|
||||
|
||||
@@ -90,8 +94,9 @@ public:
|
||||
softBody->defaultCollisionHandler(otherSoftBody);
|
||||
}
|
||||
virtual void optimize(btAlignedObjectArray<btSoftBody *> &softBodies, bool forceUpdate = false){}
|
||||
|
||||
virtual bool checkInitialized(){return true;}
|
||||
virtual void setWorld(btDeformableMultiBodyDynamicsWorld* world);
|
||||
|
||||
};
|
||||
|
||||
#endif /* btDeformableBodySolver_h */
|
||||
|
||||
@@ -19,13 +19,8 @@
|
||||
#include <cmath>
|
||||
void btDeformableContactProjection::update()
|
||||
{
|
||||
///solve rigid body constraints
|
||||
{
|
||||
// m_numIterations get temporarily to 1 so that we interleave one step of multibody solve with one step of multibody/deformable contact solve
|
||||
m_world->getSolverInfo().m_numIterations = 1;
|
||||
m_world->processIslands();
|
||||
m_world->btMultiBodyDynamicsWorld::solveInternalConstraints(m_world->getSolverInfo()); // process constraints deferred in the previous step
|
||||
}
|
||||
// m_world->getSolverInfo().m_numIterations = 1;
|
||||
|
||||
// loop through constraints to set constrained values
|
||||
for (int index = 0; index < m_constraints.size(); ++index)
|
||||
{
|
||||
|
||||
@@ -33,7 +33,6 @@ The algorithm also closely resembles the one in http://physbam.stanford.edu/~fed
|
||||
#include "btDeformableMultiBodyDynamicsWorld.h"
|
||||
#include "btDeformableBodySolver.h"
|
||||
#include "LinearMath/btQuickprof.h"
|
||||
|
||||
void btDeformableMultiBodyDynamicsWorld::internalSingleStepSimulation(btScalar timeStep)
|
||||
{
|
||||
BT_PROFILE("internalSingleStepSimulation");
|
||||
@@ -52,7 +51,7 @@ void btDeformableMultiBodyDynamicsWorld::internalSingleStepSimulation(btScalar t
|
||||
beforeSolverCallbacks(timeStep);
|
||||
|
||||
///solve deformable bodies constraints
|
||||
solveDeformableBodiesConstraints(timeStep);
|
||||
solveConstraints(timeStep);
|
||||
|
||||
afterSolverCallbacks(timeStep);
|
||||
|
||||
@@ -172,9 +171,31 @@ void btDeformableMultiBodyDynamicsWorld::integrateTransforms(btScalar timeStep)
|
||||
m_deformableBodySolver->revertVelocity();
|
||||
}
|
||||
|
||||
void btDeformableMultiBodyDynamicsWorld::solveDeformableBodiesConstraints(btScalar timeStep)
|
||||
void btDeformableMultiBodyDynamicsWorld::solveConstraints(btScalar timeStep)
|
||||
{
|
||||
m_deformableBodySolver->solveConstraints(timeStep);
|
||||
// save v_{n+1}^* velocity after explicit forces
|
||||
m_deformableBodySolver->backupVelocity();
|
||||
|
||||
// setup constraints among multibodies and between multibodies and deformable bodies
|
||||
setupConstraints();
|
||||
solveMultiBodyConstraints();
|
||||
m_deformableBodySolver->solveDeformableConstraints(timeStep);
|
||||
}
|
||||
|
||||
void btDeformableMultiBodyDynamicsWorld::setupConstraints()
|
||||
{
|
||||
m_deformableBodySolver->setConstraints();
|
||||
m_islandManager->buildIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld());
|
||||
}
|
||||
|
||||
void btDeformableMultiBodyDynamicsWorld::solveMultiBodyConstraints()
|
||||
{
|
||||
for (int i = 0; i < m_contact_iterations; ++i)
|
||||
{
|
||||
m_islandManager->processIslands(getCollisionWorld()->getDispatcher(), getCollisionWorld(), (btSimulationIslandManager::IslandCallback*)m_solverMultiBodyIslandCallback);
|
||||
btMultiBodyDynamicsWorld::processConstraintsAndDeltaVee();
|
||||
m_deformableBodySolver->solveContactConstraints();
|
||||
}
|
||||
}
|
||||
|
||||
void btDeformableMultiBodyDynamicsWorld::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask)
|
||||
|
||||
@@ -21,11 +21,14 @@
|
||||
#include "btDeformableMassSpringForce.h"
|
||||
#include "btDeformableBodySolver.h"
|
||||
#include "btSoftBodyHelpers.h"
|
||||
#include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h"
|
||||
#include <functional>
|
||||
typedef btAlignedObjectArray<btSoftBody*> btSoftBodyArray;
|
||||
|
||||
class btDeformableBodySolver;
|
||||
class btDeformableLagrangianForce;
|
||||
struct MultiBodyInplaceSolverIslandCallback;
|
||||
|
||||
typedef btAlignedObjectArray<btSoftBody*> btSoftBodyArray;
|
||||
|
||||
class btDeformableMultiBodyDynamicsWorld : public btMultiBodyDynamicsWorld
|
||||
@@ -41,6 +44,7 @@ class btDeformableMultiBodyDynamicsWorld : public btMultiBodyDynamicsWorld
|
||||
bool m_drawClusterTree;
|
||||
btSoftBodyWorldInfo m_sbi;
|
||||
btScalar m_internalTime;
|
||||
int m_contact_iterations;
|
||||
|
||||
typedef void (*btSolverCallback)(btScalar time, btDeformableMultiBodyDynamicsWorld* world);
|
||||
btSolverCallback m_solverCallback;
|
||||
@@ -52,7 +56,7 @@ protected:
|
||||
|
||||
void positionCorrection(btScalar timeStep);
|
||||
|
||||
void solveDeformableBodiesConstraints(btScalar timeStep);
|
||||
void solveConstraints(btScalar timeStep);
|
||||
|
||||
public:
|
||||
btDeformableMultiBodyDynamicsWorld(btDispatcher* dispatcher, btBroadphaseInterface* pairCache, btMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btDeformableBodySolver* deformableBodySolver = 0)
|
||||
@@ -76,6 +80,7 @@ public:
|
||||
|
||||
m_sbi.m_sparsesdf.Initialize();
|
||||
m_internalTime = 0.0;
|
||||
m_contact_iterations = 1;
|
||||
}
|
||||
|
||||
void setSolverCallback(btSolverCallback cb)
|
||||
@@ -140,6 +145,9 @@ public:
|
||||
|
||||
int getDrawFlags() const { return (m_drawFlags); }
|
||||
void setDrawFlags(int f) { m_drawFlags = f; }
|
||||
|
||||
void setupConstraints();
|
||||
void solveMultiBodyConstraints();
|
||||
};
|
||||
|
||||
#endif //BT_DEFORMABLE_RIGID_DYNAMICS_WORLD_H
|
||||
|
||||
Reference in New Issue
Block a user