mirror of
https://github.com/bulletphysics/bullet3
synced 2025-01-19 05:20:06 +00:00
Merge pull request #2141 from erwincoumans/blocksolver
solver experiment
This commit is contained in:
commit
a9e350b0fb
219
examples/BlockSolver/BlockSolverExample.cpp
Normal file
219
examples/BlockSolver/BlockSolverExample.cpp
Normal file
@ -0,0 +1,219 @@
|
|||||||
|
#include "BlockSolverExample.h"
|
||||||
|
#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h"
|
||||||
|
#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h"
|
||||||
|
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||||
|
#include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h"
|
||||||
|
#include "btBlockSolver.h"
|
||||||
|
//for URDF import support
|
||||||
|
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
|
||||||
|
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||||
|
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||||
|
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||||
|
|
||||||
|
class BlockSolverExample : public CommonMultiBodyBase
|
||||||
|
{
|
||||||
|
int m_option;
|
||||||
|
public:
|
||||||
|
BlockSolverExample(GUIHelperInterface* helper, int option);
|
||||||
|
virtual ~BlockSolverExample();
|
||||||
|
|
||||||
|
virtual void initPhysics();
|
||||||
|
|
||||||
|
virtual void stepSimulation(float deltaTime);
|
||||||
|
|
||||||
|
virtual void resetCamera()
|
||||||
|
{
|
||||||
|
float dist = 3;
|
||||||
|
float pitch = -35;
|
||||||
|
float yaw = 50;
|
||||||
|
float targetPos[3] = {0, 0, .1};
|
||||||
|
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
|
||||||
|
}
|
||||||
|
|
||||||
|
void createMultiBodyStack();
|
||||||
|
btMultiBody* createMultiBody(btScalar mass, const btTransform& trans, btCollisionShape* collisionShape);
|
||||||
|
btMultiBody* loadRobot(std::string filepath);
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
BlockSolverExample::BlockSolverExample(GUIHelperInterface* helper, int option)
|
||||||
|
: CommonMultiBodyBase(helper),
|
||||||
|
m_option(option)
|
||||||
|
{
|
||||||
|
m_guiHelper->setUpAxis(2);
|
||||||
|
}
|
||||||
|
|
||||||
|
BlockSolverExample::~BlockSolverExample()
|
||||||
|
{
|
||||||
|
// Do nothing
|
||||||
|
}
|
||||||
|
|
||||||
|
void BlockSolverExample::stepSimulation(float deltaTime)
|
||||||
|
{
|
||||||
|
//use a smaller internal timestep, there are stability issues
|
||||||
|
btScalar internalTimeStep = 1./240.f;
|
||||||
|
m_dynamicsWorld->stepSimulation(deltaTime, 10, internalTimeStep);
|
||||||
|
}
|
||||||
|
|
||||||
|
void BlockSolverExample::initPhysics()
|
||||||
|
{
|
||||||
|
|
||||||
|
///collision configuration contains default setup for memory, collision setup
|
||||||
|
m_collisionConfiguration = new btDefaultCollisionConfiguration();
|
||||||
|
|
||||||
|
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
|
||||||
|
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
|
||||||
|
|
||||||
|
m_broadphase = new btDbvtBroadphase();
|
||||||
|
|
||||||
|
|
||||||
|
btMLCPSolverInterface* mlcp;
|
||||||
|
if (m_option&BLOCK_SOLVER_SI)
|
||||||
|
{
|
||||||
|
btAssert(!m_solver);
|
||||||
|
m_solver = new btMultiBodyConstraintSolver;
|
||||||
|
b3Printf("Constraint Solver: Sequential Impulse");
|
||||||
|
}
|
||||||
|
if (m_option&BLOCK_SOLVER_MLCP_PGS)
|
||||||
|
{
|
||||||
|
btAssert(!m_solver);
|
||||||
|
mlcp = new btSolveProjectedGaussSeidel();
|
||||||
|
m_solver = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||||
|
b3Printf("Constraint Solver: MLCP + PGS");
|
||||||
|
}
|
||||||
|
if (m_option&BLOCK_SOLVER_MLCP_DANTZIG)
|
||||||
|
{
|
||||||
|
btAssert(!m_solver);
|
||||||
|
mlcp = new btDantzigSolver();
|
||||||
|
m_solver = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||||
|
b3Printf("Constraint Solver: MLCP + Dantzig");
|
||||||
|
}
|
||||||
|
if (m_option&BLOCK_SOLVER_BLOCK)
|
||||||
|
{
|
||||||
|
m_solver = new btBlockSolver();
|
||||||
|
}
|
||||||
|
|
||||||
|
btAssert(m_solver);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
btMultiBodyDynamicsWorld* world = new btMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration);
|
||||||
|
m_dynamicsWorld = world;
|
||||||
|
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
|
||||||
|
m_dynamicsWorld->setGravity(btVector3(0, 0, -10));
|
||||||
|
m_dynamicsWorld->getSolverInfo().m_numIterations = 50;
|
||||||
|
m_dynamicsWorld->getSolverInfo().m_globalCfm = btScalar(1e-6); //todo: what value is good?
|
||||||
|
|
||||||
|
if (m_option&BLOCK_SOLVER_SCENE_MB_STACK)
|
||||||
|
{
|
||||||
|
createMultiBodyStack();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void BlockSolverExample::createMultiBodyStack()
|
||||||
|
{
|
||||||
|
///create a few basic rigid bodies
|
||||||
|
bool loadPlaneFromURDF = false;
|
||||||
|
if (loadPlaneFromURDF)
|
||||||
|
{
|
||||||
|
btMultiBody* mb = loadRobot("plane.urdf");
|
||||||
|
printf("!\n");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
btBoxShape* groundShape = createBoxShape(btVector3(btScalar(50.), btScalar(50.), btScalar(50.)));
|
||||||
|
m_collisionShapes.push_back(groundShape);
|
||||||
|
btScalar mass = 0;
|
||||||
|
btTransform tr;
|
||||||
|
tr.setIdentity();
|
||||||
|
tr.setOrigin(btVector3(0, 0, -50));
|
||||||
|
btMultiBody* body = createMultiBody(mass, tr, groundShape);
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i=0;i<10;i++)
|
||||||
|
{
|
||||||
|
btBoxShape* boxShape = createBoxShape(btVector3(btScalar(.1), btScalar(.1), btScalar(.1)));
|
||||||
|
m_collisionShapes.push_back(boxShape);
|
||||||
|
btScalar mass = 1;
|
||||||
|
if (i == 9)
|
||||||
|
mass = 100;
|
||||||
|
btTransform tr;
|
||||||
|
tr.setIdentity();
|
||||||
|
tr.setOrigin(btVector3(0, 0, 0.1+i*0.2));
|
||||||
|
btMultiBody* body = createMultiBody(mass, tr, boxShape);
|
||||||
|
}
|
||||||
|
if(0)
|
||||||
|
{
|
||||||
|
btMultiBody* mb = loadRobot("cube_small.urdf");
|
||||||
|
btTransform tr;
|
||||||
|
tr.setIdentity();
|
||||||
|
tr.setOrigin(btVector3(0, 0, 1.));
|
||||||
|
mb->setBaseWorldTransform(tr);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
btMultiBody* BlockSolverExample::createMultiBody(btScalar mass, const btTransform& trans, btCollisionShape* collisionShape)
|
||||||
|
{
|
||||||
|
btVector3 inertia;
|
||||||
|
collisionShape->calculateLocalInertia(mass, inertia);
|
||||||
|
|
||||||
|
bool canSleep = false;
|
||||||
|
bool isDynamic = mass > 0;
|
||||||
|
btMultiBody* mb = new btMultiBody(0, mass, inertia, !isDynamic, canSleep);
|
||||||
|
btMultiBodyLinkCollider* collider = new btMultiBodyLinkCollider(mb, -1);
|
||||||
|
collider->setWorldTransform(trans);
|
||||||
|
mb->setBaseWorldTransform(trans);
|
||||||
|
|
||||||
|
collider->setCollisionShape(collisionShape);
|
||||||
|
|
||||||
|
int collisionFilterGroup = isDynamic ? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||||
|
int collisionFilterMask = isDynamic ? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||||
|
|
||||||
|
|
||||||
|
this->m_dynamicsWorld->addCollisionObject(collider, collisionFilterGroup, collisionFilterMask);
|
||||||
|
mb->setBaseCollider(collider);
|
||||||
|
|
||||||
|
mb->finalizeMultiDof();
|
||||||
|
|
||||||
|
|
||||||
|
this->m_dynamicsWorld->addMultiBody(mb);
|
||||||
|
m_dynamicsWorld->forwardKinematics();
|
||||||
|
return mb;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
btMultiBody* BlockSolverExample::loadRobot(std::string filepath)
|
||||||
|
{
|
||||||
|
btMultiBody* m_multiBody = 0;
|
||||||
|
BulletURDFImporter u2b(m_guiHelper, 0, 0, 1, 0);
|
||||||
|
bool loadOk = u2b.loadURDF(filepath.c_str());// lwr / kuka.urdf");
|
||||||
|
if (loadOk)
|
||||||
|
{
|
||||||
|
int rootLinkIndex = u2b.getRootLinkIndex();
|
||||||
|
b3Printf("urdf root link index = %d\n", rootLinkIndex);
|
||||||
|
MyMultiBodyCreator creation(m_guiHelper);
|
||||||
|
btTransform identityTrans;
|
||||||
|
identityTrans.setIdentity();
|
||||||
|
ConvertURDF2Bullet(u2b, creation, identityTrans, m_dynamicsWorld, true, u2b.getPathPrefix());
|
||||||
|
for (int i = 0; i < u2b.getNumAllocatedCollisionShapes(); i++)
|
||||||
|
{
|
||||||
|
m_collisionShapes.push_back(u2b.getAllocatedCollisionShape(i));
|
||||||
|
}
|
||||||
|
m_multiBody = creation.getBulletMultiBody();
|
||||||
|
if (m_multiBody)
|
||||||
|
{
|
||||||
|
b3Printf("Root link name = %s", u2b.getLinkName(u2b.getRootLinkIndex()).c_str());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return m_multiBody;
|
||||||
|
}
|
||||||
|
|
||||||
|
CommonExampleInterface* BlockSolverExampleCreateFunc(CommonExampleOptions& options)
|
||||||
|
{
|
||||||
|
return new BlockSolverExample(options.m_guiHelper, options.m_option);
|
||||||
|
}
|
19
examples/BlockSolver/BlockSolverExample.h
Normal file
19
examples/BlockSolver/BlockSolverExample.h
Normal file
@ -0,0 +1,19 @@
|
|||||||
|
|
||||||
|
#ifndef BLOCK_SOLVER_EXAMPLE_H
|
||||||
|
#define BLOCK_SOLVER_EXAMPLE_H
|
||||||
|
|
||||||
|
enum BlockSolverOptions
|
||||||
|
{
|
||||||
|
BLOCK_SOLVER_SI=1<<0,
|
||||||
|
BLOCK_SOLVER_MLCP_PGS = 1 << 1,
|
||||||
|
BLOCK_SOLVER_MLCP_DANTZIG = 1 << 2,
|
||||||
|
BLOCK_SOLVER_BLOCK = 1 << 3,
|
||||||
|
|
||||||
|
BLOCK_SOLVER_SCENE_MB_STACK= 1 << 5,
|
||||||
|
BLOCK_SOLVER_SCENE_CHAIN = 1<< 6,
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
class CommonExampleInterface* BlockSolverExampleCreateFunc(struct CommonExampleOptions& options);
|
||||||
|
|
||||||
|
#endif //BLOCK_SOLVER_EXAMPLE_H
|
160
examples/BlockSolver/btBlockSolver.cpp
Normal file
160
examples/BlockSolver/btBlockSolver.cpp
Normal file
@ -0,0 +1,160 @@
|
|||||||
|
#include "btBlockSolver.h"
|
||||||
|
#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h"
|
||||||
|
#include "LinearMath/btQuickprof.h"
|
||||||
|
|
||||||
|
struct btBlockSolverInternalData
|
||||||
|
{
|
||||||
|
btAlignedObjectArray<btSolverBody> m_tmpSolverBodyPool;
|
||||||
|
btConstraintArray m_tmpSolverContactConstraintPool;
|
||||||
|
btConstraintArray m_tmpSolverNonContactConstraintPool;
|
||||||
|
btConstraintArray m_tmpSolverContactFrictionConstraintPool;
|
||||||
|
btConstraintArray m_tmpSolverContactRollingFrictionConstraintPool;
|
||||||
|
|
||||||
|
btAlignedObjectArray<int> m_orderTmpConstraintPool;
|
||||||
|
btAlignedObjectArray<int> m_orderNonContactConstraintPool;
|
||||||
|
btAlignedObjectArray<int> m_orderFrictionConstraintPool;
|
||||||
|
btAlignedObjectArray<btTypedConstraint::btConstraintInfo1> m_tmpConstraintSizesPool;
|
||||||
|
|
||||||
|
|
||||||
|
unsigned long m_btSeed2;
|
||||||
|
int m_fixedBodyId;
|
||||||
|
int m_maxOverrideNumSolverIterations;
|
||||||
|
btAlignedObjectArray<int> m_kinematicBodyUniqueIdToSolverBodyTable; // only used for multithreading
|
||||||
|
|
||||||
|
btSingleConstraintRowSolver m_resolveSingleConstraintRowGeneric;
|
||||||
|
btSingleConstraintRowSolver m_resolveSingleConstraintRowLowerLimit;
|
||||||
|
btSingleConstraintRowSolver m_resolveSplitPenetrationImpulse;
|
||||||
|
|
||||||
|
btBlockSolverInternalData()
|
||||||
|
:m_btSeed2(0),
|
||||||
|
m_fixedBodyId(-1),
|
||||||
|
m_maxOverrideNumSolverIterations(0),
|
||||||
|
m_resolveSingleConstraintRowGeneric(btSequentialImpulseConstraintSolver::getScalarConstraintRowSolverGeneric()),
|
||||||
|
m_resolveSingleConstraintRowLowerLimit(btSequentialImpulseConstraintSolver::getScalarConstraintRowSolverLowerLimit()),
|
||||||
|
m_resolveSplitPenetrationImpulse(btSequentialImpulseConstraintSolver::getScalarSplitPenetrationImpulseGeneric())
|
||||||
|
{
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
btBlockSolver::btBlockSolver()
|
||||||
|
{
|
||||||
|
m_data = new btBlockSolverInternalData;
|
||||||
|
}
|
||||||
|
|
||||||
|
btBlockSolver::~btBlockSolver()
|
||||||
|
{
|
||||||
|
delete m_data;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
btScalar btBlockSolver::solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher)
|
||||||
|
{
|
||||||
|
|
||||||
|
btSISolverSingleIterationData siData(m_data->m_tmpSolverBodyPool,
|
||||||
|
m_data->m_tmpSolverContactConstraintPool,
|
||||||
|
m_data->m_tmpSolverNonContactConstraintPool,
|
||||||
|
m_data->m_tmpSolverContactFrictionConstraintPool,
|
||||||
|
m_data->m_tmpSolverContactRollingFrictionConstraintPool,
|
||||||
|
m_data->m_orderTmpConstraintPool,
|
||||||
|
m_data->m_orderNonContactConstraintPool,
|
||||||
|
m_data->m_orderFrictionConstraintPool,
|
||||||
|
m_data->m_tmpConstraintSizesPool,
|
||||||
|
m_data->m_resolveSingleConstraintRowGeneric,
|
||||||
|
m_data->m_resolveSingleConstraintRowLowerLimit,
|
||||||
|
m_data->m_resolveSplitPenetrationImpulse,
|
||||||
|
m_data->m_kinematicBodyUniqueIdToSolverBodyTable,
|
||||||
|
m_data->m_btSeed2,
|
||||||
|
m_data->m_fixedBodyId,
|
||||||
|
m_data->m_maxOverrideNumSolverIterations);
|
||||||
|
|
||||||
|
m_data->m_fixedBodyId = -1;
|
||||||
|
//todo: setup sse2/4 constraint row methods
|
||||||
|
|
||||||
|
btSequentialImpulseConstraintSolver::convertBodiesInternal(siData, bodies, numBodies, info);
|
||||||
|
btSequentialImpulseConstraintSolver::convertJointsInternal(siData, constraints, numConstraints, info);
|
||||||
|
|
||||||
|
int i;
|
||||||
|
btPersistentManifold* manifold = 0;
|
||||||
|
// btCollisionObject* colObj0=0,*colObj1=0;
|
||||||
|
|
||||||
|
for (i = 0; i < numManifolds; i++)
|
||||||
|
{
|
||||||
|
manifold = manifoldPtr[i];
|
||||||
|
btSequentialImpulseConstraintSolver::convertContactInternal(siData, manifold, info);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
int numNonContactPool = siData.m_tmpSolverNonContactConstraintPool.size();
|
||||||
|
int numConstraintPool = siData.m_tmpSolverContactConstraintPool.size();
|
||||||
|
int numFrictionPool = siData.m_tmpSolverContactFrictionConstraintPool.size();
|
||||||
|
|
||||||
|
///@todo: use stack allocator for such temporarily memory, same for solver bodies/constraints
|
||||||
|
siData.m_orderNonContactConstraintPool.resizeNoInitialize(numNonContactPool);
|
||||||
|
if ((info.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
||||||
|
siData.m_orderTmpConstraintPool.resizeNoInitialize(numConstraintPool * 2);
|
||||||
|
else
|
||||||
|
siData.m_orderTmpConstraintPool.resizeNoInitialize(numConstraintPool);
|
||||||
|
|
||||||
|
siData.m_orderFrictionConstraintPool.resizeNoInitialize(numFrictionPool);
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
for (i = 0; i < numNonContactPool; i++)
|
||||||
|
{
|
||||||
|
siData.m_orderNonContactConstraintPool[i] = i;
|
||||||
|
}
|
||||||
|
for (i = 0; i < numConstraintPool; i++)
|
||||||
|
{
|
||||||
|
siData.m_orderTmpConstraintPool[i] = i;
|
||||||
|
}
|
||||||
|
for (i = 0; i < numFrictionPool; i++)
|
||||||
|
{
|
||||||
|
siData.m_orderFrictionConstraintPool[i] = i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
btScalar leastSquaresResidual = 0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
{
|
||||||
|
BT_PROFILE("solveGroupCacheFriendlyIterations");
|
||||||
|
///this is a special step to resolve penetrations (just for contacts)
|
||||||
|
btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySplitImpulseIterationsInternal(siData, bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, info, debugDrawer);
|
||||||
|
|
||||||
|
int maxIterations = siData.m_maxOverrideNumSolverIterations > info.m_numIterations ? siData.m_maxOverrideNumSolverIterations : info.m_numIterations;
|
||||||
|
|
||||||
|
for (int iteration = 0; iteration < maxIterations; iteration++)
|
||||||
|
{
|
||||||
|
leastSquaresResidual = btSequentialImpulseConstraintSolver::solveSingleIterationInternal(siData, iteration, constraints, numConstraints, info);
|
||||||
|
|
||||||
|
if (leastSquaresResidual <= info.m_leastSquaresResidualThreshold || (iteration >= (maxIterations - 1)))
|
||||||
|
{
|
||||||
|
#ifdef VERBOSE_RESIDUAL_PRINTF
|
||||||
|
printf("residual = %f at iteration #%d\n", m_leastSquaresResidual, iteration);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
btScalar res = btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyFinishInternal(siData, bodies, numBodies, info);
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void btBlockSolver::solveMultiBodyGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, btMultiBodyConstraint** multiBodyConstraints, int numMultiBodyConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher)
|
||||||
|
{
|
||||||
|
btMultiBodyConstraintSolver::solveMultiBodyGroup(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, multiBodyConstraints, numMultiBodyConstraints, info, debugDrawer, dispatcher);
|
||||||
|
}
|
||||||
|
|
||||||
|
void btBlockSolver::reset()
|
||||||
|
{
|
||||||
|
//or just set m_data->m_btSeed2=0?
|
||||||
|
delete m_data;
|
||||||
|
m_data = new btBlockSolverInternalData;
|
||||||
|
}
|
29
examples/BlockSolver/btBlockSolver.h
Normal file
29
examples/BlockSolver/btBlockSolver.h
Normal file
@ -0,0 +1,29 @@
|
|||||||
|
#ifndef BT_BLOCK_SOLVER_H
|
||||||
|
#define BT_BLOCK_SOLVER_H
|
||||||
|
|
||||||
|
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||||
|
|
||||||
|
class btBlockSolver : public btMultiBodyConstraintSolver
|
||||||
|
{
|
||||||
|
struct btBlockSolverInternalData* m_data;
|
||||||
|
|
||||||
|
public:
|
||||||
|
btBlockSolver();
|
||||||
|
virtual ~btBlockSolver();
|
||||||
|
|
||||||
|
//btRigidBody
|
||||||
|
virtual btScalar solveGroup(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, class btIDebugDraw* debugDrawer, btDispatcher* dispatcher);
|
||||||
|
|
||||||
|
//btMultibody
|
||||||
|
virtual void solveMultiBodyGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, btMultiBodyConstraint** multiBodyConstraints, int numMultiBodyConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher);
|
||||||
|
|
||||||
|
///clear internal cached data and reset random seed
|
||||||
|
virtual void reset();
|
||||||
|
|
||||||
|
virtual btConstraintSolverType getSolverType() const
|
||||||
|
{
|
||||||
|
return BT_BLOCK_SOLVER;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif //BT_BLOCK_SOLVER_H
|
@ -91,7 +91,7 @@ enum SolverEnumType
|
|||||||
NNCGSOLVER = 2,
|
NNCGSOLVER = 2,
|
||||||
DANZIGSOLVER = 3,
|
DANZIGSOLVER = 3,
|
||||||
LEMKESOLVER = 4,
|
LEMKESOLVER = 4,
|
||||||
FSSOLVER = 5,
|
|
||||||
NUM_SOLVERS = 6
|
NUM_SOLVERS = 6
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -103,7 +103,7 @@ static char GAUSSSEIDELSOLVER[] = "Gauss-Seidel Solver";
|
|||||||
static char NNCGSOLVER[] = "NNCG Solver";
|
static char NNCGSOLVER[] = "NNCG Solver";
|
||||||
static char DANZIGSOLVER[] = "Danzig Solver";
|
static char DANZIGSOLVER[] = "Danzig Solver";
|
||||||
static char LEMKESOLVER[] = "Lemke Solver";
|
static char LEMKESOLVER[] = "Lemke Solver";
|
||||||
static char FSSOLVER[] = "FeatherStone Solver";
|
|
||||||
}; // namespace SolverType
|
}; // namespace SolverType
|
||||||
|
|
||||||
static const char* solverTypes[NUM_SOLVERS];
|
static const char* solverTypes[NUM_SOLVERS];
|
||||||
@ -324,7 +324,7 @@ struct NN3DWalkersTimeWarpBase : public CommonRigidBodyBase
|
|||||||
solverTypes[2] = SolverType::NNCGSOLVER;
|
solverTypes[2] = SolverType::NNCGSOLVER;
|
||||||
solverTypes[3] = SolverType::DANZIGSOLVER;
|
solverTypes[3] = SolverType::DANZIGSOLVER;
|
||||||
solverTypes[4] = SolverType::LEMKESOLVER;
|
solverTypes[4] = SolverType::LEMKESOLVER;
|
||||||
solverTypes[5] = SolverType::FSSOLVER;
|
|
||||||
|
|
||||||
{
|
{
|
||||||
ComboBoxParams comboParams;
|
ComboBoxParams comboParams;
|
||||||
@ -499,19 +499,12 @@ struct NN3DWalkersTimeWarpBase : public CommonRigidBodyBase
|
|||||||
m_solver = new btMLCPSolver(mlcp);
|
m_solver = new btMLCPSolver(mlcp);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case FSSOLVER:
|
|
||||||
{
|
|
||||||
// b3Printf("=%s=",SolverType::FSSOLVER);
|
|
||||||
//Use the btMultiBodyConstraintSolver for Featherstone btMultiBody support
|
|
||||||
m_solver = new btMultiBodyConstraintSolver;
|
|
||||||
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (SOLVER_TYPE != FSSOLVER)
|
if (1)
|
||||||
{
|
{
|
||||||
//TODO: Set parameters for other solvers
|
//TODO: Set parameters for other solvers
|
||||||
|
|
||||||
|
@ -202,6 +202,10 @@ SET(BulletExampleBrowser_SRCS
|
|||||||
../MultiThreadedDemo/MultiThreadedDemo.h
|
../MultiThreadedDemo/MultiThreadedDemo.h
|
||||||
../MultiThreadedDemo/CommonRigidBodyMTBase.cpp
|
../MultiThreadedDemo/CommonRigidBodyMTBase.cpp
|
||||||
../MultiThreadedDemo/CommonRigidBodyMTBase.h
|
../MultiThreadedDemo/CommonRigidBodyMTBase.h
|
||||||
|
../BlockSolver/btBlockSolver.cpp
|
||||||
|
../BlockSolver/btBlockSolver.h
|
||||||
|
../BlockSolver/BlockSolverExample.cpp
|
||||||
|
../BlockSolver/BlockSolverExample.h
|
||||||
../Tutorial/Tutorial.cpp
|
../Tutorial/Tutorial.cpp
|
||||||
../Tutorial/Tutorial.h
|
../Tutorial/Tutorial.h
|
||||||
../Tutorial/Dof6ConstraintTutorial.cpp
|
../Tutorial/Dof6ConstraintTutorial.cpp
|
||||||
@ -333,7 +337,6 @@ SET(BulletExampleBrowser_SRCS
|
|||||||
../MultiBody/InvertedPendulumPDControl.cpp
|
../MultiBody/InvertedPendulumPDControl.cpp
|
||||||
../MultiBody/InvertedPendulumPDControl.h
|
../MultiBody/InvertedPendulumPDControl.h
|
||||||
../MultiBody/MultiBodyConstraintFeedback.cpp
|
../MultiBody/MultiBodyConstraintFeedback.cpp
|
||||||
../MultiBody/SerialChains.cpp
|
|
||||||
../MultiBody/MultiDofDemo.cpp
|
../MultiBody/MultiDofDemo.cpp
|
||||||
../MultiBody/MultiDofDemo.h
|
../MultiBody/MultiDofDemo.h
|
||||||
../RigidBody/RigidBodySoftContact.cpp
|
../RigidBody/RigidBodySoftContact.cpp
|
||||||
|
@ -1,5 +1,6 @@
|
|||||||
#include "ExampleEntries.h"
|
#include "ExampleEntries.h"
|
||||||
|
|
||||||
|
#include "../BlockSolver/BlockSolverExample.h"
|
||||||
#include "LinearMath/btAlignedObjectArray.h"
|
#include "LinearMath/btAlignedObjectArray.h"
|
||||||
#include "EmptyExample.h"
|
#include "EmptyExample.h"
|
||||||
#include "../RenderingExamples/RenderInstancingDemo.h"
|
#include "../RenderingExamples/RenderInstancingDemo.h"
|
||||||
@ -29,7 +30,7 @@
|
|||||||
#include "../MultiBody/MultiBodyConstraintFeedback.h"
|
#include "../MultiBody/MultiBodyConstraintFeedback.h"
|
||||||
#include "../MultiBody/MultiDofDemo.h"
|
#include "../MultiBody/MultiDofDemo.h"
|
||||||
#include "../MultiBody/InvertedPendulumPDControl.h"
|
#include "../MultiBody/InvertedPendulumPDControl.h"
|
||||||
#include "../MultiBody/SerialChains.h"
|
|
||||||
#include "../RigidBody/RigidBodySoftContact.h"
|
#include "../RigidBody/RigidBodySoftContact.h"
|
||||||
#include "../VoronoiFracture/VoronoiFractureDemo.h"
|
#include "../VoronoiFracture/VoronoiFractureDemo.h"
|
||||||
#include "../SoftDemo/SoftDemo.h"
|
#include "../SoftDemo/SoftDemo.h"
|
||||||
@ -136,8 +137,8 @@ static ExampleEntry gDefaultExamples[] =
|
|||||||
ExampleEntry(1, "Constraint Feedback", "The example shows how to receive joint reaction forces in a btMultiBody. Also the applied impulse is available for a btMultiBodyJointMotor", MultiBodyConstraintFeedbackCreateFunc),
|
ExampleEntry(1, "Constraint Feedback", "The example shows how to receive joint reaction forces in a btMultiBody. Also the applied impulse is available for a btMultiBodyJointMotor", MultiBodyConstraintFeedbackCreateFunc),
|
||||||
ExampleEntry(1, "Inverted Pendulum PD", "Keep an inverted pendulum up using open loop PD control", InvertedPendulumPDControlCreateFunc),
|
ExampleEntry(1, "Inverted Pendulum PD", "Keep an inverted pendulum up using open loop PD control", InvertedPendulumPDControlCreateFunc),
|
||||||
ExampleEntry(1, "MultiBody Soft Contact", "Using the error correction parameter (ERP) and constraint force mixing (CFM) values for contacts to simulate compliant contact.", MultiBodySoftContactCreateFunc, 0),
|
ExampleEntry(1, "MultiBody Soft Contact", "Using the error correction parameter (ERP) and constraint force mixing (CFM) values for contacts to simulate compliant contact.", MultiBodySoftContactCreateFunc, 0),
|
||||||
ExampleEntry(1, "Serial Chains", "Show colliding two serial chains using different constraint solvers.", SerialChainsCreateFunc, 0),
|
|
||||||
|
|
||||||
ExampleEntry(0, "Physics Client-Server"),
|
ExampleEntry(0, "Physics Client-Server"),
|
||||||
ExampleEntry(1, "Physics Server", "Create a physics server that communicates with a physics client over shared memory. You can connect to the server using pybullet, a PhysicsClient or a UDP/TCP Bridge.",
|
ExampleEntry(1, "Physics Server", "Create a physics server that communicates with a physics client over shared memory. You can connect to the server using pybullet, a PhysicsClient or a UDP/TCP Bridge.",
|
||||||
PhysicsServerCreateFuncBullet2),
|
PhysicsServerCreateFuncBullet2),
|
||||||
@ -150,6 +151,13 @@ static ExampleEntry gDefaultExamples[] =
|
|||||||
//
|
//
|
||||||
// ExampleEntry(1, "Physics Client (Direct)", "Create a physics client that can communicate with a physics server directly in-process.", PhysicsClientCreateFunc,eCLIENTEXAMPLE_DIRECT),
|
// ExampleEntry(1, "Physics Client (Direct)", "Create a physics client that can communicate with a physics server directly in-process.", PhysicsClientCreateFunc,eCLIENTEXAMPLE_DIRECT),
|
||||||
|
|
||||||
|
|
||||||
|
ExampleEntry(0, "BlockSolver"),
|
||||||
|
ExampleEntry(1, "Stack MultiBody SI", "Create a stack of blocks, with heavy block at the top", BlockSolverExampleCreateFunc, BLOCK_SOLVER_SCENE_MB_STACK+ BLOCK_SOLVER_SI),
|
||||||
|
ExampleEntry(1, "Stack MultiBody MLCP PGS", "Create a stack of blocks, with heavy block at the top", BlockSolverExampleCreateFunc, BLOCK_SOLVER_SCENE_MB_STACK + BLOCK_SOLVER_MLCP_PGS),
|
||||||
|
ExampleEntry(1, "Stack MultiBody MLCP Dantzig", "Create a stack of blocks, with heavy block at the top", BlockSolverExampleCreateFunc, BLOCK_SOLVER_SCENE_MB_STACK + BLOCK_SOLVER_MLCP_DANTZIG),
|
||||||
|
ExampleEntry(1, "Stack MultiBody Block", "Create a stack of blocks, with heavy block at the top", BlockSolverExampleCreateFunc, BLOCK_SOLVER_SCENE_MB_STACK + BLOCK_SOLVER_BLOCK),
|
||||||
|
|
||||||
ExampleEntry(0, "Inverse Dynamics"),
|
ExampleEntry(0, "Inverse Dynamics"),
|
||||||
ExampleEntry(1, "Inverse Dynamics URDF", "Create a btMultiBody from URDF. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc, BT_ID_LOAD_URDF),
|
ExampleEntry(1, "Inverse Dynamics URDF", "Create a btMultiBody from URDF. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc, BT_ID_LOAD_URDF),
|
||||||
ExampleEntry(1, "Inverse Dynamics Prog", "Create a btMultiBody programatically. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc, BT_ID_PROGRAMMATICALLY),
|
ExampleEntry(1, "Inverse Dynamics Prog", "Create a btMultiBody programatically. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc, BT_ID_PROGRAMMATICALLY),
|
||||||
|
@ -162,6 +162,7 @@ project "App_BulletExampleBrowser"
|
|||||||
"../Evolution/NN3DWalkers.h",
|
"../Evolution/NN3DWalkers.h",
|
||||||
"../Collision/*",
|
"../Collision/*",
|
||||||
"../RoboticsLearning/*",
|
"../RoboticsLearning/*",
|
||||||
|
"../BlockSolver/*",
|
||||||
"../Collision/Internal/*",
|
"../Collision/Internal/*",
|
||||||
"../Benchmarks/*",
|
"../Benchmarks/*",
|
||||||
"../MultiThreadedDemo/*",
|
"../MultiThreadedDemo/*",
|
||||||
|
@ -35,6 +35,7 @@ enum btConstraintSolverType
|
|||||||
BT_MLCP_SOLVER = 2,
|
BT_MLCP_SOLVER = 2,
|
||||||
BT_NNCG_SOLVER = 4,
|
BT_NNCG_SOLVER = 4,
|
||||||
BT_MULTIBODY_SOLVER = 8,
|
BT_MULTIBODY_SOLVER = 8,
|
||||||
|
BT_BLOCK_SOLVER = 16,
|
||||||
};
|
};
|
||||||
|
|
||||||
class btConstraintSolver
|
class btConstraintSolver
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -29,6 +29,68 @@ class btCollisionObject;
|
|||||||
|
|
||||||
typedef btScalar (*btSingleConstraintRowSolver)(btSolverBody&, btSolverBody&, const btSolverConstraint&);
|
typedef btScalar (*btSingleConstraintRowSolver)(btSolverBody&, btSolverBody&, const btSolverConstraint&);
|
||||||
|
|
||||||
|
struct btSISolverSingleIterationData
|
||||||
|
{
|
||||||
|
btAlignedObjectArray<btSolverBody>& m_tmpSolverBodyPool;
|
||||||
|
btConstraintArray& m_tmpSolverContactConstraintPool;
|
||||||
|
btConstraintArray& m_tmpSolverNonContactConstraintPool;
|
||||||
|
btConstraintArray& m_tmpSolverContactFrictionConstraintPool;
|
||||||
|
btConstraintArray& m_tmpSolverContactRollingFrictionConstraintPool;
|
||||||
|
|
||||||
|
btAlignedObjectArray<int>& m_orderTmpConstraintPool;
|
||||||
|
btAlignedObjectArray<int>& m_orderNonContactConstraintPool;
|
||||||
|
btAlignedObjectArray<int>& m_orderFrictionConstraintPool;
|
||||||
|
btAlignedObjectArray<btTypedConstraint::btConstraintInfo1>& m_tmpConstraintSizesPool;
|
||||||
|
unsigned long& m_seed;
|
||||||
|
|
||||||
|
btSingleConstraintRowSolver& m_resolveSingleConstraintRowGeneric;
|
||||||
|
btSingleConstraintRowSolver& m_resolveSingleConstraintRowLowerLimit;
|
||||||
|
btSingleConstraintRowSolver& m_resolveSplitPenetrationImpulse;
|
||||||
|
btAlignedObjectArray<int>& m_kinematicBodyUniqueIdToSolverBodyTable;
|
||||||
|
int& m_fixedBodyId;
|
||||||
|
int& m_maxOverrideNumSolverIterations;
|
||||||
|
int getOrInitSolverBody(btCollisionObject & body, btScalar timeStep);
|
||||||
|
static void initSolverBody(btSolverBody * solverBody, btCollisionObject * collisionObject, btScalar timeStep);
|
||||||
|
int getSolverBody(btCollisionObject& body) const;
|
||||||
|
|
||||||
|
|
||||||
|
btSISolverSingleIterationData(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool,
|
||||||
|
btConstraintArray& tmpSolverContactConstraintPool,
|
||||||
|
btConstraintArray& tmpSolverNonContactConstraintPool,
|
||||||
|
btConstraintArray& tmpSolverContactFrictionConstraintPool,
|
||||||
|
btConstraintArray& tmpSolverContactRollingFrictionConstraintPool,
|
||||||
|
btAlignedObjectArray<int>& orderTmpConstraintPool,
|
||||||
|
btAlignedObjectArray<int>& orderNonContactConstraintPool,
|
||||||
|
btAlignedObjectArray<int>& orderFrictionConstraintPool,
|
||||||
|
btAlignedObjectArray<btTypedConstraint::btConstraintInfo1>& tmpConstraintSizesPool,
|
||||||
|
btSingleConstraintRowSolver& resolveSingleConstraintRowGeneric,
|
||||||
|
btSingleConstraintRowSolver& resolveSingleConstraintRowLowerLimit,
|
||||||
|
btSingleConstraintRowSolver& resolveSplitPenetrationImpulse,
|
||||||
|
btAlignedObjectArray<int>& kinematicBodyUniqueIdToSolverBodyTable,
|
||||||
|
unsigned long& seed,
|
||||||
|
int& fixedBodyId,
|
||||||
|
int& maxOverrideNumSolverIterations
|
||||||
|
)
|
||||||
|
:m_tmpSolverBodyPool(tmpSolverBodyPool),
|
||||||
|
m_tmpSolverContactConstraintPool(tmpSolverContactConstraintPool),
|
||||||
|
m_tmpSolverNonContactConstraintPool(tmpSolverNonContactConstraintPool),
|
||||||
|
m_tmpSolverContactFrictionConstraintPool(tmpSolverContactFrictionConstraintPool),
|
||||||
|
m_tmpSolverContactRollingFrictionConstraintPool(tmpSolverContactRollingFrictionConstraintPool),
|
||||||
|
m_orderTmpConstraintPool(orderTmpConstraintPool),
|
||||||
|
m_orderNonContactConstraintPool(orderNonContactConstraintPool),
|
||||||
|
m_orderFrictionConstraintPool(orderFrictionConstraintPool),
|
||||||
|
m_tmpConstraintSizesPool(tmpConstraintSizesPool),
|
||||||
|
m_resolveSingleConstraintRowGeneric(resolveSingleConstraintRowGeneric),
|
||||||
|
m_resolveSingleConstraintRowLowerLimit(resolveSingleConstraintRowLowerLimit),
|
||||||
|
m_resolveSplitPenetrationImpulse(resolveSplitPenetrationImpulse),
|
||||||
|
m_kinematicBodyUniqueIdToSolverBodyTable(kinematicBodyUniqueIdToSolverBodyTable),
|
||||||
|
m_seed(seed),
|
||||||
|
m_fixedBodyId(fixedBodyId),
|
||||||
|
m_maxOverrideNumSolverIterations(maxOverrideNumSolverIterations)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
///The btSequentialImpulseConstraintSolver is a fast SIMD implementation of the Projected Gauss Seidel (iterative LCP) method.
|
///The btSequentialImpulseConstraintSolver is a fast SIMD implementation of the Projected Gauss Seidel (iterative LCP) method.
|
||||||
ATTRIBUTE_ALIGNED16(class)
|
ATTRIBUTE_ALIGNED16(class)
|
||||||
btSequentialImpulseConstraintSolver : public btConstraintSolver
|
btSequentialImpulseConstraintSolver : public btConstraintSolver
|
||||||
@ -64,26 +126,26 @@ protected:
|
|||||||
btScalar m_leastSquaresResidual;
|
btScalar m_leastSquaresResidual;
|
||||||
|
|
||||||
void setupFrictionConstraint(btSolverConstraint & solverConstraint, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB,
|
void setupFrictionConstraint(btSolverConstraint & solverConstraint, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB,
|
||||||
btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2,
|
btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2,
|
||||||
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation,
|
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation,
|
||||||
const btContactSolverInfo& infoGlobal,
|
const btContactSolverInfo& infoGlobal,
|
||||||
btScalar desiredVelocity = 0., btScalar cfmSlip = 0.);
|
btScalar desiredVelocity = 0., btScalar cfmSlip = 0.);
|
||||||
|
|
||||||
void setupTorsionalFrictionConstraint(btSolverConstraint & solverConstraint, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB,
|
void setupTorsionalFrictionConstraint(btSolverConstraint & solverConstraint, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB,
|
||||||
btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2,
|
btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2,
|
||||||
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation,
|
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation,
|
||||||
btScalar desiredVelocity = 0., btScalar cfmSlip = 0.);
|
btScalar desiredVelocity = 0., btScalar cfmSlip = 0.);
|
||||||
|
|
||||||
btSolverConstraint& addFrictionConstraint(const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity = 0., btScalar cfmSlip = 0.);
|
btSolverConstraint& addFrictionConstraint(const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity = 0., btScalar cfmSlip = 0.);
|
||||||
btSolverConstraint& addTorsionalFrictionConstraint(const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint& cp, btScalar torsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity = 0, btScalar cfmSlip = 0.f);
|
btSolverConstraint& addTorsionalFrictionConstraint(const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint& cp, btScalar torsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity = 0, btScalar cfmSlip = 0.f);
|
||||||
|
|
||||||
void setupContactConstraint(btSolverConstraint & solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp,
|
void setupContactConstraint(btSolverConstraint & solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp,
|
||||||
const btContactSolverInfo& infoGlobal, btScalar& relaxation, const btVector3& rel_pos1, const btVector3& rel_pos2);
|
const btContactSolverInfo& infoGlobal, btScalar& relaxation, const btVector3& rel_pos1, const btVector3& rel_pos2);
|
||||||
|
|
||||||
static void applyAnisotropicFriction(btCollisionObject * colObj, btVector3 & frictionDirection, int frictionMode);
|
static void applyAnisotropicFriction(btCollisionObject * colObj, btVector3 & frictionDirection, int frictionMode);
|
||||||
|
|
||||||
void setFrictionConstraintImpulse(btSolverConstraint & solverConstraint, int solverBodyIdA, int solverBodyIdB,
|
void setFrictionConstraintImpulse(btSolverConstraint & solverConstraint, int solverBodyIdA, int solverBodyIdB,
|
||||||
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal);
|
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal);
|
||||||
|
|
||||||
///m_btSeed2 is used for re-arranging the constraint rows. improves convergence/quality of friction
|
///m_btSeed2 is used for re-arranging the constraint rows. improves convergence/quality of friction
|
||||||
unsigned long m_btSeed2;
|
unsigned long m_btSeed2;
|
||||||
@ -97,6 +159,7 @@ protected:
|
|||||||
virtual void convertJoints(btTypedConstraint * *constraints, int numConstraints, const btContactSolverInfo& infoGlobal);
|
virtual void convertJoints(btTypedConstraint * *constraints, int numConstraints, const btContactSolverInfo& infoGlobal);
|
||||||
void convertJoint(btSolverConstraint * currentConstraintRow, btTypedConstraint * constraint, const btTypedConstraint::btConstraintInfo1& info1, int solverBodyIdA, int solverBodyIdB, const btContactSolverInfo& infoGlobal);
|
void convertJoint(btSolverConstraint * currentConstraintRow, btTypedConstraint * constraint, const btTypedConstraint::btConstraintInfo1& info1, int solverBodyIdA, int solverBodyIdB, const btContactSolverInfo& infoGlobal);
|
||||||
|
|
||||||
|
|
||||||
virtual void convertBodies(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
virtual void convertBodies(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||||
|
|
||||||
btScalar resolveSplitPenetrationSIMD(btSolverBody & bodyA, btSolverBody & bodyB, const btSolverConstraint& contactConstraint)
|
btScalar resolveSplitPenetrationSIMD(btSolverBody & bodyA, btSolverBody & bodyB, const btSolverConstraint& contactConstraint)
|
||||||
@ -122,7 +185,8 @@ protected:
|
|||||||
return m_resolveSplitPenetrationImpulse(bodyA, bodyB, contactConstraint);
|
return m_resolveSplitPenetrationImpulse(bodyA, bodyB, contactConstraint);
|
||||||
}
|
}
|
||||||
|
|
||||||
protected:
|
public:
|
||||||
|
|
||||||
void writeBackContacts(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
void writeBackContacts(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
||||||
void writeBackJoints(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
void writeBackJoints(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
||||||
void writeBackBodies(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
void writeBackBodies(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
||||||
@ -130,6 +194,7 @@ protected:
|
|||||||
virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||||
virtual btScalar solveSingleIteration(int iteration, btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
virtual btScalar solveSingleIteration(int iteration, btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||||
|
|
||||||
|
|
||||||
virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
virtual btScalar solveGroupCacheFriendlySetup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||||
virtual btScalar solveGroupCacheFriendlyIterations(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
virtual btScalar solveGroupCacheFriendlyIterations(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||||
|
|
||||||
@ -141,13 +206,52 @@ public:
|
|||||||
|
|
||||||
virtual btScalar solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher);
|
virtual btScalar solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher);
|
||||||
|
|
||||||
|
static btScalar solveSingleIterationInternal(btSISolverSingleIterationData& siData, int iteration, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal);
|
||||||
|
static void convertBodiesInternal(btSISolverSingleIterationData& siData, btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||||
|
static void convertJointsInternal(btSISolverSingleIterationData& siData, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal);
|
||||||
|
static void convertContactInternal(btSISolverSingleIterationData& siData, btPersistentManifold * manifold, const btContactSolverInfo& infoGlobal);
|
||||||
|
static void setupContactConstraintInternal(btSISolverSingleIterationData& siData, btSolverConstraint& solverConstraint, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp, const btContactSolverInfo& infoGlobal, btScalar& relaxation,
|
||||||
|
const btVector3& rel_pos1, const btVector3& rel_pos2);
|
||||||
|
static btScalar restitutionCurveInternal(btScalar rel_vel, btScalar restitution, btScalar velocityThreshold);
|
||||||
|
static btSolverConstraint& addTorsionalFrictionConstraintInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btConstraintArray& tmpSolverContactRollingFrictionConstraintPool, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, btScalar desiredVelocity = 0, btScalar cfmSlip = 0.);
|
||||||
|
static void setupTorsionalFrictionConstraintInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btSolverConstraint& solverConstraint, const btVector3& normalAxis1, int solverBodyIdA, int solverBodyIdB,
|
||||||
|
btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2,
|
||||||
|
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation,
|
||||||
|
btScalar desiredVelocity, btScalar cfmSlip);
|
||||||
|
static void setupFrictionConstraintInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btSolverConstraint& solverConstraint, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity, btScalar cfmSlip);
|
||||||
|
static btSolverConstraint& addFrictionConstraintInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btConstraintArray& tmpSolverContactFrictionConstraintPool, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB, int frictionIndex, btManifoldPoint& cp, const btVector3& rel_pos1, const btVector3& rel_pos2, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity = 0., btScalar cfmSlip = 0.);
|
||||||
|
static void setFrictionConstraintImpulseInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btConstraintArray& tmpSolverContactFrictionConstraintPool,
|
||||||
|
|
||||||
|
btSolverConstraint& solverConstraint,
|
||||||
|
int solverBodyIdA, int solverBodyIdB,
|
||||||
|
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal);
|
||||||
|
static void convertJointInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool,
|
||||||
|
int& maxOverrideNumSolverIterations,
|
||||||
|
btSolverConstraint* currentConstraintRow,
|
||||||
|
btTypedConstraint* constraint,
|
||||||
|
const btTypedConstraint::btConstraintInfo1& info1,
|
||||||
|
int solverBodyIdA,
|
||||||
|
int solverBodyIdB,
|
||||||
|
const btContactSolverInfo& infoGlobal);
|
||||||
|
|
||||||
|
static btScalar solveGroupCacheFriendlyFinishInternal(btSISolverSingleIterationData& siData, btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||||
|
|
||||||
|
static void writeBackContactsInternal(btConstraintArray& tmpSolverContactConstraintPool, btConstraintArray& tmpSolverContactFrictionConstraintPool, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
||||||
|
|
||||||
|
static void writeBackJointsInternal(btConstraintArray& tmpSolverNonContactConstraintPool, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
||||||
|
static void writeBackBodiesInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal);
|
||||||
|
static void solveGroupCacheFriendlySplitImpulseIterationsInternal(btSISolverSingleIterationData& siData, btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||||
|
|
||||||
|
|
||||||
///clear internal cached data and reset random seed
|
///clear internal cached data and reset random seed
|
||||||
virtual void reset();
|
virtual void reset();
|
||||||
|
|
||||||
unsigned long btRand2();
|
unsigned long btRand2();
|
||||||
|
|
||||||
int btRandInt2(int n);
|
int btRandInt2(int n);
|
||||||
|
|
||||||
|
static unsigned long btRand2a(unsigned long& seed);
|
||||||
|
static int btRandInt2a(int n, unsigned long& seed);
|
||||||
|
|
||||||
void setRandSeed(unsigned long seed)
|
void setRandSeed(unsigned long seed)
|
||||||
{
|
{
|
||||||
m_btSeed2 = seed;
|
m_btSeed2 = seed;
|
||||||
@ -180,14 +284,18 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
///Various implementations of solving a single constraint row using a generic equality constraint, using scalar reference, SSE2 or SSE4
|
///Various implementations of solving a single constraint row using a generic equality constraint, using scalar reference, SSE2 or SSE4
|
||||||
btSingleConstraintRowSolver getScalarConstraintRowSolverGeneric();
|
static btSingleConstraintRowSolver getScalarConstraintRowSolverGeneric();
|
||||||
btSingleConstraintRowSolver getSSE2ConstraintRowSolverGeneric();
|
static btSingleConstraintRowSolver getSSE2ConstraintRowSolverGeneric();
|
||||||
btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverGeneric();
|
static btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverGeneric();
|
||||||
|
|
||||||
///Various implementations of solving a single constraint row using an inequality (lower limit) constraint, using scalar reference, SSE2 or SSE4
|
///Various implementations of solving a single constraint row using an inequality (lower limit) constraint, using scalar reference, SSE2 or SSE4
|
||||||
btSingleConstraintRowSolver getScalarConstraintRowSolverLowerLimit();
|
static btSingleConstraintRowSolver getScalarConstraintRowSolverLowerLimit();
|
||||||
btSingleConstraintRowSolver getSSE2ConstraintRowSolverLowerLimit();
|
static btSingleConstraintRowSolver getSSE2ConstraintRowSolverLowerLimit();
|
||||||
btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverLowerLimit();
|
static btSingleConstraintRowSolver getSSE4_1ConstraintRowSolverLowerLimit();
|
||||||
|
|
||||||
|
static btSingleConstraintRowSolver getScalarSplitPenetrationImpulseGeneric();
|
||||||
|
static btSingleConstraintRowSolver getSSE2SplitPenetrationImpulseGeneric();
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif //BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_H
|
#endif //BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_H
|
@ -156,7 +156,7 @@ protected:
|
|||||||
btTypedConstraint** constraints,
|
btTypedConstraint** constraints,
|
||||||
int numConstraints,
|
int numConstraints,
|
||||||
const btContactSolverInfo& infoGlobal,
|
const btContactSolverInfo& infoGlobal,
|
||||||
btIDebugDraw* debugDrawer) BT_OVERRIDE;
|
btIDebugDraw* debugDrawer) ;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
BT_DECLARE_ALIGNED_ALLOCATOR()
|
BT_DECLARE_ALIGNED_ALLOCATOR()
|
||||||
|
Loading…
Reference in New Issue
Block a user