remove src/BulletDynamics/Featherstone/btMultiBodyBlockConstraintSolver.cpp and examples/ConstraintSolvers/* code
revert changes to btMultiBodyConstraintSolver/btSequentialImpulseConstraintSolver related to btMultiBodyBlockConstraintSolver
This commit is contained in:
@@ -1,26 +1,13 @@
|
||||
#include "BlockSolverExample.h"
|
||||
#include "../OpenGLWindow/SimpleOpenGL3App.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
|
||||
#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h"
|
||||
#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h"
|
||||
|
||||
#include "BulletDynamics/Featherstone/btMultiBody.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLink.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h"
|
||||
#include "btBlockSolver.h"
|
||||
|
||||
#include "../OpenGLWindow/GLInstancingRenderer.h"
|
||||
#include "BulletCollision/CollisionShapes/btShapeHull.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
|
||||
@@ -36,29 +23,24 @@ public:
|
||||
|
||||
virtual void resetCamera()
|
||||
{
|
||||
float dist = 1;
|
||||
float dist = 3;
|
||||
float pitch = -35;
|
||||
float yaw = 50;
|
||||
float targetPos[3] = {-3, 2.8, -2.5};
|
||||
float targetPos[3] = {0, 0, .1};
|
||||
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
|
||||
}
|
||||
|
||||
btMultiBody* createFeatherstoneMultiBody(class btMultiBodyDynamicsWorld* world, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical = false, bool fixedBase = false);
|
||||
void createGround(const btVector3& halfExtents = btVector3(50, 50, 50), btScalar zOffSet = btScalar(-1.55));
|
||||
void addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents);
|
||||
void createMultiBodyStack();
|
||||
btMultiBody* createMultiBody(btScalar mass, const btTransform& trans, btCollisionShape* collisionShape);
|
||||
btMultiBody* loadRobot(std::string filepath);
|
||||
};
|
||||
|
||||
static bool g_fixedBase = true;
|
||||
static bool g_firstInit = true;
|
||||
static float scaling = 0.4f;
|
||||
static float friction = 1.;
|
||||
|
||||
|
||||
BlockSolverExample::BlockSolverExample(GUIHelperInterface* helper, int option)
|
||||
: CommonMultiBodyBase(helper),
|
||||
m_option(option)
|
||||
{
|
||||
m_guiHelper->setUpAxis(1);
|
||||
m_guiHelper->setUpAxis(2);
|
||||
}
|
||||
|
||||
BlockSolverExample::~BlockSolverExample()
|
||||
@@ -69,20 +51,13 @@ BlockSolverExample::~BlockSolverExample()
|
||||
void BlockSolverExample::stepSimulation(float deltaTime)
|
||||
{
|
||||
//use a smaller internal timestep, there are stability issues
|
||||
float internalTimeStep = 1. / 240.f;
|
||||
btScalar internalTimeStep = 1./240.f;
|
||||
m_dynamicsWorld->stepSimulation(deltaTime, 10, internalTimeStep);
|
||||
}
|
||||
|
||||
void BlockSolverExample::initPhysics()
|
||||
{
|
||||
m_guiHelper->setUpAxis(1);
|
||||
|
||||
if (g_firstInit)
|
||||
{
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraDistance(btScalar(10. * scaling));
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraPitch(50);
|
||||
g_firstInit = false;
|
||||
}
|
||||
|
||||
///collision configuration contains default setup for memory, collision setup
|
||||
m_collisionConfiguration = new btDefaultCollisionConfiguration();
|
||||
|
||||
@@ -91,7 +66,7 @@ void BlockSolverExample::initPhysics()
|
||||
|
||||
m_broadphase = new btDbvtBroadphase();
|
||||
|
||||
|
||||
|
||||
btMLCPSolverInterface* mlcp;
|
||||
if (m_option&BLOCK_SOLVER_SI)
|
||||
{
|
||||
@@ -117,261 +92,125 @@ void BlockSolverExample::initPhysics()
|
||||
{
|
||||
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, -10, 0));
|
||||
m_dynamicsWorld->getSolverInfo().m_globalCfm = btScalar(1e-4); //todo: what value is good?
|
||||
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();
|
||||
}
|
||||
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
/////////////////////////////////////////////////////////////////
|
||||
|
||||
bool damping = true;
|
||||
bool gyro = true;
|
||||
int numLinks = 5;
|
||||
bool spherical = true; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals
|
||||
bool multibodyOnly = true; //false
|
||||
bool canSleep = true;
|
||||
bool selfCollide = true;
|
||||
btVector3 linkHalfExtents(0.05, 0.37, 0.1);
|
||||
btVector3 baseHalfExtents(0.05, 0.37, 0.1);
|
||||
|
||||
btMultiBody* mbC1 = createFeatherstoneMultiBody(world, numLinks, btVector3(-0.4f, 3.f, 0.f), linkHalfExtents, baseHalfExtents, spherical, g_fixedBase);
|
||||
btMultiBody* mbC2 = createFeatherstoneMultiBody(world, numLinks, btVector3(-0.4f, 3.0f, 0.5f), linkHalfExtents, baseHalfExtents, spherical, g_fixedBase);
|
||||
|
||||
mbC1->setCanSleep(canSleep);
|
||||
mbC1->setHasSelfCollision(selfCollide);
|
||||
mbC1->setUseGyroTerm(gyro);
|
||||
|
||||
if (!damping)
|
||||
{
|
||||
mbC1->setLinearDamping(0.f);
|
||||
mbC1->setAngularDamping(0.f);
|
||||
}
|
||||
else
|
||||
{
|
||||
mbC1->setLinearDamping(0.1f);
|
||||
mbC1->setAngularDamping(0.9f);
|
||||
}
|
||||
//
|
||||
m_dynamicsWorld->setGravity(btVector3(0, -9.81, 0));
|
||||
//////////////////////////////////////////////
|
||||
if (numLinks > 0)
|
||||
{
|
||||
btScalar q0 = 45.f * SIMD_PI / 180.f;
|
||||
if (!spherical)
|
||||
{
|
||||
mbC1->setJointPosMultiDof(0, &q0);
|
||||
}
|
||||
else
|
||||
{
|
||||
btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0);
|
||||
quat0.normalize();
|
||||
mbC1->setJointPosMultiDof(0, quat0);
|
||||
}
|
||||
}
|
||||
///
|
||||
addColliders(mbC1, world, baseHalfExtents, linkHalfExtents);
|
||||
|
||||
mbC2->setCanSleep(canSleep);
|
||||
mbC2->setHasSelfCollision(selfCollide);
|
||||
mbC2->setUseGyroTerm(gyro);
|
||||
//
|
||||
if (!damping)
|
||||
{
|
||||
mbC2->setLinearDamping(0.f);
|
||||
mbC2->setAngularDamping(0.f);
|
||||
}
|
||||
else
|
||||
{
|
||||
mbC2->setLinearDamping(0.1f);
|
||||
mbC2->setAngularDamping(0.9f);
|
||||
}
|
||||
//
|
||||
m_dynamicsWorld->setGravity(btVector3(0, -9.81, 0));
|
||||
//////////////////////////////////////////////
|
||||
if (numLinks > 0)
|
||||
{
|
||||
btScalar q0 = -45.f * SIMD_PI / 180.f;
|
||||
if (!spherical)
|
||||
{
|
||||
mbC2->setJointPosMultiDof(0, &q0);
|
||||
}
|
||||
else
|
||||
{
|
||||
btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0);
|
||||
quat0.normalize();
|
||||
mbC2->setJointPosMultiDof(0, quat0);
|
||||
}
|
||||
}
|
||||
///
|
||||
addColliders(mbC2, world, baseHalfExtents, linkHalfExtents);
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
btScalar groundHeight = -51.55;
|
||||
btScalar mass(0.);
|
||||
|
||||
//rigidbody is dynamic if and only if mass is non zero, otherwise static
|
||||
bool isDynamic = (mass != 0.f);
|
||||
|
||||
btVector3 localInertia(0, 0, 0);
|
||||
|
||||
|
||||
createGround();
|
||||
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
}
|
||||
|
||||
btMultiBody* BlockSolverExample::createFeatherstoneMultiBody(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool fixedBase)
|
||||
|
||||
void BlockSolverExample::createMultiBodyStack()
|
||||
{
|
||||
//init the base
|
||||
btVector3 baseInertiaDiag(0.f, 0.f, 0.f);
|
||||
float baseMass = 1.f;
|
||||
|
||||
if (baseMass)
|
||||
///create a few basic rigid bodies
|
||||
bool loadPlaneFromURDF = false;
|
||||
if (loadPlaneFromURDF)
|
||||
{
|
||||
btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2]));
|
||||
pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag);
|
||||
delete pTempBox;
|
||||
btMultiBody* mb = loadRobot("plane.urdf");
|
||||
printf("!\n");
|
||||
}
|
||||
|
||||
bool canSleep = false;
|
||||
|
||||
btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, fixedBase, canSleep);
|
||||
|
||||
btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f);
|
||||
pMultiBody->setBasePos(basePosition);
|
||||
pMultiBody->setWorldToBaseRot(baseOriQuat);
|
||||
btVector3 vel(0, 0, 0);
|
||||
|
||||
//init the links
|
||||
btVector3 hingeJointAxis(1, 0, 0);
|
||||
float linkMass = 1.f;
|
||||
btVector3 linkInertiaDiag(0.f, 0.f, 0.f);
|
||||
|
||||
btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2]));
|
||||
pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag);
|
||||
delete pTempBox;
|
||||
|
||||
//y-axis assumed up
|
||||
btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset
|
||||
btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset
|
||||
btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset
|
||||
|
||||
//////
|
||||
btScalar q0 = 0.f * SIMD_PI / 180.f;
|
||||
btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0);
|
||||
quat0.normalize();
|
||||
/////
|
||||
|
||||
for (int i = 0; i < numLinks; ++i)
|
||||
else
|
||||
{
|
||||
if (!spherical)
|
||||
pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, true);
|
||||
else
|
||||
//pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false);
|
||||
pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, true);
|
||||
}
|
||||
|
||||
pMultiBody->finalizeMultiDof();
|
||||
|
||||
///
|
||||
pWorld->addMultiBody(pMultiBody);
|
||||
///
|
||||
return pMultiBody;
|
||||
}
|
||||
|
||||
void BlockSolverExample::createGround(const btVector3& halfExtents, btScalar zOffSet)
|
||||
{
|
||||
btCollisionShape* groundShape = new btBoxShape(halfExtents);
|
||||
m_collisionShapes.push_back(groundShape);
|
||||
|
||||
// rigidbody is dynamic if and only if mass is non zero, otherwise static
|
||||
btScalar mass(0.);
|
||||
const bool isDynamic = (mass != 0.f);
|
||||
|
||||
btVector3 localInertia(0, 0, 0);
|
||||
if (isDynamic)
|
||||
groundShape->calculateLocalInertia(mass, localInertia);
|
||||
|
||||
// using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
|
||||
btTransform groundTransform;
|
||||
groundTransform.setIdentity();
|
||||
groundTransform.setOrigin(btVector3(0, -halfExtents.z() + zOffSet, 0));
|
||||
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
|
||||
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
|
||||
btRigidBody* body = new btRigidBody(rbInfo);
|
||||
|
||||
// add the body to the dynamics world
|
||||
m_dynamicsWorld->addRigidBody(body, 1, 1 + 2);
|
||||
}
|
||||
|
||||
void BlockSolverExample::addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents)
|
||||
{
|
||||
btAlignedObjectArray<btQuaternion> world_to_local;
|
||||
world_to_local.resize(pMultiBody->getNumLinks() + 1);
|
||||
|
||||
btAlignedObjectArray<btVector3> local_origin;
|
||||
local_origin.resize(pMultiBody->getNumLinks() + 1);
|
||||
world_to_local[0] = pMultiBody->getWorldToBaseRot();
|
||||
local_origin[0] = pMultiBody->getBasePos();
|
||||
|
||||
{
|
||||
btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()};
|
||||
|
||||
if (1)
|
||||
{
|
||||
btCollisionShape* box = new btBoxShape(baseHalfExtents);
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1);
|
||||
col->setCollisionShape(box);
|
||||
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr.setOrigin(local_origin[0]);
|
||||
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
|
||||
col->setWorldTransform(tr);
|
||||
|
||||
pWorld->addCollisionObject(col, 2, 1 + 2);
|
||||
|
||||
col->setFriction(friction);
|
||||
pMultiBody->setBaseCollider(col);
|
||||
}
|
||||
}
|
||||
|
||||
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
|
||||
{
|
||||
const int parent = pMultiBody->getParent(i);
|
||||
world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1];
|
||||
local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i)));
|
||||
}
|
||||
|
||||
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
|
||||
{
|
||||
btVector3 posr = local_origin[i + 1];
|
||||
|
||||
btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()};
|
||||
|
||||
btCollisionShape* box = new btBoxShape(linkHalfExtents);
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i);
|
||||
|
||||
col->setCollisionShape(box);
|
||||
btBoxShape* groundShape = createBoxShape(btVector3(btScalar(50.), btScalar(50.), btScalar(50.)));
|
||||
m_collisionShapes.push_back(groundShape);
|
||||
btScalar mass = 0;
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr.setOrigin(posr);
|
||||
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
|
||||
col->setWorldTransform(tr);
|
||||
col->setFriction(friction);
|
||||
pWorld->addCollisionObject(col, 2, 1 + 2);
|
||||
|
||||
pMultiBody->getLink(i).m_collider = col;
|
||||
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)
|
||||
|
||||
@@ -9,7 +9,7 @@ enum BlockSolverOptions
|
||||
BLOCK_SOLVER_MLCP_DANTZIG = 1 << 2,
|
||||
BLOCK_SOLVER_BLOCK = 1 << 3,
|
||||
|
||||
BLOCK_SOLVER_SCENE_STACK= 1 << 5,
|
||||
BLOCK_SOLVER_SCENE_MB_STACK= 1 << 5,
|
||||
BLOCK_SOLVER_SCENE_CHAIN = 1<< 6,
|
||||
|
||||
};
|
||||
|
||||
@@ -128,7 +128,6 @@ btScalar btBlockSolver::solveGroup(btCollisionObject * *bodies, int numBodies, b
|
||||
int maxIterations = siData.m_maxOverrideNumSolverIterations > info.m_numIterations ? siData.m_maxOverrideNumSolverIterations : info.m_numIterations;
|
||||
|
||||
for (int iteration = 0; iteration < maxIterations; iteration++)
|
||||
//for ( int iteration = maxIterations-1 ; iteration >= 0;iteration--)
|
||||
{
|
||||
leastSquaresResidual = btSequentialImpulseConstraintSolver::solveSingleIterationInternal(siData, iteration, constraints, numConstraints, info);
|
||||
|
||||
@@ -150,7 +149,7 @@ btScalar btBlockSolver::solveGroup(btCollisionObject * *bodies, int numBodies, b
|
||||
|
||||
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);
|
||||
btMultiBodyConstraintSolver::solveMultiBodyGroup(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, multiBodyConstraints, numMultiBodyConstraints, info, debugDrawer, dispatcher);
|
||||
}
|
||||
|
||||
void btBlockSolver::reset()
|
||||
|
||||
@@ -1,335 +0,0 @@
|
||||
#include "BoxStacks.h"
|
||||
#include "../OpenGLWindow/SimpleOpenGL3App.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
|
||||
#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h"
|
||||
#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h"
|
||||
|
||||
#include "BulletDynamics/Featherstone/btMultiBody.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyBlockConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLink.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h"
|
||||
|
||||
#include "../OpenGLWindow/GLInstancingRenderer.h"
|
||||
#include "BulletCollision/CollisionShapes/btShapeHull.h"
|
||||
|
||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||
|
||||
class BoxStacks : public CommonMultiBodyBase
|
||||
{
|
||||
public:
|
||||
BoxStacks(GUIHelperInterface* helper);
|
||||
virtual ~BoxStacks();
|
||||
|
||||
virtual void initPhysics();
|
||||
|
||||
virtual void stepSimulation(float deltaTime);
|
||||
|
||||
virtual void resetCamera()
|
||||
{
|
||||
float dist = 1;
|
||||
float pitch = -35;
|
||||
float yaw = 50;
|
||||
float targetPos[3] = {-3, 2.8, -2.5};
|
||||
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
|
||||
}
|
||||
|
||||
void createBoxStack(int numBoxes, btScalar centerX, btScalar centerY);
|
||||
btMultiBody* createFeatherstoneMultiBody(class btMultiBodyDynamicsWorld* world, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical = false, bool fixedBase = false);
|
||||
void createGround(const btVector3& halfExtents = btVector3(50, 50, 50), btScalar zOffSet = btScalar(-1.55));
|
||||
void addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents);
|
||||
};
|
||||
|
||||
static bool g_fixedBase = true;
|
||||
static bool g_firstInit = true;
|
||||
static float scaling = 0.4f;
|
||||
static float friction = 1.;
|
||||
static int g_constraintSolverType = 0;
|
||||
|
||||
BoxStacks::BoxStacks(GUIHelperInterface* helper)
|
||||
: CommonMultiBodyBase(helper)
|
||||
{
|
||||
m_guiHelper->setUpAxis(1);
|
||||
}
|
||||
|
||||
BoxStacks::~BoxStacks()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void BoxStacks::stepSimulation(float deltaTime)
|
||||
{
|
||||
//use a smaller internal timestep, there are stability issues
|
||||
float internalTimeStep = 1. / 240.f;
|
||||
m_dynamicsWorld->stepSimulation(deltaTime, 10, internalTimeStep);
|
||||
}
|
||||
|
||||
void BoxStacks::initPhysics()
|
||||
{
|
||||
m_guiHelper->setUpAxis(1);
|
||||
|
||||
if (g_firstInit)
|
||||
{
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraDistance(btScalar(10. * scaling));
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraPitch(50);
|
||||
g_firstInit = false;
|
||||
}
|
||||
///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();
|
||||
|
||||
if (g_constraintSolverType == 3)
|
||||
{
|
||||
g_constraintSolverType = 0;
|
||||
g_fixedBase = !g_fixedBase;
|
||||
}
|
||||
|
||||
btMLCPSolverInterface* mlcp;
|
||||
switch (g_constraintSolverType++)
|
||||
{
|
||||
case 0:
|
||||
m_solver = new btMultiBodyConstraintSolver;
|
||||
b3Printf("Constraint Solver: Sequential Impulse");
|
||||
break;
|
||||
case 1:
|
||||
mlcp = new btSolveProjectedGaussSeidel();
|
||||
m_solver = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||
b3Printf("Constraint Solver: MLCP + PGS");
|
||||
break;
|
||||
default:
|
||||
mlcp = new btDantzigSolver();
|
||||
m_solver = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||
b3Printf("Constraint Solver: MLCP + Dantzig");
|
||||
break;
|
||||
}
|
||||
m_solver = new btMultiBodyBlockConstraintSolver();
|
||||
|
||||
btMultiBodyDynamicsWorld* world = new btMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration);
|
||||
m_dynamicsWorld = world;
|
||||
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
|
||||
m_dynamicsWorld->setGravity(btVector3(btScalar(0), btScalar(-9.81), btScalar(0)));
|
||||
m_dynamicsWorld->getSolverInfo().m_globalCfm = btScalar(1e-4); //todo: what value is good?
|
||||
|
||||
/// Create a few basic rigid bodies
|
||||
btVector3 groundHalfExtents(50, 50, 50);
|
||||
btCollisionShape* groundShape = new btBoxShape(groundHalfExtents);
|
||||
|
||||
m_collisionShapes.push_back(groundShape);
|
||||
|
||||
btTransform groundTransform;
|
||||
groundTransform.setIdentity();
|
||||
groundTransform.setOrigin(btVector3(0, -50, 00));
|
||||
|
||||
btVector3 linkHalfExtents(btScalar(0.05), btScalar(0.37), btScalar(0.1));
|
||||
btVector3 baseHalfExtents(btScalar(0.05), btScalar(0.37), btScalar(0.1));
|
||||
|
||||
createBoxStack(1, 0, 0);
|
||||
|
||||
btScalar groundHeight = btScalar(-51.55);
|
||||
btScalar mass = btScalar(0.0);
|
||||
|
||||
btVector3 localInertia(0, 0, 0);
|
||||
groundShape->calculateLocalInertia(mass, localInertia);
|
||||
|
||||
// Using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
|
||||
groundTransform.setIdentity();
|
||||
groundTransform.setOrigin(btVector3(0, groundHeight, 0));
|
||||
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
|
||||
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
|
||||
btRigidBody* body = new btRigidBody(rbInfo);
|
||||
|
||||
// Add the body to the dynamics world
|
||||
m_dynamicsWorld->addRigidBody(body, 1, 1 + 2);
|
||||
|
||||
createGround();
|
||||
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
}
|
||||
|
||||
void BoxStacks::createBoxStack(int numBoxes, btScalar centerX, btScalar centerZ)
|
||||
{
|
||||
//create a few dynamic rigidbodies
|
||||
// Re-using the same collision is better for memory usage and performance
|
||||
|
||||
const btScalar boxHalfSize = btScalar(0.1);
|
||||
|
||||
btBoxShape* colShape = createBoxShape(btVector3(boxHalfSize, boxHalfSize, boxHalfSize));
|
||||
m_collisionShapes.push_back(colShape);
|
||||
|
||||
/// Create Dynamic Objects
|
||||
btTransform startTransform;
|
||||
startTransform.setIdentity();
|
||||
|
||||
btScalar mass(1.0);
|
||||
|
||||
btVector3 localInertia(0, 0, 0);
|
||||
colShape->calculateLocalInertia(mass,localInertia);
|
||||
|
||||
for (int i = 0; i < numBoxes; ++i)
|
||||
{
|
||||
startTransform.setOrigin(btVector3(centerX, 1+btScalar(btScalar(2) * boxHalfSize * i), centerZ));
|
||||
createRigidBody(mass, startTransform, colShape);
|
||||
}
|
||||
}
|
||||
|
||||
btMultiBody* BoxStacks::createFeatherstoneMultiBody(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool fixedBase)
|
||||
{
|
||||
//init the base
|
||||
btVector3 baseInertiaDiag(0.f, 0.f, 0.f);
|
||||
float baseMass = 1.f;
|
||||
|
||||
if (baseMass)
|
||||
{
|
||||
btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2]));
|
||||
pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag);
|
||||
delete pTempBox;
|
||||
}
|
||||
|
||||
bool canSleep = false;
|
||||
|
||||
btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, fixedBase, canSleep);
|
||||
|
||||
btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f);
|
||||
pMultiBody->setBasePos(basePosition);
|
||||
pMultiBody->setWorldToBaseRot(baseOriQuat);
|
||||
btVector3 vel(0, 0, 0);
|
||||
|
||||
//init the links
|
||||
btVector3 hingeJointAxis(1, 0, 0);
|
||||
float linkMass = 1.f;
|
||||
btVector3 linkInertiaDiag(0.f, 0.f, 0.f);
|
||||
|
||||
btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2]));
|
||||
pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag);
|
||||
delete pTempBox;
|
||||
|
||||
//y-axis assumed up
|
||||
btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset
|
||||
btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset
|
||||
btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset
|
||||
|
||||
//////
|
||||
btScalar q0 = 0.f * SIMD_PI / 180.f;
|
||||
btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0);
|
||||
quat0.normalize();
|
||||
/////
|
||||
|
||||
for (int i = 0; i < numLinks; ++i)
|
||||
{
|
||||
if (!spherical)
|
||||
pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, true);
|
||||
else
|
||||
//pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false);
|
||||
pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, true);
|
||||
}
|
||||
|
||||
pMultiBody->finalizeMultiDof();
|
||||
|
||||
///
|
||||
pWorld->addMultiBody(pMultiBody);
|
||||
///
|
||||
return pMultiBody;
|
||||
}
|
||||
|
||||
void BoxStacks::createGround(const btVector3& halfExtents, btScalar zOffSet)
|
||||
{
|
||||
btCollisionShape* groundShape = new btBoxShape(halfExtents);
|
||||
m_collisionShapes.push_back(groundShape);
|
||||
|
||||
// rigidbody is dynamic if and only if mass is non zero, otherwise static
|
||||
btScalar mass(0.);
|
||||
const bool isDynamic = (mass != 0.f);
|
||||
|
||||
btVector3 localInertia(0, 0, 0);
|
||||
if (isDynamic)
|
||||
groundShape->calculateLocalInertia(mass, localInertia);
|
||||
|
||||
// using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
|
||||
btTransform groundTransform;
|
||||
groundTransform.setIdentity();
|
||||
groundTransform.setOrigin(btVector3(0, -halfExtents.z() + zOffSet, 0));
|
||||
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
|
||||
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
|
||||
btRigidBody* body = new btRigidBody(rbInfo);
|
||||
|
||||
// add the body to the dynamics world
|
||||
m_dynamicsWorld->addRigidBody(body, 1, 1 + 2);
|
||||
}
|
||||
|
||||
void BoxStacks::addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents)
|
||||
{
|
||||
btAlignedObjectArray<btQuaternion> world_to_local;
|
||||
world_to_local.resize(pMultiBody->getNumLinks() + 1);
|
||||
|
||||
btAlignedObjectArray<btVector3> local_origin;
|
||||
local_origin.resize(pMultiBody->getNumLinks() + 1);
|
||||
world_to_local[0] = pMultiBody->getWorldToBaseRot();
|
||||
local_origin[0] = pMultiBody->getBasePos();
|
||||
|
||||
{
|
||||
btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()};
|
||||
|
||||
if (1)
|
||||
{
|
||||
btCollisionShape* box = new btBoxShape(baseHalfExtents);
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1);
|
||||
col->setCollisionShape(box);
|
||||
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr.setOrigin(local_origin[0]);
|
||||
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
|
||||
col->setWorldTransform(tr);
|
||||
|
||||
pWorld->addCollisionObject(col, 2, 1 + 2);
|
||||
|
||||
col->setFriction(friction);
|
||||
pMultiBody->setBaseCollider(col);
|
||||
}
|
||||
}
|
||||
|
||||
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
|
||||
{
|
||||
const int parent = pMultiBody->getParent(i);
|
||||
world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1];
|
||||
local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i)));
|
||||
}
|
||||
|
||||
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
|
||||
{
|
||||
btVector3 posr = local_origin[i + 1];
|
||||
|
||||
btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()};
|
||||
|
||||
btCollisionShape* box = new btBoxShape(linkHalfExtents);
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i);
|
||||
|
||||
col->setCollisionShape(box);
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr.setOrigin(posr);
|
||||
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
|
||||
col->setWorldTransform(tr);
|
||||
col->setFriction(friction);
|
||||
pWorld->addCollisionObject(col, 2, 1 + 2);
|
||||
|
||||
pMultiBody->getLink(i).m_collider = col;
|
||||
}
|
||||
}
|
||||
|
||||
CommonExampleInterface* BoxStacksCreateFunc(CommonExampleOptions& options)
|
||||
{
|
||||
return new BoxStacks(options.m_guiHelper);
|
||||
}
|
||||
@@ -1,7 +0,0 @@
|
||||
|
||||
#ifndef CONSTRAINT_SOLVERS_BOX_STACKS_DEMO_H
|
||||
#define CONSTRAINT_SOLVERS_BOX_STACKS_DEMO_H
|
||||
|
||||
class CommonExampleInterface* BoxStacksCreateFunc(struct CommonExampleOptions& options);
|
||||
|
||||
#endif // CONSTRAINT_SOLVERS_BOX_STACKS_DEMO_H
|
||||
@@ -1,224 +0,0 @@
|
||||
#include "BoxStacks_MLCP.h"
|
||||
#include "../OpenGLWindow/SimpleOpenGL3App.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBody.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyBlockConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||
#include "../RobotSimulator/b3RobotSimulatorClientAPI.h"
|
||||
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
|
||||
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||
#include "BulletDynamics/MLCPSolvers/btLemkeSolver.h"
|
||||
#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h"
|
||||
#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h"
|
||||
|
||||
|
||||
class BoxStacks_MLCP : public CommonMultiBodyBase
|
||||
{
|
||||
public:
|
||||
BoxStacks_MLCP(GUIHelperInterface* helper);
|
||||
virtual ~BoxStacks_MLCP();
|
||||
|
||||
virtual void initPhysics();
|
||||
|
||||
virtual void stepSimulation(float deltaTime);
|
||||
|
||||
virtual void resetCamera()
|
||||
{
|
||||
float dist = 2;
|
||||
float pitch = -35;
|
||||
float yaw = 50;
|
||||
float targetPos[3] = {0, 0, 0};
|
||||
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
|
||||
}
|
||||
|
||||
btMultiBody* createMultiBody(btScalar mass, const btTransform& trans, btCollisionShape* collisionShape);
|
||||
|
||||
btMultiBody* loadRobot(std::string filepath = "kuka_iiwa/model.urdf");
|
||||
};
|
||||
|
||||
|
||||
|
||||
static int g_constraintSolverType = 0;
|
||||
|
||||
BoxStacks_MLCP::BoxStacks_MLCP(GUIHelperInterface* helper)
|
||||
: CommonMultiBodyBase(helper)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
BoxStacks_MLCP::~BoxStacks_MLCP()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void BoxStacks_MLCP::stepSimulation(float deltaTime)
|
||||
{
|
||||
float internalTimeStep = 1. / 240.f;
|
||||
m_dynamicsWorld->stepSimulation(deltaTime, 10, internalTimeStep);
|
||||
for (int i = 0; i < m_dynamicsWorld->getNumMultibodies(); i++)
|
||||
{
|
||||
btVector3 pos = m_dynamicsWorld->getMultiBody(i)->getBaseWorldTransform().getOrigin();
|
||||
printf("pos[%d]=%f,%f,%f\n", i, pos.x(), pos.y(), pos.z());
|
||||
}
|
||||
}
|
||||
|
||||
void BoxStacks_MLCP::initPhysics()
|
||||
{
|
||||
m_guiHelper->setUpAxis(2);
|
||||
|
||||
createEmptyDynamicsWorld();
|
||||
m_dynamicsWorld->getSolverInfo().m_numIterations = 50;
|
||||
if (g_constraintSolverType == 5)
|
||||
{
|
||||
g_constraintSolverType = 0;
|
||||
}
|
||||
|
||||
btMultiBodyConstraintSolver* sol = 0;
|
||||
|
||||
btMLCPSolverInterface* mlcp;
|
||||
switch (g_constraintSolverType++)
|
||||
{
|
||||
case 0:
|
||||
sol = new btMultiBodyConstraintSolver;
|
||||
b3Printf("Constraint Solver: Sequential Impulse");
|
||||
break;
|
||||
case 1:
|
||||
mlcp = new btSolveProjectedGaussSeidel();
|
||||
sol = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||
b3Printf("Constraint Solver: MLCP + PGS");
|
||||
break;
|
||||
case 2:
|
||||
mlcp = new btDantzigSolver();
|
||||
sol = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||
b3Printf("Constraint Solver: MLCP + Dantzig");
|
||||
break;
|
||||
case 3:
|
||||
mlcp = new btLemkeSolver();
|
||||
sol = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||
|
||||
b3Printf("Constraint Solver: MLCP + Lemke");
|
||||
break;
|
||||
|
||||
default:
|
||||
sol = new btMultiBodyBlockConstraintSolver();
|
||||
b3Printf("btMultiBodyBlockConstraintSolver");
|
||||
break;
|
||||
}
|
||||
|
||||
m_solver = sol;
|
||||
|
||||
btMultiBodyDynamicsWorld* world = new btMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, sol, m_collisionConfiguration);
|
||||
m_dynamicsWorld = world;
|
||||
m_dynamicsWorld->getSolverInfo().m_globalCfm = btScalar(1e-4);
|
||||
|
||||
|
||||
m_dynamicsWorld->setGravity(btVector3(0,0,-10));
|
||||
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
|
||||
|
||||
if (m_dynamicsWorld->getDebugDrawer())
|
||||
m_dynamicsWorld->getDebugDrawer()->setDebugMode(btIDebugDraw::DBG_DrawWireframe+btIDebugDraw::DBG_DrawContactPoints);
|
||||
|
||||
///create a few basic rigid bodies
|
||||
bool loadPlaneFromURDF = true;
|
||||
if (loadPlaneFromURDF)
|
||||
{
|
||||
loadRobot("plane.urdf");
|
||||
} 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);
|
||||
}
|
||||
|
||||
{
|
||||
btBoxShape* boxShape = createBoxShape(btVector3(btScalar(.1), btScalar(.1), btScalar(.1)));
|
||||
m_collisionShapes.push_back(boxShape);
|
||||
btScalar mass = 10;
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr.setOrigin(btVector3(0, 0, 0.5));
|
||||
btMultiBody* body = createMultiBody(mass, tr, boxShape);
|
||||
}
|
||||
|
||||
{
|
||||
btMultiBody* mb = loadRobot("cube_small.urdf");
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr.setOrigin(btVector3(0, 0, 1.));
|
||||
mb->setBaseWorldTransform(tr);
|
||||
}
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
}
|
||||
|
||||
|
||||
|
||||
btMultiBody* BoxStacks_MLCP::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*BoxStacks_MLCP::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* BoxStacks_MLCPCreateFunc(CommonExampleOptions& options)
|
||||
{
|
||||
return new BoxStacks_MLCP(options.m_guiHelper);
|
||||
}
|
||||
@@ -1,7 +0,0 @@
|
||||
|
||||
#ifndef CONSTRAINT_SOLVERS_BOX_STACKS_MLCP_DEMO_H
|
||||
#define CONSTRAINT_SOLVERS_BOX_STACKS_MLCP_DEMO_H
|
||||
|
||||
class CommonExampleInterface* BoxStacks_MLCPCreateFunc(struct CommonExampleOptions& options);
|
||||
|
||||
#endif // CONSTRAINT_SOLVERS_BOX_STACKS_DEMO_H
|
||||
@@ -1,335 +0,0 @@
|
||||
#include "Grasp_Block.h"
|
||||
#include "../OpenGLWindow/SimpleOpenGL3App.h"
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
|
||||
#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h"
|
||||
#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h"
|
||||
|
||||
#include "BulletDynamics/Featherstone/btMultiBody.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyBlockConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLink.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyJointMotor.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h"
|
||||
|
||||
#include "../OpenGLWindow/GLInstancingRenderer.h"
|
||||
#include "BulletCollision/CollisionShapes/btShapeHull.h"
|
||||
|
||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||
|
||||
class Grasp_Block : public CommonMultiBodyBase
|
||||
{
|
||||
public:
|
||||
Grasp_Block(GUIHelperInterface* helper);
|
||||
virtual ~Grasp_Block();
|
||||
|
||||
virtual void initPhysics();
|
||||
|
||||
virtual void stepSimulation(float deltaTime);
|
||||
|
||||
virtual void resetCamera()
|
||||
{
|
||||
float dist = 1;
|
||||
float pitch = -35;
|
||||
float yaw = 50;
|
||||
float targetPos[3] = {-3, 2.8, -2.5};
|
||||
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
|
||||
}
|
||||
|
||||
void createBoxStack(int numBoxes, btScalar centerX, btScalar centerY);
|
||||
btMultiBody* createFeatherstoneMultiBody(class btMultiBodyDynamicsWorld* world, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical = false, bool fixedBase = false);
|
||||
void createGround(const btVector3& halfExtents = btVector3(50, 50, 50), btScalar zOffSet = btScalar(-1.55));
|
||||
void addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents);
|
||||
};
|
||||
|
||||
static bool g_fixedBase = true;
|
||||
static bool g_firstInit = true;
|
||||
static float scaling = 0.4f;
|
||||
static float friction = 1.;
|
||||
static int g_constraintSolverType = 0;
|
||||
|
||||
Grasp_Block::Grasp_Block(GUIHelperInterface* helper)
|
||||
: CommonMultiBodyBase(helper)
|
||||
{
|
||||
m_guiHelper->setUpAxis(1);
|
||||
}
|
||||
|
||||
Grasp_Block::~Grasp_Block()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void Grasp_Block::stepSimulation(float deltaTime)
|
||||
{
|
||||
//use a smaller internal timestep, there are stability issues
|
||||
float internalTimeStep = 1. / 240.f;
|
||||
m_dynamicsWorld->stepSimulation(deltaTime, 10, internalTimeStep);
|
||||
}
|
||||
|
||||
void Grasp_Block::initPhysics()
|
||||
{
|
||||
m_guiHelper->setUpAxis(1);
|
||||
|
||||
if (g_firstInit)
|
||||
{
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraDistance(btScalar(10. * scaling));
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraPitch(50);
|
||||
g_firstInit = false;
|
||||
}
|
||||
///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();
|
||||
|
||||
if (g_constraintSolverType == 3)
|
||||
{
|
||||
g_constraintSolverType = 0;
|
||||
g_fixedBase = !g_fixedBase;
|
||||
}
|
||||
|
||||
btMLCPSolverInterface* mlcp;
|
||||
switch (g_constraintSolverType++)
|
||||
{
|
||||
case 0:
|
||||
m_solver = new btMultiBodyConstraintSolver;
|
||||
b3Printf("Constraint Solver: Sequential Impulse");
|
||||
break;
|
||||
case 1:
|
||||
mlcp = new btSolveProjectedGaussSeidel();
|
||||
m_solver = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||
b3Printf("Constraint Solver: MLCP + PGS");
|
||||
break;
|
||||
default:
|
||||
mlcp = new btDantzigSolver();
|
||||
m_solver = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||
b3Printf("Constraint Solver: MLCP + Dantzig");
|
||||
break;
|
||||
}
|
||||
m_solver = new btMultiBodyBlockConstraintSolver();
|
||||
|
||||
btMultiBodyDynamicsWorld* world = new btMultiBodyDynamicsWorld(m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration);
|
||||
m_dynamicsWorld = world;
|
||||
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
|
||||
m_dynamicsWorld->setGravity(btVector3(btScalar(0), btScalar(-9.81), btScalar(0)));
|
||||
m_dynamicsWorld->getSolverInfo().m_globalCfm = btScalar(1e-4); //todo: what value is good?
|
||||
|
||||
/// Create a few basic rigid bodies
|
||||
btVector3 groundHalfExtents(50, 50, 50);
|
||||
btCollisionShape* groundShape = new btBoxShape(groundHalfExtents);
|
||||
|
||||
m_collisionShapes.push_back(groundShape);
|
||||
|
||||
btTransform groundTransform;
|
||||
groundTransform.setIdentity();
|
||||
groundTransform.setOrigin(btVector3(0, -50, 00));
|
||||
|
||||
btVector3 linkHalfExtents(btScalar(0.05), btScalar(0.37), btScalar(0.1));
|
||||
btVector3 baseHalfExtents(btScalar(0.05), btScalar(0.37), btScalar(0.1));
|
||||
|
||||
// createBoxStack(5, 0, 0);
|
||||
|
||||
btScalar groundHeight = btScalar(-51.55);
|
||||
btScalar mass = btScalar(0.0);
|
||||
|
||||
btVector3 localInertia(0, 0, 0);
|
||||
groundShape->calculateLocalInertia(mass, localInertia);
|
||||
|
||||
// Using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
|
||||
groundTransform.setIdentity();
|
||||
groundTransform.setOrigin(btVector3(0, groundHeight, 0));
|
||||
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
|
||||
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
|
||||
btRigidBody* body = new btRigidBody(rbInfo);
|
||||
|
||||
// Add the body to the dynamics world
|
||||
m_dynamicsWorld->addRigidBody(body, 1, 1 + 2);
|
||||
|
||||
createGround();
|
||||
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
}
|
||||
|
||||
void Grasp_Block::createBoxStack(int numBoxes, btScalar centerX, btScalar centerZ)
|
||||
{
|
||||
//create a few dynamic rigidbodies
|
||||
// Re-using the same collision is better for memory usage and performance
|
||||
|
||||
const btScalar boxHalfSize = btScalar(0.1);
|
||||
|
||||
btBoxShape* colShape = createBoxShape(btVector3(boxHalfSize, boxHalfSize, boxHalfSize));
|
||||
m_collisionShapes.push_back(colShape);
|
||||
|
||||
/// Create Dynamic Objects
|
||||
btTransform startTransform;
|
||||
startTransform.setIdentity();
|
||||
|
||||
btScalar mass(1.0);
|
||||
|
||||
btVector3 localInertia(0, 0, 0);
|
||||
colShape->calculateLocalInertia(mass,localInertia);
|
||||
|
||||
for (int i = 0; i < numBoxes; ++i)
|
||||
{
|
||||
startTransform.setOrigin(btVector3(centerX, btScalar(btScalar(2) * boxHalfSize * i), centerZ));
|
||||
createRigidBody(mass, startTransform, colShape);
|
||||
}
|
||||
}
|
||||
|
||||
btMultiBody* Grasp_Block::createFeatherstoneMultiBody(btMultiBodyDynamicsWorld* pWorld, int numLinks, const btVector3& basePosition, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents, bool spherical, bool fixedBase)
|
||||
{
|
||||
//init the base
|
||||
btVector3 baseInertiaDiag(0.f, 0.f, 0.f);
|
||||
float baseMass = 1.f;
|
||||
|
||||
if (baseMass)
|
||||
{
|
||||
btCollisionShape* pTempBox = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2]));
|
||||
pTempBox->calculateLocalInertia(baseMass, baseInertiaDiag);
|
||||
delete pTempBox;
|
||||
}
|
||||
|
||||
bool canSleep = false;
|
||||
|
||||
btMultiBody* pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, fixedBase, canSleep);
|
||||
|
||||
btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f);
|
||||
pMultiBody->setBasePos(basePosition);
|
||||
pMultiBody->setWorldToBaseRot(baseOriQuat);
|
||||
btVector3 vel(0, 0, 0);
|
||||
|
||||
//init the links
|
||||
btVector3 hingeJointAxis(1, 0, 0);
|
||||
float linkMass = 1.f;
|
||||
btVector3 linkInertiaDiag(0.f, 0.f, 0.f);
|
||||
|
||||
btCollisionShape* pTempBox = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2]));
|
||||
pTempBox->calculateLocalInertia(linkMass, linkInertiaDiag);
|
||||
delete pTempBox;
|
||||
|
||||
//y-axis assumed up
|
||||
btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset
|
||||
btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset
|
||||
btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset
|
||||
|
||||
//////
|
||||
btScalar q0 = 0.f * SIMD_PI / 180.f;
|
||||
btQuaternion quat0(btVector3(0, 1, 0).normalized(), q0);
|
||||
quat0.normalize();
|
||||
/////
|
||||
|
||||
for (int i = 0; i < numLinks; ++i)
|
||||
{
|
||||
if (!spherical)
|
||||
pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, true);
|
||||
else
|
||||
//pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false);
|
||||
pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, true);
|
||||
}
|
||||
|
||||
pMultiBody->finalizeMultiDof();
|
||||
|
||||
///
|
||||
pWorld->addMultiBody(pMultiBody);
|
||||
///
|
||||
return pMultiBody;
|
||||
}
|
||||
|
||||
void Grasp_Block::createGround(const btVector3& halfExtents, btScalar zOffSet)
|
||||
{
|
||||
btCollisionShape* groundShape = new btBoxShape(halfExtents);
|
||||
m_collisionShapes.push_back(groundShape);
|
||||
|
||||
// rigidbody is dynamic if and only if mass is non zero, otherwise static
|
||||
btScalar mass(0.);
|
||||
const bool isDynamic = (mass != 0.f);
|
||||
|
||||
btVector3 localInertia(0, 0, 0);
|
||||
if (isDynamic)
|
||||
groundShape->calculateLocalInertia(mass, localInertia);
|
||||
|
||||
// using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
|
||||
btTransform groundTransform;
|
||||
groundTransform.setIdentity();
|
||||
groundTransform.setOrigin(btVector3(0, -halfExtents.z() + zOffSet, 0));
|
||||
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
|
||||
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
|
||||
btRigidBody* body = new btRigidBody(rbInfo);
|
||||
|
||||
// add the body to the dynamics world
|
||||
m_dynamicsWorld->addRigidBody(body, 1, 1 + 2);
|
||||
}
|
||||
|
||||
void Grasp_Block::addColliders(btMultiBody* pMultiBody, btMultiBodyDynamicsWorld* pWorld, const btVector3& baseHalfExtents, const btVector3& linkHalfExtents)
|
||||
{
|
||||
btAlignedObjectArray<btQuaternion> world_to_local;
|
||||
world_to_local.resize(pMultiBody->getNumLinks() + 1);
|
||||
|
||||
btAlignedObjectArray<btVector3> local_origin;
|
||||
local_origin.resize(pMultiBody->getNumLinks() + 1);
|
||||
world_to_local[0] = pMultiBody->getWorldToBaseRot();
|
||||
local_origin[0] = pMultiBody->getBasePos();
|
||||
|
||||
{
|
||||
btScalar quat[4] = {-world_to_local[0].x(), -world_to_local[0].y(), -world_to_local[0].z(), world_to_local[0].w()};
|
||||
|
||||
if (1)
|
||||
{
|
||||
btCollisionShape* box = new btBoxShape(baseHalfExtents);
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, -1);
|
||||
col->setCollisionShape(box);
|
||||
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr.setOrigin(local_origin[0]);
|
||||
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
|
||||
col->setWorldTransform(tr);
|
||||
|
||||
pWorld->addCollisionObject(col, 2, 1 + 2);
|
||||
|
||||
col->setFriction(friction);
|
||||
pMultiBody->setBaseCollider(col);
|
||||
}
|
||||
}
|
||||
|
||||
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
|
||||
{
|
||||
const int parent = pMultiBody->getParent(i);
|
||||
world_to_local[i + 1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent + 1];
|
||||
local_origin[i + 1] = local_origin[parent + 1] + (quatRotate(world_to_local[i + 1].inverse(), pMultiBody->getRVector(i)));
|
||||
}
|
||||
|
||||
for (int i = 0; i < pMultiBody->getNumLinks(); ++i)
|
||||
{
|
||||
btVector3 posr = local_origin[i + 1];
|
||||
|
||||
btScalar quat[4] = {-world_to_local[i + 1].x(), -world_to_local[i + 1].y(), -world_to_local[i + 1].z(), world_to_local[i + 1].w()};
|
||||
|
||||
btCollisionShape* box = new btBoxShape(linkHalfExtents);
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i);
|
||||
|
||||
col->setCollisionShape(box);
|
||||
btTransform tr;
|
||||
tr.setIdentity();
|
||||
tr.setOrigin(posr);
|
||||
tr.setRotation(btQuaternion(quat[0], quat[1], quat[2], quat[3]));
|
||||
col->setWorldTransform(tr);
|
||||
col->setFriction(friction);
|
||||
pWorld->addCollisionObject(col, 2, 1 + 2);
|
||||
|
||||
pMultiBody->getLink(i).m_collider = col;
|
||||
}
|
||||
}
|
||||
|
||||
CommonExampleInterface* Grasp_BlockCreateFunc(CommonExampleOptions& options)
|
||||
{
|
||||
return new Grasp_Block(options.m_guiHelper);
|
||||
}
|
||||
@@ -1,7 +0,0 @@
|
||||
|
||||
#ifndef CONSTRAINT_SOLVERS_GRASP_BLOCK_DEMO_H
|
||||
#define CONSTRAINT_SOLVERS_GRASP_BLOCK_DEMO_H
|
||||
|
||||
class CommonExampleInterface* Grasp_BlockCreateFunc(struct CommonExampleOptions& options);
|
||||
|
||||
#endif // CONSTRAINT_SOLVERS_GRASP_BLOCK_DEMO_H
|
||||
@@ -202,10 +202,6 @@ SET(BulletExampleBrowser_SRCS
|
||||
../MultiThreadedDemo/MultiThreadedDemo.h
|
||||
../MultiThreadedDemo/CommonRigidBodyMTBase.cpp
|
||||
../MultiThreadedDemo/CommonRigidBodyMTBase.h
|
||||
../ConstraintSolvers/BoxStacks.cpp
|
||||
../ConstraintSolvers/BoxStacks_MLCP.cpp
|
||||
../ConstraintSolvers/Grasp_Block.cpp
|
||||
../ConstraintSolvers/SerialChains.cpp
|
||||
../BlockSolver/btBlockSolver.cpp
|
||||
../BlockSolver/btBlockSolver.h
|
||||
../BlockSolver/BlockSolverExample.cpp
|
||||
|
||||
@@ -21,10 +21,6 @@
|
||||
#include "../Importers/ImportSDFDemo/ImportSDFSetup.h"
|
||||
#include "../Importers/ImportMJCFDemo/ImportMJCFSetup.h"
|
||||
#include "../Collision/CollisionTutorialBullet2.h"
|
||||
#include "../ConstraintSolvers/SerialChains.h"
|
||||
#include "../ConstraintSolvers/BoxStacks.h"
|
||||
#include "../ConstraintSolvers/BoxStacks_MLCP.h"
|
||||
#include "../ConstraintSolvers/Grasp_Block.h"
|
||||
#include "../GyroscopicDemo/GyroscopicSetup.h"
|
||||
#include "../Constraints/Dof6Spring2Setup.h"
|
||||
#include "../Constraints/ConstraintPhysicsSetup.h"
|
||||
@@ -142,13 +138,7 @@ static ExampleEntry gDefaultExamples[] =
|
||||
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(0, "Constraint Solvers"),
|
||||
ExampleEntry(1, "Serial Chains", "Show colliding two serial chains using different constraint solvers.", SerialChainsCreateFunc, 0),
|
||||
ExampleEntry(1, "Box Stack", "Show box stacks with different constraint solvers for each stack.", BoxStacksCreateFunc, 0),
|
||||
ExampleEntry(1, "Box Stack MLCP", "Show box stacks with different constraint solvers for each stack.", BoxStacks_MLCPCreateFunc, 0),
|
||||
ExampleEntry(1, "Grasp Block", "Show box stacks with different constraint solvers for each stack.", Grasp_BlockCreateFunc, 0),
|
||||
|
||||
|
||||
|
||||
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.",
|
||||
PhysicsServerCreateFuncBullet2),
|
||||
@@ -163,10 +153,10 @@ static ExampleEntry gDefaultExamples[] =
|
||||
|
||||
|
||||
ExampleEntry(0, "BlockSolver"),
|
||||
ExampleEntry(1, "Stack MultiBody SI", "Create a stack of blocks, with heavy block at the top", BlockSolverExampleCreateFunc, BLOCK_SOLVER_SCENE_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_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_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_STACK + BLOCK_SOLVER_BLOCK),
|
||||
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(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),
|
||||
|
||||
@@ -163,7 +163,6 @@ project "App_BulletExampleBrowser"
|
||||
"../Collision/*",
|
||||
"../RoboticsLearning/*",
|
||||
"../BlockSolver/*",
|
||||
"../ConstraintSolvers/*",
|
||||
"../Collision/Internal/*",
|
||||
"../Benchmarks/*",
|
||||
"../MultiThreadedDemo/*",
|
||||
|
||||
@@ -7,7 +7,6 @@
|
||||
|
||||
#include "BulletDynamics/Featherstone/btMultiBody.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyBlockConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h"
|
||||
@@ -113,13 +112,12 @@ void SerialChains::initPhysics()
|
||||
b3Printf("Constraint Solver: MLCP + Dantzig");
|
||||
break;
|
||||
}
|
||||
m_solver = new btMultiBodyBlockConstraintSolver();
|
||||
|
||||
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, -10, 0));
|
||||
m_dynamicsWorld->getSolverInfo().m_globalCfm = btScalar(1e-4); //todo: what value is good?
|
||||
m_dynamicsWorld->getSolverInfo().m_globalCfm = btScalar(1e-4); //todo: what value is good?
|
||||
|
||||
///create a few basic rigid bodies
|
||||
btVector3 groundHalfExtents(50, 50, 50);
|
||||
@@ -239,53 +237,6 @@ void SerialChains::initPhysics()
|
||||
|
||||
createGround();
|
||||
|
||||
{
|
||||
btVector3 halfExtents(.5,.5,.5);
|
||||
btBoxShape* colShape = new btBoxShape(halfExtents);
|
||||
//btCollisionShape* colShape = new btSphereShape(btScalar(1.));
|
||||
m_collisionShapes.push_back(colShape);
|
||||
|
||||
/// Create Dynamic Objects
|
||||
btTransform startTransform;
|
||||
startTransform.setIdentity();
|
||||
|
||||
btScalar mass(1.f);
|
||||
|
||||
//rigidbody is dynamic if and only if mass is non zero, otherwise static
|
||||
bool isDynamic = (mass != 0.f);
|
||||
|
||||
btVector3 localInertia(0,0,0);
|
||||
if (isDynamic)
|
||||
colShape->calculateLocalInertia(mass,localInertia);
|
||||
|
||||
startTransform.setOrigin(btVector3(
|
||||
btScalar(0.0),
|
||||
0.0,
|
||||
btScalar(0.0)));
|
||||
|
||||
|
||||
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
|
||||
btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
|
||||
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,colShape,localInertia);
|
||||
// btRigidBody* body = new btRigidBody(rbInfo);
|
||||
|
||||
// m_dynamicsWorld->addRigidBody(body);//,1,1+2);
|
||||
|
||||
{
|
||||
btVector3 pointInA = -linkHalfExtents;
|
||||
// btVector3 pointInB = halfExtents;
|
||||
btMatrix3x3 frameInA;
|
||||
btMatrix3x3 frameInB;
|
||||
frameInA.setIdentity();
|
||||
frameInB.setIdentity();
|
||||
btVector3 jointAxis(1.0,0.0,0.0);
|
||||
//btMultiBodySliderConstraint* p2p = new btMultiBodySliderConstraint(mbC,numLinks-1,body,pointInA,pointInB,frameInA,frameInB,jointAxis);
|
||||
btMultiBodyPoint2Point* p2p = new btMultiBodyPoint2Point(mbC1, numLinks- 1 , mbC2, numLinks - 1, pointInA, pointInA);
|
||||
p2p->setMaxAppliedImpulse(20.0);
|
||||
m_dynamicsWorld->addMultiBodyConstraint(p2p);
|
||||
}
|
||||
}
|
||||
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
@@ -32,7 +32,6 @@ SET(BulletDynamics_SRCS
|
||||
Vehicle/btWheelInfo.cpp
|
||||
Featherstone/btMultiBody.cpp
|
||||
Featherstone/btMultiBodyConstraint.cpp
|
||||
Featherstone/btMultiBodyBlockConstraintSolver.cpp
|
||||
Featherstone/btMultiBodyConstraintSolver.cpp
|
||||
Featherstone/btMultiBodyDynamicsWorld.cpp
|
||||
Featherstone/btMultiBodyFixedConstraint.cpp
|
||||
|
||||
@@ -649,15 +649,15 @@ btSolverConstraint& btSequentialImpulseConstraintSolver::addFrictionConstraint(c
|
||||
btSolverConstraint& solverConstraint = m_tmpSolverContactFrictionConstraintPool.expandNonInitializing();
|
||||
solverConstraint.m_frictionIndex = frictionIndex;
|
||||
setupFrictionConstraint(solverConstraint, normalAxis, solverBodyIdA, solverBodyIdB, cp, rel_pos1, rel_pos2,
|
||||
colObj0, colObj1, relaxation, infoGlobal, desiredVelocity, cfmSlip);
|
||||
colObj0, colObj1, relaxation, infoGlobal, desiredVelocity, cfmSlip);
|
||||
return solverConstraint;
|
||||
}
|
||||
|
||||
|
||||
void btSequentialImpulseConstraintSolver::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)
|
||||
btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2,
|
||||
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation,
|
||||
btScalar desiredVelocity, btScalar cfmSlip)
|
||||
|
||||
{
|
||||
btVector3 normalAxis(0, 0, 0);
|
||||
@@ -724,7 +724,7 @@ void btSequentialImpulseConstraintSolver::setupTorsionalFrictionConstraint(btSol
|
||||
btScalar desiredVelocity, btScalar cfmSlip)
|
||||
|
||||
{
|
||||
setupTorsionalFrictionConstraintInternal(m_tmpSolverBodyPool, solverConstraint, normalAxis1,solverBodyIdA, solverBodyIdB,
|
||||
setupTorsionalFrictionConstraintInternal(m_tmpSolverBodyPool, solverConstraint, normalAxis1, solverBodyIdA, solverBodyIdB,
|
||||
cp, combinedTorsionalFriction, rel_pos1, rel_pos2,
|
||||
colObj0, colObj1, relaxation,
|
||||
desiredVelocity, cfmSlip);
|
||||
@@ -746,7 +746,7 @@ btSolverConstraint& btSequentialImpulseConstraintSolver::addTorsionalFrictionCon
|
||||
btSolverConstraint& solverConstraint = m_tmpSolverContactRollingFrictionConstraintPool.expandNonInitializing();
|
||||
solverConstraint.m_frictionIndex = frictionIndex;
|
||||
setupTorsionalFrictionConstraint(solverConstraint, normalAxis, solverBodyIdA, solverBodyIdB, cp, combinedTorsionalFriction, rel_pos1, rel_pos2,
|
||||
colObj0, colObj1, relaxation, desiredVelocity, cfmSlip);
|
||||
colObj0, colObj1, relaxation, desiredVelocity, cfmSlip);
|
||||
return solverConstraint;
|
||||
}
|
||||
|
||||
@@ -1067,11 +1067,11 @@ int btSequentialImpulseConstraintSolver::getOrInitSolverBody(btCollisionObject&
|
||||
|
||||
|
||||
void btSequentialImpulseConstraintSolver::setupContactConstraintInternal(btSISolverSingleIterationData& siData,
|
||||
btSolverConstraint& solverConstraint,
|
||||
int solverBodyIdA, int solverBodyIdB,
|
||||
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal,
|
||||
btScalar& relaxation,
|
||||
const btVector3& rel_pos1, const btVector3& rel_pos2)
|
||||
btSolverConstraint& solverConstraint,
|
||||
int solverBodyIdA, int solverBodyIdB,
|
||||
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal,
|
||||
btScalar& relaxation,
|
||||
const btVector3& rel_pos1, const btVector3& rel_pos2)
|
||||
{
|
||||
// const btVector3& pos1 = cp.getPositionWorldOnA();
|
||||
// const btVector3& pos2 = cp.getPositionWorldOnB();
|
||||
@@ -1198,7 +1198,7 @@ void btSequentialImpulseConstraintSolver::setupContactConstraintInternal(btSISol
|
||||
if (rb0)
|
||||
bodyA->internalApplyImpulse(solverConstraint.m_contactNormal1 * bodyA->internalGetInvMass(), solverConstraint.m_angularComponentA, solverConstraint.m_appliedImpulse);
|
||||
if (rb1)
|
||||
bodyB->internalApplyImpulse(-solverConstraint.m_contactNormal2 * bodyB->internalGetInvMass() , -solverConstraint.m_angularComponentB, -(btScalar)solverConstraint.m_appliedImpulse);
|
||||
bodyB->internalApplyImpulse(-solverConstraint.m_contactNormal2 * bodyB->internalGetInvMass(), -solverConstraint.m_angularComponentB, -(btScalar)solverConstraint.m_appliedImpulse);
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -1274,7 +1274,7 @@ void btSequentialImpulseConstraintSolver::setupContactConstraint(btSolverConstra
|
||||
m_btSeed2,
|
||||
m_fixedBodyId,
|
||||
m_maxOverrideNumSolverIterations
|
||||
);
|
||||
);
|
||||
|
||||
|
||||
setupContactConstraintInternal(siData, solverConstraint,
|
||||
@@ -1285,10 +1285,10 @@ void btSequentialImpulseConstraintSolver::setupContactConstraint(btSolverConstra
|
||||
}
|
||||
|
||||
|
||||
void btSequentialImpulseConstraintSolver::setFrictionConstraintImpulseInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btConstraintArray& tmpSolverContactFrictionConstraintPool,
|
||||
btSolverConstraint& solverConstraint,
|
||||
int solverBodyIdA, int solverBodyIdB,
|
||||
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal)
|
||||
void btSequentialImpulseConstraintSolver::setFrictionConstraintImpulseInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, btConstraintArray& tmpSolverContactFrictionConstraintPool,
|
||||
btSolverConstraint& solverConstraint,
|
||||
int solverBodyIdA, int solverBodyIdB,
|
||||
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal)
|
||||
{
|
||||
btSolverBody* bodyA = &tmpSolverBodyPool[solverBodyIdA];
|
||||
btSolverBody* bodyB = &tmpSolverBodyPool[solverBodyIdB];
|
||||
@@ -1302,9 +1302,9 @@ void btSequentialImpulseConstraintSolver::setFrictionConstraintImpulseInternal(b
|
||||
{
|
||||
frictionConstraint1.m_appliedImpulse = cp.m_appliedImpulseLateral1 * infoGlobal.m_warmstartingFactor;
|
||||
if (rb0)
|
||||
bodyA->internalApplyImpulse(frictionConstraint1.m_contactNormal1 * rb0->getInvMass() , frictionConstraint1.m_angularComponentA, frictionConstraint1.m_appliedImpulse);
|
||||
bodyA->internalApplyImpulse(frictionConstraint1.m_contactNormal1 * rb0->getInvMass(), frictionConstraint1.m_angularComponentA, frictionConstraint1.m_appliedImpulse);
|
||||
if (rb1)
|
||||
bodyB->internalApplyImpulse(-frictionConstraint1.m_contactNormal2 * rb1->getInvMass() , -frictionConstraint1.m_angularComponentB, -(btScalar)frictionConstraint1.m_appliedImpulse);
|
||||
bodyB->internalApplyImpulse(-frictionConstraint1.m_contactNormal2 * rb1->getInvMass(), -frictionConstraint1.m_angularComponentB, -(btScalar)frictionConstraint1.m_appliedImpulse);
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -1419,13 +1419,13 @@ void btSequentialImpulseConstraintSolver::convertContactInternal(btSISolverSingl
|
||||
if (axis0.length() > 0.001)
|
||||
{
|
||||
btSequentialImpulseConstraintSolver::addTorsionalFrictionConstraintInternal(siData.m_tmpSolverBodyPool,
|
||||
siData.m_tmpSolverContactRollingFrictionConstraintPool,axis0, solverBodyIdA, solverBodyIdB, frictionIndex, cp,
|
||||
siData.m_tmpSolverContactRollingFrictionConstraintPool, axis0, solverBodyIdA, solverBodyIdB, frictionIndex, cp,
|
||||
cp.m_combinedRollingFriction, rel_pos1, rel_pos2, colObj0, colObj1, relaxation);
|
||||
}
|
||||
if (axis1.length() > 0.001)
|
||||
{
|
||||
btSequentialImpulseConstraintSolver::addTorsionalFrictionConstraintInternal(siData.m_tmpSolverBodyPool,
|
||||
siData.m_tmpSolverContactRollingFrictionConstraintPool,axis1, solverBodyIdA, solverBodyIdB, frictionIndex, cp,
|
||||
siData.m_tmpSolverContactRollingFrictionConstraintPool, axis1, solverBodyIdA, solverBodyIdB, frictionIndex, cp,
|
||||
cp.m_combinedRollingFriction, rel_pos1, rel_pos2, colObj0, colObj1, relaxation);
|
||||
}
|
||||
}
|
||||
@@ -1456,7 +1456,7 @@ void btSequentialImpulseConstraintSolver::convertContactInternal(btSISolverSingl
|
||||
cp.m_lateralFrictionDir1 *= 1.f / btSqrt(lat_rel_vel);
|
||||
applyAnisotropicFriction(colObj0, cp.m_lateralFrictionDir1, btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
applyAnisotropicFriction(colObj1, cp.m_lateralFrictionDir1, btCollisionObject::CF_ANISOTROPIC_FRICTION);
|
||||
btSequentialImpulseConstraintSolver::addFrictionConstraintInternal(siData.m_tmpSolverBodyPool, siData.m_tmpSolverContactFrictionConstraintPool,
|
||||
btSequentialImpulseConstraintSolver::addFrictionConstraintInternal(siData.m_tmpSolverBodyPool, siData.m_tmpSolverContactFrictionConstraintPool,
|
||||
cp.m_lateralFrictionDir1, solverBodyIdA, solverBodyIdB, frictionIndex, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal);
|
||||
|
||||
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
||||
@@ -1494,7 +1494,7 @@ void btSequentialImpulseConstraintSolver::convertContactInternal(btSISolverSingl
|
||||
}
|
||||
else
|
||||
{
|
||||
btSequentialImpulseConstraintSolver::addFrictionConstraintInternal(siData.m_tmpSolverBodyPool, siData.m_tmpSolverContactFrictionConstraintPool,
|
||||
btSequentialImpulseConstraintSolver::addFrictionConstraintInternal(siData.m_tmpSolverBodyPool, siData.m_tmpSolverContactFrictionConstraintPool,
|
||||
cp.m_lateralFrictionDir1, solverBodyIdA, solverBodyIdB, frictionIndex, cp, rel_pos1, rel_pos2, colObj0, colObj1, relaxation, infoGlobal, cp.m_contactMotion1, cp.m_frictionCFM);
|
||||
|
||||
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
|
||||
@@ -1545,14 +1545,14 @@ void btSequentialImpulseConstraintSolver::convertContacts(btPersistentManifold**
|
||||
}
|
||||
}
|
||||
|
||||
void btSequentialImpulseConstraintSolver::convertJointInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool,
|
||||
int& maxOverrideNumSolverIterations,
|
||||
btSolverConstraint* currentConstraintRow,
|
||||
btTypedConstraint* constraint,
|
||||
const btTypedConstraint::btConstraintInfo1& info1,
|
||||
int solverBodyIdA,
|
||||
int solverBodyIdB,
|
||||
const btContactSolverInfo& infoGlobal)
|
||||
void btSequentialImpulseConstraintSolver::convertJointInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool,
|
||||
int& maxOverrideNumSolverIterations,
|
||||
btSolverConstraint* currentConstraintRow,
|
||||
btTypedConstraint* constraint,
|
||||
const btTypedConstraint::btConstraintInfo1& info1,
|
||||
int solverBodyIdA,
|
||||
int solverBodyIdB,
|
||||
const btContactSolverInfo& infoGlobal)
|
||||
{
|
||||
const btRigidBody& rbA = constraint->getRigidBodyA();
|
||||
const btRigidBody& rbB = constraint->getRigidBodyB();
|
||||
@@ -1602,7 +1602,7 @@ void btSequentialImpulseConstraintSolver::convertJointInternal(btAlignedObjectAr
|
||||
info2.m_J2linearAxis = currentConstraintRow->m_contactNormal2;
|
||||
info2.m_J2angularAxis = currentConstraintRow->m_relpos2CrossNormal;
|
||||
info2.rowskip = sizeof(btSolverConstraint) / sizeof(btScalar); //check this
|
||||
///the size of btSolverConstraint needs be a multiple of btScalar
|
||||
///the size of btSolverConstraint needs be a multiple of btScalar
|
||||
btAssert(info2.rowskip * sizeof(btScalar) == sizeof(btSolverConstraint));
|
||||
info2.m_constraintError = ¤tConstraintRow->m_rhs;
|
||||
currentConstraintRow->m_cfm = infoGlobal.m_globalCfm;
|
||||
@@ -1747,7 +1747,7 @@ void btSequentialImpulseConstraintSolver::convertJointsInternal(btSISolverSingle
|
||||
int solverBodyIdB = siData.getOrInitSolverBody(rbB, infoGlobal.m_timeStep);
|
||||
|
||||
convertJointInternal(siData.m_tmpSolverBodyPool, siData.m_maxOverrideNumSolverIterations,
|
||||
currentConstraintRow, constraint, info1, solverBodyIdA, solverBodyIdB, infoGlobal);
|
||||
currentConstraintRow, constraint, info1, solverBodyIdA, solverBodyIdB, infoGlobal);
|
||||
}
|
||||
currentRow += info1.m_numConstraintRows;
|
||||
}
|
||||
@@ -1844,16 +1844,7 @@ void btSequentialImpulseConstraintSolver::convertBodies(btCollisionObject** bodi
|
||||
convertBodiesInternal(siData, bodies, numBodies, infoGlobal);
|
||||
}
|
||||
|
||||
|
||||
btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer)
|
||||
{
|
||||
solveGroupConvertConstraintPrestep(bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer);
|
||||
solveGroupConvertConstraints(bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer);
|
||||
solveGroupConvertConstraintPoststep(bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer);
|
||||
return 0.;
|
||||
}
|
||||
|
||||
btScalar btSequentialImpulseConstraintSolver::solveGroupConvertConstraints(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer)
|
||||
{
|
||||
m_fixedBodyId = -1;
|
||||
BT_PROFILE("solveGroupCacheFriendlySetup");
|
||||
@@ -1943,17 +1934,6 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupConvertConstraints(btCol
|
||||
|
||||
convertContacts(manifoldPtr, numManifolds, infoGlobal);
|
||||
|
||||
|
||||
return 0.f;
|
||||
}
|
||||
|
||||
btScalar btSequentialImpulseConstraintSolver::solveGroupConvertConstraintPrestep(btCollisionObject** /*bodies*/, int /*numBodies*/, btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/, btTypedConstraint** /*constraints*/, int /*numConstraints*/, const btContactSolverInfo& /*infoGlobal*/, btIDebugDraw* /*debugDrawer*/)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
btScalar btSequentialImpulseConstraintSolver::solveGroupConvertConstraintPoststep(btCollisionObject** /*bodies*/, int /*numBodies*/, btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/, btTypedConstraint** /*constraints*/, int /*numConstraints*/, const btContactSolverInfo& infoGlobal, btIDebugDraw* /*debugDrawer*/)
|
||||
{
|
||||
// btContactSolverInfo info = infoGlobal;
|
||||
|
||||
int numNonContactPool = m_tmpSolverNonContactConstraintPool.size();
|
||||
@@ -1984,8 +1964,9 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupConvertConstraintPostste
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
return 0.f;
|
||||
}
|
||||
|
||||
btScalar btSequentialImpulseConstraintSolver::solveSingleIterationInternal(btSISolverSingleIterationData& siData, int iteration, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal)
|
||||
{
|
||||
BT_PROFILE("solveSingleIteration");
|
||||
@@ -2013,7 +1994,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIterationInternal(btSIS
|
||||
for (int j = 0; j < numConstraintPool; ++j)
|
||||
{
|
||||
int tmp = siData.m_orderTmpConstraintPool[j];
|
||||
int swapi = btRandInt2a(j + 1,siData.m_seed);
|
||||
int swapi = btRandInt2a(j + 1, siData.m_seed);
|
||||
siData.m_orderTmpConstraintPool[j] = siData.m_orderTmpConstraintPool[swapi];
|
||||
siData.m_orderTmpConstraintPool[swapi] = tmp;
|
||||
}
|
||||
@@ -2021,7 +2002,7 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIterationInternal(btSIS
|
||||
for (int j = 0; j < numFrictionPool; ++j)
|
||||
{
|
||||
int tmp = siData.m_orderFrictionConstraintPool[j];
|
||||
int swapi = btRandInt2a(j + 1,siData.m_seed);
|
||||
int swapi = btRandInt2a(j + 1, siData.m_seed);
|
||||
siData.m_orderFrictionConstraintPool[j] = siData.m_orderFrictionConstraintPool[swapi];
|
||||
siData.m_orderFrictionConstraintPool[swapi] = tmp;
|
||||
}
|
||||
@@ -2161,21 +2142,21 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIterationInternal(btSIS
|
||||
btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration, btCollisionObject** /*bodies */, int /*numBodies*/, btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* /*debugDrawer*/)
|
||||
{
|
||||
btSISolverSingleIterationData siData(m_tmpSolverBodyPool,
|
||||
m_tmpSolverContactConstraintPool,
|
||||
m_tmpSolverNonContactConstraintPool,
|
||||
m_tmpSolverContactFrictionConstraintPool,
|
||||
m_tmpSolverContactRollingFrictionConstraintPool,
|
||||
m_orderTmpConstraintPool,
|
||||
m_orderNonContactConstraintPool,
|
||||
m_orderFrictionConstraintPool,
|
||||
m_tmpConstraintSizesPool,
|
||||
m_resolveSingleConstraintRowGeneric,
|
||||
m_resolveSingleConstraintRowLowerLimit,
|
||||
m_resolveSplitPenetrationImpulse,
|
||||
m_kinematicBodyUniqueIdToSolverBodyTable,
|
||||
m_btSeed2,
|
||||
m_fixedBodyId,
|
||||
m_maxOverrideNumSolverIterations);
|
||||
m_tmpSolverContactConstraintPool,
|
||||
m_tmpSolverNonContactConstraintPool,
|
||||
m_tmpSolverContactFrictionConstraintPool,
|
||||
m_tmpSolverContactRollingFrictionConstraintPool,
|
||||
m_orderTmpConstraintPool,
|
||||
m_orderNonContactConstraintPool,
|
||||
m_orderFrictionConstraintPool,
|
||||
m_tmpConstraintSizesPool,
|
||||
m_resolveSingleConstraintRowGeneric,
|
||||
m_resolveSingleConstraintRowLowerLimit,
|
||||
m_resolveSplitPenetrationImpulse,
|
||||
m_kinematicBodyUniqueIdToSolverBodyTable,
|
||||
m_btSeed2,
|
||||
m_fixedBodyId,
|
||||
m_maxOverrideNumSolverIterations);
|
||||
|
||||
btScalar leastSquaresResidual = btSequentialImpulseConstraintSolver::solveSingleIterationInternal(siData,
|
||||
iteration, constraints, numConstraints, infoGlobal);
|
||||
@@ -2249,7 +2230,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyIterations(
|
||||
int maxIterations = m_maxOverrideNumSolverIterations > infoGlobal.m_numIterations ? m_maxOverrideNumSolverIterations : infoGlobal.m_numIterations;
|
||||
|
||||
for (int iteration = 0; iteration < maxIterations; iteration++)
|
||||
//for ( int iteration = maxIterations-1 ; iteration >= 0;iteration--)
|
||||
//for ( int iteration = maxIterations-1 ; iteration >= 0;iteration--)
|
||||
{
|
||||
m_leastSquaresResidual = solveSingleIteration(iteration, bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer);
|
||||
|
||||
@@ -2321,7 +2302,7 @@ void btSequentialImpulseConstraintSolver::writeBackJointsInternal(btConstraintAr
|
||||
|
||||
void btSequentialImpulseConstraintSolver::writeBackBodies(int iBegin, int iEnd, const btContactSolverInfo& infoGlobal)
|
||||
{
|
||||
writeBackBodiesInternal(m_tmpSolverBodyPool,iBegin, iEnd, infoGlobal);
|
||||
writeBackBodiesInternal(m_tmpSolverBodyPool, iBegin, iEnd, infoGlobal);
|
||||
}
|
||||
void btSequentialImpulseConstraintSolver::writeBackBodiesInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool, int iBegin, int iEnd, const btContactSolverInfo& infoGlobal)
|
||||
{
|
||||
@@ -2357,11 +2338,11 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlyFinishInter
|
||||
|
||||
if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING)
|
||||
{
|
||||
writeBackContactsInternal(siData.m_tmpSolverContactConstraintPool,siData.m_tmpSolverContactFrictionConstraintPool,0, siData.m_tmpSolverContactConstraintPool.size(), infoGlobal);
|
||||
writeBackContactsInternal(siData.m_tmpSolverContactConstraintPool, siData.m_tmpSolverContactFrictionConstraintPool, 0, siData.m_tmpSolverContactConstraintPool.size(), infoGlobal);
|
||||
}
|
||||
|
||||
writeBackJointsInternal(siData.m_tmpSolverNonContactConstraintPool, 0, siData.m_tmpSolverNonContactConstraintPool.size(), infoGlobal);
|
||||
writeBackBodiesInternal(siData.m_tmpSolverBodyPool,0, siData.m_tmpSolverBodyPool.size(), infoGlobal);
|
||||
writeBackBodiesInternal(siData.m_tmpSolverBodyPool, 0, siData.m_tmpSolverBodyPool.size(), infoGlobal);
|
||||
|
||||
siData.m_tmpSolverContactConstraintPool.resizeNoInitialize(0);
|
||||
siData.m_tmpSolverNonContactConstraintPool.resizeNoInitialize(0);
|
||||
@@ -2412,34 +2393,4 @@ btScalar btSequentialImpulseConstraintSolver::solveGroup(btCollisionObject** bod
|
||||
void btSequentialImpulseConstraintSolver::reset()
|
||||
{
|
||||
m_btSeed2 = 0;
|
||||
}
|
||||
|
||||
btScalar btSequentialImpulseConstraintSolver::solveGroupConvertBackPrestep(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal)
|
||||
{
|
||||
return btScalar(0);
|
||||
}
|
||||
|
||||
btScalar btSequentialImpulseConstraintSolver::solveGroupConvertBack(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal)
|
||||
{
|
||||
if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING)
|
||||
{
|
||||
writeBackContacts(0, m_tmpSolverContactConstraintPool.size(), infoGlobal);
|
||||
}
|
||||
|
||||
writeBackJoints(0, m_tmpSolverNonContactConstraintPool.size(), infoGlobal);
|
||||
writeBackBodies(0, m_tmpSolverBodyPool.size(), infoGlobal);
|
||||
|
||||
return btScalar(0);
|
||||
}
|
||||
|
||||
btScalar btSequentialImpulseConstraintSolver::solveGroupConvertBackPoststep(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal)
|
||||
{
|
||||
m_tmpSolverContactConstraintPool.resizeNoInitialize(0);
|
||||
m_tmpSolverNonContactConstraintPool.resizeNoInitialize(0);
|
||||
m_tmpSolverContactFrictionConstraintPool.resizeNoInitialize(0);
|
||||
m_tmpSolverContactRollingFrictionConstraintPool.resizeNoInitialize(0);
|
||||
|
||||
m_tmpSolverBodyPool.resizeNoInitialize(0);
|
||||
|
||||
return btScalar(0);
|
||||
}
|
||||
}
|
||||
@@ -52,25 +52,25 @@ struct btSISolverSingleIterationData
|
||||
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
|
||||
)
|
||||
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),
|
||||
@@ -126,26 +126,26 @@ protected:
|
||||
btScalar m_leastSquaresResidual;
|
||||
|
||||
void setupFrictionConstraint(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 = 0., btScalar cfmSlip = 0.);
|
||||
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.);
|
||||
|
||||
void setupTorsionalFrictionConstraint(btSolverConstraint & solverConstraint, const btVector3& normalAxis, int solverBodyIdA, int solverBodyIdB,
|
||||
btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2,
|
||||
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation,
|
||||
btScalar desiredVelocity = 0., btScalar cfmSlip = 0.);
|
||||
btManifoldPoint& cp, btScalar combinedTorsionalFriction, const btVector3& rel_pos1, const btVector3& rel_pos2,
|
||||
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation,
|
||||
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);
|
||||
|
||||
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);
|
||||
|
||||
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
|
||||
unsigned long m_btSeed2;
|
||||
@@ -159,7 +159,7 @@ protected:
|
||||
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);
|
||||
|
||||
|
||||
|
||||
virtual void convertBodies(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||
|
||||
btScalar resolveSplitPenetrationSIMD(btSolverBody & bodyA, btSolverBody & bodyB, const btSolverConstraint& contactConstraint)
|
||||
@@ -186,15 +186,15 @@ protected:
|
||||
}
|
||||
|
||||
public:
|
||||
|
||||
|
||||
void writeBackContacts(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);
|
||||
virtual void solveGroupCacheFriendlySplitImpulseIterations(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||
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 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);
|
||||
|
||||
@@ -210,22 +210,22 @@ public:
|
||||
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,
|
||||
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 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,
|
||||
|
||||
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,
|
||||
static void convertJointInternal(btAlignedObjectArray<btSolverBody>& tmpSolverBodyPool,
|
||||
int& maxOverrideNumSolverIterations,
|
||||
btSolverConstraint* currentConstraintRow,
|
||||
btTypedConstraint* constraint,
|
||||
@@ -242,7 +242,7 @@ public:
|
||||
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
|
||||
virtual void reset();
|
||||
|
||||
@@ -296,14 +296,6 @@ public:
|
||||
static btSingleConstraintRowSolver getScalarSplitPenetrationImpulseGeneric();
|
||||
static btSingleConstraintRowSolver getSSE2SplitPenetrationImpulseGeneric();
|
||||
|
||||
virtual btScalar solveGroupConvertConstraintPrestep(btCollisionObject** /*bodies*/, int /*numBodies*/, btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/, btTypedConstraint** /*constraints*/, int /*numConstraints*/, const btContactSolverInfo& /*infoGlobal*/, btIDebugDraw* /*debugDrawer*/);
|
||||
virtual btScalar solveGroupConvertConstraintPoststep(btCollisionObject** /*bodies*/, int /*numBodies*/, btPersistentManifold** /*manifoldPtr*/, int /*numManifolds*/, btTypedConstraint** /*constraints*/, int /*numConstraints*/, const btContactSolverInfo& infoGlobal, btIDebugDraw* /*debugDrawer*/);
|
||||
virtual btScalar solveGroupConvertConstraints(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||
|
||||
virtual btScalar solveGroupConvertBackPrestep(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||
virtual btScalar solveGroupConvertBack(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||
virtual btScalar solveGroupConvertBackPoststep(btCollisionObject** bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||
|
||||
};
|
||||
|
||||
#endif //BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_H
|
||||
#endif //BT_SEQUENTIAL_IMPULSE_CONSTRAINT_SOLVER_H
|
||||
@@ -1,760 +0,0 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2018 Google Inc. http://bulletphysics.org
|
||||
|
||||
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.
|
||||
*/
|
||||
|
||||
#include "btMultiBodyBlockConstraintSolver.h"
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include "LinearMath/btQuickprof.h"
|
||||
#include "btMultiBodyMLCPConstraintSolver.h"
|
||||
#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h"
|
||||
|
||||
static void rigidBodyNotSupported()
|
||||
{
|
||||
printf("Attempts to use rigid body for block solver, which is not supported yet.\n");
|
||||
btAssert(false);
|
||||
}
|
||||
|
||||
btMultiBodyConstraintBlock::btMultiBodyConstraintBlock()
|
||||
: m_constraintConfigId(-1)
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
btMultiBodyConstraintBlock::btMultiBodyConstraintBlock(
|
||||
btTypedConstraint** m_constraints,
|
||||
int m_numConstraints,
|
||||
btAlignedObjectArray<btSolverBody>* m_solverBodyPool,
|
||||
btConstraintArray& m_nonContactConstraints,
|
||||
btConstraintArray& m_normalContactConstraints,
|
||||
btConstraintArray& m_frictionContactConstraints,
|
||||
btConstraintArray& m_rollingFrictionContactConstraints,
|
||||
btMultiBodyConstraint** m_multiBodyConstraints,
|
||||
int m_numMultiBodyConstraints,
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& m_multiBodyNonContactConstraints,
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& m_multiBodyNormalContactConstraints,
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& m_multiBodyFrictionContactConstraints,
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& m_multiBodyTorsionalFrictionContactConstraints,
|
||||
btMultiBodyJacobianData* m_data)
|
||||
: m_constraintConfigId(-1)
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
static void copyConstraintDynamicDataToBlock(btAlignedObjectArray<btMultiBodySolverConstraint*>& originalConstraints, const btAlignedObjectArray<btMultiBodySolverConstraint>& blockConstraints)
|
||||
{
|
||||
btAssert(originalConstraints.size() == blockConstraints.size());
|
||||
for (int i = 0; i < blockConstraints.size(); ++i)
|
||||
{
|
||||
btMultiBodySolverConstraint& originalConstraint = *originalConstraints[i];
|
||||
const btMultiBodySolverConstraint& blockConstraint = blockConstraints[i];
|
||||
|
||||
blockConstraint.m_appliedImpulse = originalConstraint.m_appliedImpulse;
|
||||
blockConstraint.m_appliedPushImpulse = originalConstraint.m_appliedPushImpulse;
|
||||
}
|
||||
}
|
||||
|
||||
void debugPrint(const btScalar* data, int size)
|
||||
{
|
||||
for (int i = 0; i < size; ++i)
|
||||
{
|
||||
printf("\t%.5f", data[i]);
|
||||
if (i != size - 1)
|
||||
printf(",");
|
||||
}
|
||||
printf("\n");
|
||||
}
|
||||
|
||||
void debugPrintDiff(const btScalar* dataA, const btScalar* dataB, int size, bool ignoreZero = false)
|
||||
{
|
||||
for (int i = 0; i < size; ++i)
|
||||
{
|
||||
if (ignoreZero)
|
||||
{
|
||||
if (btFabs(dataA[i] - dataB[i]) < 1e-9)
|
||||
continue;
|
||||
}
|
||||
printf("\t%f", dataA[i] - dataB[i]);
|
||||
if (i != size - 1)
|
||||
printf(",");
|
||||
}
|
||||
printf("\n");
|
||||
}
|
||||
|
||||
void btMultiBodyConstraintBlock::copyDynamicDataFromOriginalToBlock()
|
||||
{
|
||||
copyConstraintDynamicDataToBlock(m_originalMultiBodyNormalContactConstraintPtrs, m_internalData.m_multiBodyNormalContactConstraints);
|
||||
copyConstraintDynamicDataToBlock(m_originalMultiBodyFrictionContactConstraintPtrs, m_internalData.m_multiBodyFrictionContactConstraints);
|
||||
copyConstraintDynamicDataToBlock(m_originalMultiBodyTorsionalFrictionContactConstraintPtrs, m_internalData.m_multiBodyTorsionalFrictionContactConstraints);
|
||||
|
||||
btAssert(m_multiBodies.size() == m_originalDeltaVelIndices.size());
|
||||
btAssert(m_multiBodies.size() == m_deltaVelIndices.size());
|
||||
for (int i = 0; i < m_multiBodies.size(); ++i)
|
||||
{
|
||||
btMultiBody* multiBody = m_multiBodies[i];
|
||||
const int ndof = multiBody->getNumDofs() + 6;
|
||||
|
||||
btMultiBodyJacobianData& originalData = m_internalData.m_data; // TODO(JS): WRONG !!
|
||||
btAlignedObjectArray<btScalar>& originaDeltaVelocities = originalData.m_deltaVelocities;
|
||||
|
||||
btAlignedObjectArray<btScalar>& blockDeltaVelocities = m_internalData.m_data.m_deltaVelocities;
|
||||
|
||||
const int originalIndex = m_originalDeltaVelIndices[i];
|
||||
const int blockIndex = m_deltaVelIndices[i];
|
||||
|
||||
const btScalar* originalDeltaVelocitiesPtr = &originaDeltaVelocities[originalIndex];
|
||||
btScalar* blockDeltaVelocitiesPtr = &blockDeltaVelocities[blockIndex];
|
||||
|
||||
// printf("[ original --> block ]\n");
|
||||
// printf("original: ");
|
||||
// debugPrint(originalDeltaVelocitiesPtr, ndof);
|
||||
// printf("block: ");
|
||||
// debugPrint(blockDeltaVelocitiesPtr, ndof);
|
||||
// printf("diff: ");
|
||||
// debugPrintDiff(originalDeltaVelocitiesPtr, blockDeltaVelocitiesPtr, ndof, true);
|
||||
// printf("\n");
|
||||
|
||||
memcpy(blockDeltaVelocitiesPtr, originalDeltaVelocitiesPtr, ndof * sizeof(btScalar));
|
||||
}
|
||||
}
|
||||
|
||||
static void copyConstraintDynamicDataFromToOriginal(btAlignedObjectArray<btMultiBodySolverConstraint*>& originalConstraints, const btAlignedObjectArray<btMultiBodySolverConstraint>& blockConstraints)
|
||||
{
|
||||
btAssert(originalConstraints.size() == blockConstraints.size());
|
||||
for (int i = 0; i < blockConstraints.size(); ++i)
|
||||
{
|
||||
btMultiBodySolverConstraint& originalConstraint = *originalConstraints[i];
|
||||
const btMultiBodySolverConstraint& blockConstraint = blockConstraints[i];
|
||||
|
||||
originalConstraint.m_appliedImpulse = blockConstraint.m_appliedImpulse;
|
||||
originalConstraint.m_appliedPushImpulse = blockConstraint.m_appliedPushImpulse;
|
||||
}
|
||||
}
|
||||
|
||||
void btMultiBodyConstraintBlock::copyDynamicDataFromBlockToOriginal()
|
||||
{
|
||||
copyConstraintDynamicDataFromToOriginal(m_originalMultiBodyNormalContactConstraintPtrs, m_internalData.m_multiBodyNormalContactConstraints);
|
||||
copyConstraintDynamicDataFromToOriginal(m_originalMultiBodyFrictionContactConstraintPtrs, m_internalData.m_multiBodyFrictionContactConstraints);
|
||||
copyConstraintDynamicDataFromToOriginal(m_originalMultiBodyTorsionalFrictionContactConstraintPtrs, m_internalData.m_multiBodyTorsionalFrictionContactConstraints);
|
||||
|
||||
btAssert(m_multiBodies.size() == m_originalDeltaVelIndices.size());
|
||||
btAssert(m_multiBodies.size() == m_deltaVelIndices.size());
|
||||
for (int i = 0; i < m_multiBodies.size(); ++i)
|
||||
{
|
||||
btMultiBody* multiBody = m_multiBodies[i];
|
||||
const int ndof = multiBody->getNumDofs() + 6;
|
||||
|
||||
btMultiBodyJacobianData& originalData = m_internalData.m_data;
|
||||
btAlignedObjectArray<btScalar>& originaDeltaVelocities = originalData.m_deltaVelocities;
|
||||
|
||||
btAlignedObjectArray<btScalar>& blockDeltaVelocities = m_internalData.m_data.m_deltaVelocities;
|
||||
|
||||
const int originalIndex = m_originalDeltaVelIndices[i];
|
||||
const int blockIndex = m_deltaVelIndices[i];
|
||||
|
||||
btScalar* originalDeltaVelocitiesPtr = &originaDeltaVelocities[originalIndex];
|
||||
const btScalar* blockDeltaVelocitiesPtr = &blockDeltaVelocities[blockIndex];
|
||||
|
||||
// printf("[ block --> original ]\n");
|
||||
// printf("original: ");
|
||||
// debugPrint(originalDeltaVelocitiesPtr, ndof);
|
||||
// printf("block: ");
|
||||
// debugPrint(blockDeltaVelocitiesPtr, ndof);
|
||||
// printf("diff: ");
|
||||
// debugPrintDiff(originalDeltaVelocitiesPtr, blockDeltaVelocitiesPtr, ndof, true);
|
||||
// printf("\n");
|
||||
|
||||
memcpy(originalDeltaVelocitiesPtr, blockDeltaVelocitiesPtr, ndof * sizeof(btScalar));
|
||||
}
|
||||
}
|
||||
|
||||
btSingleBlockSplittingPolicy::btSingleBlockSplittingPolicy(btMultiBodyConstraintSolver* solver)
|
||||
: m_solver(solver)
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
btSingleBlockSplittingPolicy::~btSingleBlockSplittingPolicy()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void btSingleBlockSplittingPolicy::split(btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& blockInput, const btAlignedObjectArray<btBlockConstraintSolverConfig>& availableConfigs, btAlignedObjectArray<btMultiBodyConstraintBlock>& blocksOutput)
|
||||
{
|
||||
btMultiBodyConstraintBlock newBlock;
|
||||
// newBlock.m_originalInternalDataBlock = blockInput;
|
||||
// m_solver->setMultiBodyInternalConstraintData(newBlock.m_originalInternalDataBlock);
|
||||
newBlock.m_solver = m_solver;
|
||||
// newBlock.m_constraints = blockInput.m_constraints;
|
||||
// newBlock.m_numConstraints = blockInput.m_numConstraints;
|
||||
// newBlock.m_multiBodyConstraints = blockInput.m_multiBodyConstraints;
|
||||
// newBlock.m_numMultiBodyConstraints = blockInput.m_numMultiBodyConstraints;
|
||||
|
||||
blocksOutput.push_back(newBlock);
|
||||
}
|
||||
|
||||
btDoubleBlockSplittingPolicy::btDoubleBlockSplittingPolicy(btMultiBodyConstraintSolver* solver)
|
||||
: m_solver(solver)
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
btDoubleBlockSplittingPolicy::~btDoubleBlockSplittingPolicy()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
template <typename ArrayT>
|
||||
void splitContactConstraints(const ArrayT& input, ArrayT& output1, ArrayT& output2)
|
||||
{
|
||||
const int totalSize = input.size();
|
||||
const int halfSize = totalSize / 2;
|
||||
|
||||
output1.resize(halfSize);
|
||||
output2.resize(totalSize - halfSize);
|
||||
|
||||
for (int i = 0; i < halfSize; ++i)
|
||||
{
|
||||
output1[i] = input[i];
|
||||
}
|
||||
|
||||
for (int i = halfSize; i < totalSize; ++i)
|
||||
{
|
||||
output2[i - halfSize] = input[i];
|
||||
}
|
||||
}
|
||||
|
||||
btMultiBodyConstraintBlock initializeConstraintBlock(btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& input)
|
||||
{
|
||||
btMultiBodyConstraintBlock output;
|
||||
|
||||
// MultiBody
|
||||
|
||||
output.m_internalData.m_multiBodyConstraints = input.m_multiBodyConstraints;
|
||||
output.m_internalData.m_numMultiBodyConstraints = input.m_numMultiBodyConstraints;
|
||||
//output.m_multiBodyConstraintSet.m_data = input.m_multiBodyConstraintSet.m_data;
|
||||
|
||||
btAssert(output.m_internalData.m_multiBodyNormalContactConstraints.size() == 0);
|
||||
btAssert(output.m_internalData.m_multiBodyFrictionContactConstraints.size() == 0);
|
||||
|
||||
return output;
|
||||
}
|
||||
|
||||
static void setupBlockMultiBodyJacobianData(
|
||||
btMultiBody* multiBody,
|
||||
btAlignedObjectArray<btMultiBody*>& multiBodySet,
|
||||
btAlignedObjectArray<int>& blockDeltaVelIndices,
|
||||
int& blockDeltaVelIndex,
|
||||
int& blockJacobianIndex,
|
||||
btMultiBodyJacobianData& blockJacobianData,
|
||||
btAlignedObjectArray<int>& originalDeltaVelIndices,
|
||||
const int originalDeltaVelIndex,
|
||||
const int originalJacobianIndex,
|
||||
const btMultiBodyJacobianData& originalJacobianData)
|
||||
{
|
||||
const int ndof = multiBody->getNumDofs() + 6;
|
||||
|
||||
btAlignedObjectArray<btScalar>& blockJacobians = blockJacobianData.m_jacobians;
|
||||
btAlignedObjectArray<btScalar>& blockDeltaVelocities = blockJacobianData.m_deltaVelocities;
|
||||
btAlignedObjectArray<btScalar>& blockDeltaVelocitiesUnitImpulse = blockJacobianData.m_deltaVelocitiesUnitImpulse;
|
||||
|
||||
const btAlignedObjectArray<btScalar>& originalJacobians = originalJacobianData.m_jacobians;
|
||||
const btAlignedObjectArray<btScalar>& originalDeltaVelocitiesUnitImpulse = originalJacobianData.m_deltaVelocitiesUnitImpulse;
|
||||
|
||||
int indexInBlock = -1;
|
||||
for (int i = 0; i < multiBodySet.size(); ++i)
|
||||
{
|
||||
if (multiBody == multiBodySet[i])
|
||||
{
|
||||
indexInBlock = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (indexInBlock == -1)
|
||||
{
|
||||
blockDeltaVelIndex = blockDeltaVelocities.size();
|
||||
blockDeltaVelocities.resize(blockDeltaVelocities.size() + ndof);
|
||||
multiBodySet.push_back(multiBody);
|
||||
originalDeltaVelIndices.push_back(originalDeltaVelIndex);
|
||||
blockDeltaVelIndices.push_back(blockDeltaVelIndex);
|
||||
}
|
||||
else
|
||||
{
|
||||
blockDeltaVelIndex = blockDeltaVelIndices[indexInBlock];
|
||||
}
|
||||
|
||||
blockJacobianIndex = blockJacobians.size();
|
||||
blockJacobians.resize(blockJacobians.size() + ndof);
|
||||
blockDeltaVelocitiesUnitImpulse.resize(blockDeltaVelocitiesUnitImpulse.size() + ndof);
|
||||
btAssert(blockJacobians.size() == blockDeltaVelocitiesUnitImpulse.size());
|
||||
|
||||
btScalar* blockJacobiansRawPtr = &blockJacobians[blockJacobianIndex];
|
||||
const btScalar* originalJacobiansRawPtr = &originalJacobians[originalJacobianIndex];
|
||||
memcpy(blockJacobiansRawPtr, originalJacobiansRawPtr, ndof * sizeof(btScalar));
|
||||
|
||||
btScalar* blockDeltaVelUnitImp = &blockDeltaVelocitiesUnitImpulse[blockJacobianIndex];
|
||||
const btScalar* originalDeltaVelUnitImp = &originalDeltaVelocitiesUnitImpulse[originalJacobianIndex];
|
||||
memcpy(blockDeltaVelUnitImp, originalDeltaVelUnitImp, ndof * sizeof(btScalar));
|
||||
|
||||
btAssert(blockJacobians.size() >= blockDeltaVelocities.size());
|
||||
}
|
||||
|
||||
static void setupMultiBodyBlockConstraintData(
|
||||
btMultiBodyConstraintBlock& block,
|
||||
btAlignedObjectArray<btMultiBody*>& blockMultiBodySet,
|
||||
btAlignedObjectArray<int>& blockDeltaVelIndices,
|
||||
btMultiBodySolverConstraint& blockContactConstraint,
|
||||
btMultiBodyJacobianData& blockJacobianData,
|
||||
int blockFrictionIndex,
|
||||
btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& originalInternalData,
|
||||
btAlignedObjectArray<int>& originalDeltaVelIndices,
|
||||
const btMultiBodySolverConstraint& originalContactConstraint,
|
||||
const btMultiBodyJacobianData& originalJacobianData)
|
||||
{
|
||||
// Copy all the values. Some values will be updated below if necessary.
|
||||
blockContactConstraint = originalContactConstraint;
|
||||
blockContactConstraint.m_frictionIndex = blockFrictionIndex;
|
||||
|
||||
btMultiBody* multiBodyA = blockContactConstraint.m_multiBodyA;
|
||||
if (multiBodyA)
|
||||
{
|
||||
setupBlockMultiBodyJacobianData(
|
||||
multiBodyA,
|
||||
blockMultiBodySet,
|
||||
blockDeltaVelIndices,
|
||||
blockContactConstraint.m_deltaVelAindex,
|
||||
blockContactConstraint.m_jacAindex,
|
||||
blockJacobianData,
|
||||
originalDeltaVelIndices,
|
||||
originalContactConstraint.m_deltaVelAindex,
|
||||
originalContactConstraint.m_jacAindex,
|
||||
originalJacobianData);
|
||||
}
|
||||
else
|
||||
{
|
||||
rigidBodyNotSupported();
|
||||
}
|
||||
|
||||
btMultiBody* multiBodyB = blockContactConstraint.m_multiBodyB;
|
||||
if (multiBodyB)
|
||||
{
|
||||
setupBlockMultiBodyJacobianData(
|
||||
multiBodyB,
|
||||
blockMultiBodySet,
|
||||
blockDeltaVelIndices,
|
||||
blockContactConstraint.m_deltaVelBindex,
|
||||
blockContactConstraint.m_jacBindex,
|
||||
blockJacobianData,
|
||||
originalDeltaVelIndices,
|
||||
originalContactConstraint.m_deltaVelBindex,
|
||||
originalContactConstraint.m_jacBindex,
|
||||
originalJacobianData);
|
||||
}
|
||||
else
|
||||
{
|
||||
rigidBodyNotSupported();
|
||||
}
|
||||
}
|
||||
|
||||
void btDoubleBlockSplittingPolicy::split(
|
||||
btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& originalInternalData,
|
||||
const btAlignedObjectArray<btBlockConstraintSolverConfig>& availableConfigs,
|
||||
btAlignedObjectArray<btMultiBodyConstraintBlock>& subBlocks)
|
||||
{
|
||||
btMultiBodyConstraintBlock constraintBlock1 = initializeConstraintBlock(originalInternalData);
|
||||
btMultiBodyConstraintBlock constraintBlock2 = initializeConstraintBlock(originalInternalData);
|
||||
btMultiBodyConstraintBlock constraintBlock3 = initializeConstraintBlock(originalInternalData);
|
||||
|
||||
constraintBlock1.m_solver = m_solver;
|
||||
constraintBlock2.m_solver = m_solver;
|
||||
constraintBlock3.m_solver = m_solver;
|
||||
|
||||
btDantzigSolver* mlcp = new btDantzigSolver();
|
||||
btMultiBodyMLCPConstraintSolver* sol = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||
// constraintBlock2.m_solver = sol;
|
||||
|
||||
const int totalMultiBodyContactConstraintSize = originalInternalData.m_multiBodyNormalContactConstraints.size();
|
||||
const int halfMultiBodyContactConstraintSize = totalMultiBodyContactConstraintSize / 2;
|
||||
|
||||
for (int i = 0; i < halfMultiBodyContactConstraintSize; ++i)
|
||||
{
|
||||
copyMultiBodyContactConstraint(constraintBlock1, originalInternalData, i);
|
||||
}
|
||||
|
||||
for (int i = halfMultiBodyContactConstraintSize; i < totalMultiBodyContactConstraintSize; ++i)
|
||||
{
|
||||
copyMultiBodyContactConstraint(constraintBlock2, originalInternalData, i);
|
||||
}
|
||||
|
||||
const int totalMultiBodyNonContactConstraintSize = originalInternalData.m_multiBodyNonContactConstraints.size();
|
||||
|
||||
for (int i = 0; i < totalMultiBodyNonContactConstraintSize; ++i)
|
||||
{
|
||||
// copyMultiBodyNonContactConstraint(constraintBlock3, originalInternalData, i);
|
||||
}
|
||||
|
||||
|
||||
// for (int i = 0; i < totalMultiBodyContactConstraintSize; ++i)
|
||||
// {
|
||||
// if (strcmp(originalInternalData.m_multiBodyNormalContactConstraints[i].m_multiBodyA->getBaseName(), "group1") == 0)
|
||||
// copyMultiBodyContactConstraint(constraintBlock1, originalInternalData, i);
|
||||
// else
|
||||
// copyMultiBodyContactConstraint(constraintBlock2, originalInternalData, i);
|
||||
// }
|
||||
|
||||
subBlocks.push_back(constraintBlock1);
|
||||
subBlocks.push_back(constraintBlock2);
|
||||
subBlocks.push_back(constraintBlock3);
|
||||
}
|
||||
|
||||
btMultiBodyBlockSplittingPolicy::~btMultiBodyBlockSplittingPolicy()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
void btMultiBodyBlockSplittingPolicy::copyMultiBodyNonContactConstraint(btMultiBodyConstraintBlock& block, btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& originalInternalData, int originalNonContactConstraintIndex)
|
||||
{
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& originalNonContactConstraints = originalInternalData.m_multiBodyNonContactConstraints;
|
||||
const btMultiBodyJacobianData& originalJacobianData = originalInternalData.m_data;
|
||||
|
||||
btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& blockInternalData = block.m_internalData;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& blockNonContactConstraints = blockInternalData.m_multiBodyNonContactConstraints;
|
||||
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint*>& blockOriginalNonContactConstraintPtrs = block.m_originalMultiBodyNonContactConstraintPtrs;
|
||||
|
||||
btMultiBodyJacobianData& blockJacobianData = block.m_internalData.m_data;
|
||||
|
||||
btAlignedObjectArray<btMultiBody*>& blockMultiBodySet = block.m_multiBodies;
|
||||
|
||||
const int blockFrictionIndex = blockNonContactConstraints.size();
|
||||
|
||||
btMultiBodySolverConstraint& originalNonContactConstraint = originalNonContactConstraints[originalNonContactConstraintIndex];
|
||||
|
||||
btMultiBodySolverConstraint& blockNonContactConstraint = blockNonContactConstraints.expandNonInitializing();
|
||||
blockOriginalNonContactConstraintPtrs.push_back(&originalNonContactConstraint);
|
||||
|
||||
setupMultiBodyBlockConstraintData(
|
||||
block,
|
||||
blockMultiBodySet,
|
||||
block.m_deltaVelIndices,
|
||||
blockNonContactConstraint,
|
||||
blockJacobianData,
|
||||
blockFrictionIndex,
|
||||
originalInternalData,
|
||||
block.m_originalDeltaVelIndices,
|
||||
originalNonContactConstraint,
|
||||
originalJacobianData);
|
||||
}
|
||||
|
||||
void btMultiBodyBlockSplittingPolicy::copyMultiBodyContactConstraint(btMultiBodyConstraintBlock& block, btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& originalInternalData, int originalNormalContactConstraintIndex)
|
||||
{
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& originalNormalContactConstraints = originalInternalData.m_multiBodyNormalContactConstraints;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& originalFrictionContactConstraints = originalInternalData.m_multiBodyFrictionContactConstraints;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& originalTortionalFrictionContactConstraints = originalInternalData.m_multiBodyTorsionalFrictionContactConstraints;
|
||||
const btMultiBodyJacobianData& originalJacobianData = originalInternalData.m_data;
|
||||
|
||||
btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& blockInternalData = block.m_internalData;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& blockNormalContactConstraints = blockInternalData.m_multiBodyNormalContactConstraints;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& blockFrictionContactConstraints = blockInternalData.m_multiBodyFrictionContactConstraints;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& blockTortionalFrictionContactConstraints = blockInternalData.m_multiBodyTorsionalFrictionContactConstraints;
|
||||
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint*>& blockOriginalNormalContactConstraintPtrs = block.m_originalMultiBodyNormalContactConstraintPtrs;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint*>& blockOriginalFrictionContactConstraintPtrs = block.m_originalMultiBodyFrictionContactConstraintPtrs;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint*>& blockOriginalTorsionalFrictionContactConstraintPtrs = block.m_originalMultiBodyTorsionalFrictionContactConstraintPtrs;
|
||||
|
||||
btMultiBodyJacobianData& blockJacobianData = block.m_internalData.m_data;
|
||||
|
||||
const int numFrictionPerContact = originalNormalContactConstraints.size() == originalFrictionContactConstraints.size() ? 1 : 2;
|
||||
|
||||
btAlignedObjectArray<btMultiBody*>& blockMultiBodySet = block.m_multiBodies;
|
||||
|
||||
const int blockFrictionIndex = blockNormalContactConstraints.size();
|
||||
|
||||
//-- 1. Normal contact
|
||||
|
||||
btMultiBodySolverConstraint& originalNormalContactConstraint = originalNormalContactConstraints[originalNormalContactConstraintIndex];
|
||||
|
||||
btMultiBodySolverConstraint& blockNormalContactConstraint = blockNormalContactConstraints.expandNonInitializing();
|
||||
blockOriginalNormalContactConstraintPtrs.push_back(&originalNormalContactConstraint);
|
||||
|
||||
setupMultiBodyBlockConstraintData(
|
||||
block,
|
||||
blockMultiBodySet,
|
||||
block.m_deltaVelIndices,
|
||||
blockNormalContactConstraint,
|
||||
blockJacobianData,
|
||||
blockFrictionIndex,
|
||||
originalInternalData,
|
||||
block.m_originalDeltaVelIndices,
|
||||
originalNormalContactConstraint,
|
||||
originalJacobianData);
|
||||
|
||||
//-- 2. Friction contacts
|
||||
|
||||
btAssert(originalFrictionContactConstraints.size() != 0);
|
||||
const int originalFrictionContactConstraintIndex1 = originalNormalContactConstraintIndex * numFrictionPerContact;
|
||||
btMultiBodySolverConstraint& originalFrictionContactConstraint = originalFrictionContactConstraints[originalFrictionContactConstraintIndex1];
|
||||
|
||||
blockOriginalFrictionContactConstraintPtrs.push_back(&originalFrictionContactConstraint);
|
||||
btMultiBodySolverConstraint& blockFrictionContactConstraint1 = blockFrictionContactConstraints.expandNonInitializing();
|
||||
setupMultiBodyBlockConstraintData(
|
||||
block,
|
||||
blockMultiBodySet,
|
||||
block.m_deltaVelIndices,
|
||||
blockFrictionContactConstraint1,
|
||||
blockJacobianData,
|
||||
blockFrictionIndex,
|
||||
originalInternalData,
|
||||
block.m_originalDeltaVelIndices,
|
||||
originalFrictionContactConstraint,
|
||||
originalJacobianData);
|
||||
|
||||
if (numFrictionPerContact == 2)
|
||||
{
|
||||
const int originalFrictionContactConstraintIndex2 = originalFrictionContactConstraintIndex1 + 1;
|
||||
btMultiBodySolverConstraint& originalFrictionContactConstraint = originalFrictionContactConstraints[originalFrictionContactConstraintIndex2];
|
||||
|
||||
blockOriginalFrictionContactConstraintPtrs.push_back(&originalFrictionContactConstraint);
|
||||
btMultiBodySolverConstraint& blockFrictionContactConstraint2 = blockFrictionContactConstraints.expandNonInitializing();
|
||||
setupMultiBodyBlockConstraintData(
|
||||
block,
|
||||
blockMultiBodySet,
|
||||
block.m_deltaVelIndices,
|
||||
blockFrictionContactConstraint2,
|
||||
blockJacobianData,
|
||||
blockFrictionIndex,
|
||||
originalInternalData,
|
||||
block.m_originalDeltaVelIndices,
|
||||
originalFrictionContactConstraint,
|
||||
originalJacobianData);
|
||||
}
|
||||
|
||||
// TODO(JS): Torsional friction contact constraints
|
||||
}
|
||||
|
||||
btMultiBodyBlockConstraintSolver::btMultiBodyBlockConstraintSolver()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
btMultiBodyBlockConstraintSolver::~btMultiBodyBlockConstraintSolver()
|
||||
{
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
btScalar btMultiBodyBlockConstraintSolver::solveGroupConvertConstraintPoststep(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer)
|
||||
{
|
||||
return btMultiBodyConstraintSolver::solveGroupConvertConstraintPoststep(bodies, numBodies, manifoldPtr, numManifolds, constraints, numConstraints, infoGlobal, debugDrawer);
|
||||
}
|
||||
|
||||
void btMultiBodyBlockConstraintSolver::solveMultiBodyGroup(
|
||||
btCollisionObject** bodies,
|
||||
int numBodies,
|
||||
btPersistentManifold** manifold,
|
||||
int numManifolds,
|
||||
btTypedConstraint** constraints,
|
||||
int numConstraints,
|
||||
btMultiBodyConstraint** multiBodyConstraints,
|
||||
int numMultiBodyConstraints,
|
||||
const btContactSolverInfo& info,
|
||||
btIDebugDraw* debugDrawer,
|
||||
btDispatcher* /*dispatcher*/)
|
||||
{
|
||||
m_tmpMultiBodyConstraints = multiBodyConstraints;
|
||||
m_tmpNumMultiBodyConstraints = numMultiBodyConstraints;
|
||||
|
||||
// 1. Convert rigid bodies/multibodies, joints, contacts into constraints.
|
||||
solveGroupCacheFriendlySetup(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, info, debugDrawer);
|
||||
|
||||
// 2. Split constraints into constraint blocks
|
||||
btMultiBodyInternalConstraintData originalInternalDataCopy;
|
||||
getMultiBodyInternalConstraintData(originalInternalDataCopy);
|
||||
|
||||
btAlignedObjectArray<btBlockConstraintSolverConfig> configs;
|
||||
// TODO(JS): This is just for test
|
||||
//m_splittingPolicy = new btSingleBlockSplittingPolicy(new btMultiBodyConstraintSolver());
|
||||
|
||||
// btDantzigSolver* mlcp = new btDantzigSolver();
|
||||
// btMultiBodyMLCPConstraintSolver* sol = new btMultiBodyMLCPConstraintSolver(mlcp);
|
||||
// m_splittingPolicy = new btDoubleBlockSplittingPolicy(sol);
|
||||
|
||||
m_splittingPolicy = new btDoubleBlockSplittingPolicy(new btMultiBodyConstraintSolver());
|
||||
|
||||
btAssert(m_splittingPolicy);
|
||||
m_blocks.resize(0);
|
||||
m_splittingPolicy->split(originalInternalDataCopy, configs, m_blocks);
|
||||
|
||||
// for (int i = 0; i < m_blocks.size(); ++i)
|
||||
// {
|
||||
// btMultiBodyConstraintBlock& block = m_blocks[i];
|
||||
// btMultiBodyConstraintSolver* solver = block.m_solver;
|
||||
// btAssert(solver);
|
||||
|
||||
// solver->solveGroupConvertConstraintPrestep(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, info, debugDrawer);
|
||||
// copyDynamicDataFromOriginalToBlock(block);
|
||||
//// block.copyDynamicDataFromOriginalToBlock();
|
||||
// solver->setMultiBodyInternalConstraintData(block.m_internalData, false);
|
||||
// solver->solveGroupConvertConstraintPoststep(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, info, debugDrawer);
|
||||
// }
|
||||
|
||||
// 3. Gauss-Seidel iterations
|
||||
|
||||
const int maxIterations = m_maxOverrideNumSolverIterations > info.m_numIterations ? m_maxOverrideNumSolverIterations : info.m_numIterations;
|
||||
|
||||
m_leastSquaresResidual = 0;
|
||||
|
||||
for (int iteration = 0; iteration < maxIterations; ++iteration)
|
||||
{
|
||||
for (int i = 0; i < m_blocks.size(); ++i)
|
||||
{
|
||||
// Change the sweep direction every iteration
|
||||
const int index = iteration & 1 ? m_blocks.size() - 1 - i : i;
|
||||
|
||||
btMultiBodyConstraintBlock& block = m_blocks[index];
|
||||
btMultiBodyConstraintSolver* solver = block.m_solver;
|
||||
btAssert(solver);
|
||||
|
||||
solver->solveGroupConvertConstraintPrestep(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, info, debugDrawer);
|
||||
copyDynamicDataFromOriginalToBlock(block);
|
||||
solver->setMultiBodyInternalConstraintData(block.m_internalData, false);
|
||||
solver->solveGroupConvertConstraintPoststep(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, info, debugDrawer);
|
||||
|
||||
// TODO(JS): Add split impulse
|
||||
btScalar newSquaredResidual = solver->solveGroupCacheFriendlyIterations(bodies, numBodies, manifold, numManifolds, constraints, numConstraints, info, debugDrawer);
|
||||
m_leastSquaresResidual = btMax(m_leastSquaresResidual, newSquaredResidual);
|
||||
|
||||
solver->solveGroupConvertBackPrestep(bodies, numBodies, info);
|
||||
solver->solveGroupConvertBack(bodies, numBodies, info);
|
||||
solver->getMultiBodyInternalConstraintData(block.m_internalData, false);
|
||||
copyDynamicDataFromBlockToOriginal(block);
|
||||
solver->solveGroupConvertBackPoststep(bodies, numBodies, info);
|
||||
}
|
||||
|
||||
if (m_leastSquaresResidual <= info.m_leastSquaresResidualThreshold || (iteration >= (maxIterations - 1)))
|
||||
{
|
||||
#ifdef VERBOSE_RESIDUAL_PRINTF
|
||||
printf("residual = %f at iteration #%d\n", m_leastSquaresResidual, iteration);
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// solveGroupConvertBackPrestep(bodies, numBodies, info);
|
||||
// solveGroupConvertBack(bodies, numBodies, info);
|
||||
// getMultiBodyInternalConstraintData(block.m_internalData, false);
|
||||
// copyDynamicDataFromBlockToOriginal(block);
|
||||
// solveGroupConvertBackPoststep(bodies, numBodies, info);
|
||||
|
||||
solveGroupCacheFriendlyFinish(bodies, numBodies, info);
|
||||
|
||||
m_tmpMultiBodyConstraints = 0;
|
||||
m_tmpNumMultiBodyConstraints = 0;
|
||||
}
|
||||
|
||||
void btMultiBodyBlockConstraintSolver::setSplittingPolicy(btMultiBodyBlockSplittingPolicy* policy)
|
||||
{
|
||||
m_splittingPolicy = policy;
|
||||
}
|
||||
|
||||
void btMultiBodyBlockConstraintSolver::copyDynamicDataFromOriginalToBlock(btMultiBodyConstraintBlock& block)
|
||||
{
|
||||
copyConstraintDynamicDataToBlock(block.m_originalMultiBodyNormalContactConstraintPtrs, block.m_internalData.m_multiBodyNormalContactConstraints);
|
||||
copyConstraintDynamicDataToBlock(block.m_originalMultiBodyFrictionContactConstraintPtrs, block.m_internalData.m_multiBodyFrictionContactConstraints);
|
||||
copyConstraintDynamicDataToBlock(block.m_originalMultiBodyTorsionalFrictionContactConstraintPtrs, block.m_internalData.m_multiBodyTorsionalFrictionContactConstraints);
|
||||
|
||||
btAssert(block.m_multiBodies.size() == block.m_originalDeltaVelIndices.size());
|
||||
btAssert(block.m_multiBodies.size() == block.m_deltaVelIndices.size());
|
||||
for (int i = 0; i < block.m_multiBodies.size(); ++i)
|
||||
{
|
||||
btMultiBody* multiBody = block.m_multiBodies[i];
|
||||
const int ndof = multiBody->getNumDofs() + 6;
|
||||
|
||||
btMultiBodyJacobianData& originalData = m_data; // TODO(JS): WRONG !!
|
||||
btAlignedObjectArray<btScalar>& originaDeltaVelocities = originalData.m_deltaVelocities;
|
||||
|
||||
btAlignedObjectArray<btScalar>& blockDeltaVelocities = block.m_internalData.m_data.m_deltaVelocities;
|
||||
|
||||
const int originalIndex = block.m_originalDeltaVelIndices[i];
|
||||
const int blockIndex = block.m_deltaVelIndices[i];
|
||||
|
||||
const btScalar* originalDeltaVelocitiesPtr = &originaDeltaVelocities[originalIndex];
|
||||
btScalar* blockDeltaVelocitiesPtr = &blockDeltaVelocities[blockIndex];
|
||||
|
||||
// printf("[ original --> block ]\n");
|
||||
// printf("original: ");
|
||||
// debugPrint(originalDeltaVelocitiesPtr, ndof);
|
||||
// printf("block: ");
|
||||
// debugPrint(blockDeltaVelocitiesPtr, ndof);
|
||||
// printf("diff: ");
|
||||
// debugPrintDiff(originalDeltaVelocitiesPtr, blockDeltaVelocitiesPtr, ndof, true);
|
||||
// printf("\n");
|
||||
|
||||
memcpy(blockDeltaVelocitiesPtr, originalDeltaVelocitiesPtr, ndof * sizeof(btScalar));
|
||||
}
|
||||
}
|
||||
|
||||
void btMultiBodyBlockConstraintSolver::copyDynamicDataFromBlockToOriginal(btMultiBodyConstraintBlock& block)
|
||||
{
|
||||
copyConstraintDynamicDataFromToOriginal(block.m_originalMultiBodyNormalContactConstraintPtrs, block.m_internalData.m_multiBodyNormalContactConstraints);
|
||||
copyConstraintDynamicDataFromToOriginal(block.m_originalMultiBodyFrictionContactConstraintPtrs, block.m_internalData.m_multiBodyFrictionContactConstraints);
|
||||
copyConstraintDynamicDataFromToOriginal(block.m_originalMultiBodyTorsionalFrictionContactConstraintPtrs, block.m_internalData.m_multiBodyTorsionalFrictionContactConstraints);
|
||||
|
||||
btAssert(block.m_multiBodies.size() == block.m_originalDeltaVelIndices.size());
|
||||
btAssert(block.m_multiBodies.size() == block.m_deltaVelIndices.size());
|
||||
for (int i = 0; i < block.m_multiBodies.size(); ++i)
|
||||
{
|
||||
btMultiBody* multiBody = block.m_multiBodies[i];
|
||||
const int ndof = multiBody->getNumDofs() + 6;
|
||||
|
||||
btMultiBodyJacobianData& originalData = m_data;
|
||||
btAlignedObjectArray<btScalar>& originaDeltaVelocities = originalData.m_deltaVelocities;
|
||||
|
||||
btAlignedObjectArray<btScalar>& blockDeltaVelocities = block.m_internalData.m_data.m_deltaVelocities;
|
||||
|
||||
const int originalIndex = block.m_originalDeltaVelIndices[i];
|
||||
const int blockIndex = block.m_deltaVelIndices[i];
|
||||
|
||||
btScalar* originalDeltaVelocitiesPtr = &originaDeltaVelocities[originalIndex];
|
||||
const btScalar* blockDeltaVelocitiesPtr = &blockDeltaVelocities[blockIndex];
|
||||
|
||||
// printf("[ block --> original ]\n");
|
||||
// printf("original: ");
|
||||
// debugPrint(originalDeltaVelocitiesPtr, ndof);
|
||||
// printf("block: ");
|
||||
// debugPrint(blockDeltaVelocitiesPtr, ndof);
|
||||
// printf("diff: ");
|
||||
// debugPrintDiff(originalDeltaVelocitiesPtr, blockDeltaVelocitiesPtr, ndof, true);
|
||||
// printf("\n");
|
||||
|
||||
memcpy(originalDeltaVelocitiesPtr, blockDeltaVelocitiesPtr, ndof * sizeof(btScalar));
|
||||
}
|
||||
}
|
||||
|
||||
int btMultiBodyBlockConstraintSolver::addConfig(btBlockConstraintSolverConfig& config)
|
||||
{
|
||||
m_configs.push_back(config);
|
||||
return m_configs.size();
|
||||
}
|
||||
|
||||
int btMultiBodyBlockConstraintSolver::getNumConfigs() const
|
||||
{
|
||||
return m_configs.size();
|
||||
}
|
||||
|
||||
void btMultiBodyBlockConstraintSolver::removeConfig(int configIndex)
|
||||
{
|
||||
m_configs.removeAtIndex(configIndex);
|
||||
}
|
||||
@@ -1,186 +0,0 @@
|
||||
/*
|
||||
Bullet Continuous Collision Detection and Physics Library
|
||||
Copyright (c) 2018 Google Inc. http://bulletphysics.org
|
||||
|
||||
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.
|
||||
*/
|
||||
|
||||
#ifndef BT_MULTIBODY_BLOCK_CONSTRAINT_SOLVER_H
|
||||
#define BT_MULTIBODY_BLOCK_CONSTRAINT_SOLVER_H
|
||||
|
||||
#include "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h"
|
||||
|
||||
struct btBlockConstraintSolverConfig
|
||||
{
|
||||
int m_solverType; //SI or MLCP Dantzig
|
||||
//to be decided: full or subset of
|
||||
|
||||
btContactSolverInfo m_info;
|
||||
};
|
||||
|
||||
struct btMultiBodyConstraintBlock
|
||||
{
|
||||
/// \{ \name Multi-body Data
|
||||
|
||||
btAlignedObjectArray<btMultiBody*> m_multiBodies;
|
||||
btAlignedObjectArray<int> m_originalDeltaVelIndices;
|
||||
btAlignedObjectArray<int> m_deltaVelIndices;
|
||||
|
||||
// btMultiBodyJacobianData* m_originalDataPtr;
|
||||
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint*> m_originalMultiBodyNonContactConstraintPtrs;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint*> m_originalMultiBodyNormalContactConstraintPtrs;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint*> m_originalMultiBodyFrictionContactConstraintPtrs;
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint*> m_originalMultiBodyTorsionalFrictionContactConstraintPtrs;
|
||||
|
||||
/// \}
|
||||
|
||||
btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData m_internalData;
|
||||
|
||||
/// Constraint solver
|
||||
btMultiBodyConstraintSolver* m_solver;
|
||||
|
||||
bool m_ownSolver = false;
|
||||
// TODO(JS): If this is true, then don't copy all the constraint data, but
|
||||
// only dynamic data
|
||||
// TODO(JS): not utilized yet
|
||||
|
||||
/// Index to constraint solver configuration
|
||||
int m_constraintConfigId;
|
||||
|
||||
/// Default constructor
|
||||
btMultiBodyConstraintBlock();
|
||||
|
||||
/// Constructor
|
||||
btMultiBodyConstraintBlock(
|
||||
btTypedConstraint** m_constraints,
|
||||
int m_numConstraints,
|
||||
btAlignedObjectArray<btSolverBody>* m_solverBodyPool,
|
||||
btConstraintArray& m_originalNonContactConstraints,
|
||||
btConstraintArray& m_originalNormalContactConstraints,
|
||||
btConstraintArray& m_originalFrictionContactConstraints,
|
||||
btConstraintArray& m_orginalRollingFrictionContactConstraints,
|
||||
btMultiBodyConstraint** m_multiBodyConstraints,
|
||||
int m_numMultiBodyConstraints,
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& m_multiBodyNonContactConstraints,
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& m_multiBodyNormalContactConstraints,
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& m_multiBodyFrictionContactConstraints,
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint>& m_multiBodyTorsionalFrictionContactConstraints,
|
||||
btMultiBodyJacobianData* m_data);
|
||||
|
||||
void copyDynamicDataFromOriginalToBlock();
|
||||
void copyDynamicDataFromBlockToOriginal();
|
||||
};
|
||||
|
||||
class btMultiBodyBlockSplittingPolicy
|
||||
{
|
||||
public:
|
||||
/// Destructor
|
||||
virtual ~btMultiBodyBlockSplittingPolicy();
|
||||
|
||||
/// Splits a set of constraints into multiple subsets.
|
||||
///
|
||||
/// \param[in] blockInput
|
||||
/// \param[in] availableConfigs
|
||||
/// \param[in,out] blocksOutput The splitted blocks. This function adds blocks without clearning the array
|
||||
/// beforehand. Clearning the array is the caller's responsibility.
|
||||
virtual void split(btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& blockInput, const btAlignedObjectArray<btBlockConstraintSolverConfig>& availableConfigs, btAlignedObjectArray<btMultiBodyConstraintBlock>& blocksOutput) = 0;
|
||||
|
||||
protected:
|
||||
void copyMultiBodyNonContactConstraint(
|
||||
btMultiBodyConstraintBlock& block,
|
||||
btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& originalInternalData,
|
||||
int originalNonContactConstraintIndex);
|
||||
|
||||
void copyMultiBodyContactConstraint(
|
||||
btMultiBodyConstraintBlock& block,
|
||||
btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& originalInternalData,
|
||||
int originalNormalContactConstraintIndex);
|
||||
};
|
||||
|
||||
class btSingleBlockSplittingPolicy : public btMultiBodyBlockSplittingPolicy
|
||||
{
|
||||
protected:
|
||||
btMultiBodyConstraintSolver* m_solver;
|
||||
|
||||
public:
|
||||
/// Constructor
|
||||
btSingleBlockSplittingPolicy(btMultiBodyConstraintSolver* solver);
|
||||
|
||||
/// Destructor
|
||||
virtual ~btSingleBlockSplittingPolicy();
|
||||
|
||||
// Documentation inherited
|
||||
virtual void split(btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& blockInput, const btAlignedObjectArray<btBlockConstraintSolverConfig>& availableConfigs, btAlignedObjectArray<btMultiBodyConstraintBlock>& blocksOutput);
|
||||
};
|
||||
|
||||
class btDoubleBlockSplittingPolicy : public btMultiBodyBlockSplittingPolicy
|
||||
{
|
||||
protected:
|
||||
btMultiBodyConstraintSolver* m_solver;
|
||||
|
||||
public:
|
||||
/// Constructor
|
||||
btDoubleBlockSplittingPolicy(btMultiBodyConstraintSolver* solver);
|
||||
|
||||
/// Destructor
|
||||
virtual ~btDoubleBlockSplittingPolicy();
|
||||
|
||||
// Documentation inherited
|
||||
virtual void split(btMultiBodyConstraintSolver::btMultiBodyInternalConstraintData& blockInput, const btAlignedObjectArray<btBlockConstraintSolverConfig>& availableConfigs, btAlignedObjectArray<btMultiBodyConstraintBlock>& blocksOutput);
|
||||
};
|
||||
|
||||
class btMultiBodyBlockConstraintSolver : public btMultiBodyConstraintSolver
|
||||
{
|
||||
protected:
|
||||
/// Splitting policy. Assumed not a null.
|
||||
btMultiBodyBlockSplittingPolicy* m_splittingPolicy;
|
||||
|
||||
/// Array of constraint configurations for constraint blocks.
|
||||
btAlignedObjectArray<btBlockConstraintSolverConfig> m_configs;
|
||||
|
||||
/// Array of constraint blocks.
|
||||
btAlignedObjectArray<btMultiBodyConstraintBlock> m_blocks;
|
||||
|
||||
public:
|
||||
/// Constructor
|
||||
btMultiBodyBlockConstraintSolver();
|
||||
|
||||
/// Destructor
|
||||
virtual ~btMultiBodyBlockConstraintSolver();
|
||||
|
||||
virtual btScalar solveGroupConvertConstraintPoststep(btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||
|
||||
|
||||
protected:
|
||||
// Documentation inherited.
|
||||
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);
|
||||
|
||||
/// Sets the splitting policy.
|
||||
virtual void setSplittingPolicy(btMultiBodyBlockSplittingPolicy* policy);
|
||||
|
||||
void copyDynamicDataFromOriginalToBlock(btMultiBodyConstraintBlock& block);
|
||||
void copyDynamicDataFromBlockToOriginal(btMultiBodyConstraintBlock& block);
|
||||
|
||||
/// Adds a constraint block configuration and returns the total number of configurations added to this solver.
|
||||
virtual int addConfig(btBlockConstraintSolverConfig& config);
|
||||
|
||||
/// Returns the number of configurations added to this solver.
|
||||
virtual int getNumConfigs() const;
|
||||
|
||||
/// Removes an configuration at \c configIndex
|
||||
///
|
||||
/// \param[in] configIndex The configuration indext in the range of [0, numConfigs). Passing out of the range is an
|
||||
/// undefined behavior.
|
||||
virtual void removeConfig(int configIndex);
|
||||
};
|
||||
|
||||
#endif // BT_MULTIBODY_BLOCK_CONSTRAINT_SOLVER_H
|
||||
File diff suppressed because it is too large
Load Diff
@@ -28,111 +28,68 @@ class btMultiBody;
|
||||
ATTRIBUTE_ALIGNED16(class)
|
||||
btMultiBodyConstraintSolver : public btSequentialImpulseConstraintSolver
|
||||
{
|
||||
|
||||
protected:
|
||||
btMultiBodyConstraintArray m_multiBodyNonContactConstraints;
|
||||
|
||||
btMultiBodyConstraintArray m_multiBodyNonContactConstraints;
|
||||
btMultiBodyConstraintArray m_multiBodyNormalContactConstraints;
|
||||
btMultiBodyConstraintArray m_multiBodyFrictionContactConstraints;
|
||||
btMultiBodyConstraintArray m_multiBodyTorsionalFrictionContactConstraints;
|
||||
|
||||
btMultiBodyConstraintArray m_multiBodyNormalContactConstraints;
|
||||
btMultiBodyConstraintArray m_multiBodyFrictionContactConstraints;
|
||||
btMultiBodyConstraintArray m_multiBodyTorsionalFrictionContactConstraints;
|
||||
btMultiBodyJacobianData m_data;
|
||||
|
||||
btMultiBodyJacobianData m_data;
|
||||
|
||||
//temp storage for multi body constraints for a specific island/group called by 'solveGroup'
|
||||
btMultiBodyConstraint** m_tmpMultiBodyConstraints;
|
||||
int m_tmpNumMultiBodyConstraints;
|
||||
btMultiBodyConstraint** m_tmpMultiBodyConstraints;
|
||||
int m_tmpNumMultiBodyConstraints;
|
||||
|
||||
btScalar resolveSingleConstraintRowGeneric(const btMultiBodySolverConstraint& c);
|
||||
|
||||
|
||||
//solve 2 friction directions and clamp against the implicit friction cone
|
||||
btScalar resolveConeFrictionConstraintRows(const btMultiBodySolverConstraint& cA1, const btMultiBodySolverConstraint& cB);
|
||||
|
||||
|
||||
void convertContacts(btPersistentManifold** manifoldPtr,int numManifolds, const btContactSolverInfo& infoGlobal);
|
||||
|
||||
btMultiBodySolverConstraint& addMultiBodyFrictionConstraint(const btVector3& normalAxis,btPersistentManifold* manifold,int frictionIndex,btManifoldPoint& cp,btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity=0, btScalar cfmSlip=0);
|
||||
void convertContacts(btPersistentManifold * *manifoldPtr, int numManifolds, const btContactSolverInfo& infoGlobal);
|
||||
|
||||
btMultiBodySolverConstraint& addMultiBodyTorsionalFrictionConstraint(const btVector3& normalAxis,btPersistentManifold* manifold,int frictionIndex,btManifoldPoint& cp,
|
||||
btScalar combinedTorsionalFriction,
|
||||
btCollisionObject* colObj0,btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity=0, btScalar cfmSlip=0);
|
||||
btMultiBodySolverConstraint& addMultiBodyFrictionConstraint(const btVector3& normalAxis, btPersistentManifold* manifold, int frictionIndex, btManifoldPoint& cp, btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity = 0, btScalar cfmSlip = 0);
|
||||
|
||||
void setupMultiBodyJointLimitConstraint(btMultiBodySolverConstraint& constraintRow,
|
||||
btScalar* jacA,btScalar* jacB,
|
||||
btScalar penetration,btScalar combinedFrictionCoeff, btScalar combinedRestitutionCoeff,
|
||||
const btContactSolverInfo& infoGlobal);
|
||||
btMultiBodySolverConstraint& addMultiBodyTorsionalFrictionConstraint(const btVector3& normalAxis, btPersistentManifold* manifold, int frictionIndex, btManifoldPoint& cp,
|
||||
btScalar combinedTorsionalFriction,
|
||||
btCollisionObject* colObj0, btCollisionObject* colObj1, btScalar relaxation, const btContactSolverInfo& infoGlobal, btScalar desiredVelocity = 0, btScalar cfmSlip = 0);
|
||||
|
||||
void setupMultiBodyContactConstraint(btMultiBodySolverConstraint& solverConstraint,
|
||||
const btVector3& contactNormal,
|
||||
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal,
|
||||
btScalar& relaxation,
|
||||
bool isFriction, btScalar desiredVelocity=0, btScalar cfmSlip=0);
|
||||
|
||||
//either rolling or spinning friction
|
||||
void setupMultiBodyTorsionalFrictionConstraint(btMultiBodySolverConstraint& solverConstraint,
|
||||
const btVector3& contactNormal,
|
||||
btManifoldPoint& cp,
|
||||
btScalar combinedTorsionalFriction,
|
||||
const btContactSolverInfo& infoGlobal,
|
||||
btScalar& relaxation,
|
||||
bool isFriction, btScalar desiredVelocity=0, btScalar cfmSlip=0);
|
||||
void setupMultiBodyJointLimitConstraint(btMultiBodySolverConstraint & constraintRow,
|
||||
btScalar * jacA, btScalar * jacB,
|
||||
btScalar penetration, btScalar combinedFrictionCoeff, btScalar combinedRestitutionCoeff,
|
||||
const btContactSolverInfo& infoGlobal);
|
||||
|
||||
void convertMultiBodyContact(btPersistentManifold* manifold,const btContactSolverInfo& infoGlobal);
|
||||
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);
|
||||
void setupMultiBodyContactConstraint(btMultiBodySolverConstraint & solverConstraint,
|
||||
const btVector3& contactNormal,
|
||||
btManifoldPoint& cp, const btContactSolverInfo& infoGlobal,
|
||||
btScalar& relaxation,
|
||||
bool isFriction, btScalar desiredVelocity = 0, btScalar cfmSlip = 0);
|
||||
|
||||
//either rolling or spinning friction
|
||||
void setupMultiBodyTorsionalFrictionConstraint(btMultiBodySolverConstraint & solverConstraint,
|
||||
const btVector3& contactNormal,
|
||||
btManifoldPoint& cp,
|
||||
btScalar combinedTorsionalFriction,
|
||||
const btContactSolverInfo& infoGlobal,
|
||||
btScalar& relaxation,
|
||||
bool isFriction, btScalar desiredVelocity = 0, btScalar cfmSlip = 0);
|
||||
|
||||
void convertMultiBodyContact(btPersistentManifold * manifold, const btContactSolverInfo& infoGlobal);
|
||||
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 solveSingleIteration(int iteration, btCollisionObject** bodies, int numBodies, btPersistentManifold** manifoldPtr, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& infoGlobal, btIDebugDraw* debugDrawer);
|
||||
void applyDeltaVee(btScalar * deltaV, btScalar impulse, int velocityIndex, int ndof);
|
||||
void writeBackSolverBodyToMultiBody(btMultiBodySolverConstraint & constraint, btScalar deltaTime);
|
||||
|
||||
virtual btScalar solveSingleIteration(int iteration, btCollisionObject** bodies ,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer);
|
||||
void applyDeltaVee(btScalar* deltaV, btScalar impulse, int velocityIndex, int ndof);
|
||||
void writeBackSolverBodyToMultiBody(btMultiBodySolverConstraint& constraint, btScalar deltaTime);
|
||||
public:
|
||||
|
||||
struct btMultiBodyInternalConstraintData
|
||||
{
|
||||
/// Multibody (joint) constraints. This is shared by all the blocks.
|
||||
btMultiBodyConstraint** m_multiBodyConstraints;
|
||||
|
||||
/// Number of multibody (joint) constraints. This is shared by all the
|
||||
/// blocks.
|
||||
int m_numMultiBodyConstraints;
|
||||
|
||||
/// Array of multibody non-contact constraints
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint> m_multiBodyNonContactConstraints;
|
||||
|
||||
/// Array of multibody normal contact constraints
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint> m_multiBodyNormalContactConstraints;
|
||||
|
||||
/// Array of multibody friction contact constraints
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint> m_multiBodyFrictionContactConstraints;
|
||||
|
||||
/// Array of multibody rolling friction contact constraints
|
||||
btAlignedObjectArray<btMultiBodySolverConstraint> m_multiBodyTorsionalFrictionContactConstraints;
|
||||
|
||||
/// Pointer to the block constraint solver's multi body Jacobian data, which
|
||||
/// is shared by all the constraint blocks.
|
||||
btMultiBodyJacobianData m_data;
|
||||
};
|
||||
|
||||
BT_DECLARE_ALIGNED_ALLOCATOR();
|
||||
|
||||
/// Copies internal constraint data from \p proxy
|
||||
virtual void setMultiBodyInternalConstraintData(const btMultiBodyInternalConstraintData& proxy, bool onlyDynamicData = false);
|
||||
|
||||
/// Copies internal constraint data to \p proxy
|
||||
virtual void getMultiBodyInternalConstraintData(btMultiBodyInternalConstraintData& data, bool onlyDynamicData = false);
|
||||
|
||||
///this method should not be called, it was just used during porting/integration of Featherstone btMultiBody, providing backwards compatibility but no support for btMultiBodyConstraint (only contact constraints)
|
||||
virtual btScalar solveGroup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifold,int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& info, btIDebugDraw* debugDrawer,btDispatcher* dispatcher);
|
||||
virtual btScalar solveGroupConvertConstraintPrestep(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer);
|
||||
virtual btScalar solveGroupConvertConstraintPoststep(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer);
|
||||
virtual btScalar solveSingleIterationNew(int iteration, btCollisionObject** bodies ,int numBodies,btPersistentManifold** manifoldPtr, int numManifolds,btTypedConstraint** constraints,int numConstraints,const btContactSolverInfo& infoGlobal,btIDebugDraw* debugDrawer);
|
||||
virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject** bodies,int numBodies,const btContactSolverInfo& infoGlobal);
|
||||
|
||||
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);
|
||||
virtual btScalar solveGroup(btCollisionObject * *bodies, int numBodies, btPersistentManifold** manifold, int numManifolds, btTypedConstraint** constraints, int numConstraints, const btContactSolverInfo& info, btIDebugDraw* debugDrawer, btDispatcher* dispatcher);
|
||||
virtual btScalar solveGroupCacheFriendlyFinish(btCollisionObject * *bodies, int numBodies, const btContactSolverInfo& infoGlobal);
|
||||
|
||||
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);
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#endif //BT_MULTIBODY_CONSTRAINT_SOLVER_H
|
||||
|
||||
#endif //BT_MULTIBODY_CONSTRAINT_SOLVER_H
|
||||
|
||||
Reference in New Issue
Block a user