fix tab/space issue in Python file
fix determinism issue introduced in previous commit
This commit is contained in:
@@ -2366,8 +2366,10 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
|||||||
m_data->m_pairCache->setOverlapFilterCallback(m_data->m_broadphaseCollisionFilterCallback);
|
m_data->m_pairCache->setOverlapFilterCallback(m_data->m_broadphaseCollisionFilterCallback);
|
||||||
|
|
||||||
int maxProxies = 32768;
|
int maxProxies = 32768;
|
||||||
m_data->m_broadphase = new btSimpleBroadphase(maxProxies, m_data->m_pairCache);
|
//m_data->m_broadphase = new btSimpleBroadphase(maxProxies, m_data->m_pairCache);
|
||||||
//m_data->m_broadphase = new btDbvtBroadphase(m_data->m_pairCache);
|
btDbvtBroadphase* bv = new btDbvtBroadphase(m_data->m_pairCache);
|
||||||
|
bv->setVelocityPrediction(0);
|
||||||
|
m_data->m_broadphase = bv;
|
||||||
|
|
||||||
|
|
||||||
m_data->m_solver = new btMultiBodyConstraintSolver;
|
m_data->m_solver = new btMultiBodyConstraintSolver;
|
||||||
@@ -2391,7 +2393,7 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
|||||||
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
|
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
|
||||||
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50;
|
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50;
|
||||||
m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 0;
|
m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 0;
|
||||||
gDbvtMargin = btScalar(0.001);//1mm
|
gDbvtMargin = btScalar(0);
|
||||||
m_data->m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-7;
|
m_data->m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-7;
|
||||||
// m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 2;
|
// m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 2;
|
||||||
//todo: islands/constraints are buggy in btMultiBodyDynamicsWorld! (performance + see slipping grasp)
|
//todo: islands/constraints are buggy in btMultiBodyDynamicsWorld! (performance + see slipping grasp)
|
||||||
|
|||||||
@@ -12,7 +12,7 @@ logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "saveRestoreTimings
|
|||||||
|
|
||||||
def setupWorld():
|
def setupWorld():
|
||||||
p.resetSimulation()
|
p.resetSimulation()
|
||||||
p.setPhysicsEngineParameter(deterministicOverlappingPairs=1)
|
p.setPhysicsEngineParameter(deterministicOverlappingPairs=1)
|
||||||
p.loadURDF("planeMesh.urdf")
|
p.loadURDF("planeMesh.urdf")
|
||||||
kukaId = p.loadURDF("kuka_iiwa/model_free_base.urdf",[0,0,10])
|
kukaId = p.loadURDF("kuka_iiwa/model_free_base.urdf",[0,0,10])
|
||||||
for i in range (p.getNumJoints(kukaId)):
|
for i in range (p.getNumJoints(kukaId)):
|
||||||
|
|||||||
Reference in New Issue
Block a user