From 186ddb81d83338f7a256c3572b2c29bba54a6c4c Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sun, 26 Aug 2018 17:17:42 -0700 Subject: [PATCH] fix tab/space issue in Python file fix determinism issue introduced in previous commit --- examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 8 +++++--- examples/pybullet/examples/saveRestoreState.py | 2 +- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 1b29ea48f..2ed79fc08 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -2366,8 +2366,10 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld() m_data->m_pairCache->setOverlapFilterCallback(m_data->m_broadphaseCollisionFilterCallback); int maxProxies = 32768; - m_data->m_broadphase = new btSimpleBroadphase(maxProxies, m_data->m_pairCache); - //m_data->m_broadphase = new btDbvtBroadphase(m_data->m_pairCache); + //m_data->m_broadphase = new btSimpleBroadphase(maxProxies, 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; @@ -2391,7 +2393,7 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld() m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001; m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50; 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_minimumSolverBatchSize = 2; //todo: islands/constraints are buggy in btMultiBodyDynamicsWorld! (performance + see slipping grasp) diff --git a/examples/pybullet/examples/saveRestoreState.py b/examples/pybullet/examples/saveRestoreState.py index 3f8736c04..dd1007527 100644 --- a/examples/pybullet/examples/saveRestoreState.py +++ b/examples/pybullet/examples/saveRestoreState.py @@ -12,7 +12,7 @@ logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "saveRestoreTimings def setupWorld(): p.resetSimulation() - p.setPhysicsEngineParameter(deterministicOverlappingPairs=1) + p.setPhysicsEngineParameter(deterministicOverlappingPairs=1) p.loadURDF("planeMesh.urdf") kukaId = p.loadURDF("kuka_iiwa/model_free_base.urdf",[0,0,10]) for i in range (p.getNumJoints(kukaId)):