From fa7cb25c95dd61127564a224d532afbf6a8d93ff Mon Sep 17 00:00:00 2001 From: Xuchen Han Date: Wed, 20 Nov 2019 23:47:15 -0800 Subject: [PATCH] revert the default world to SOFT_MULTIBODY_WORLD --- .../PhysicsServerCommandProcessor.cpp | 24 +++++++++---------- examples/SharedMemory/SharedMemoryPublic.h | 2 +- .../pybullet/examples/deformable_anchor.py | 2 +- examples/pybullet/examples/deformable_ball.py | 2 +- .../pybullet/examples/deformable_torus.py | 2 ++ examples/pybullet/examples/load_soft_body.py | 1 - examples/pybullet/pybullet.c | 2 +- 7 files changed, 18 insertions(+), 17 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 1f96b2d09..2231eb98a 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -2651,24 +2651,24 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld(int flags) m_data->m_broadphase = bv; } - if (flags & RESET_USE_SOFT_MULTIBODY_WORLD) + if (flags & RESET_USE_DEFORMABLE_WORLD) { - m_data->m_solver = new btMultiBodyConstraintSolver; -#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD - m_data->m_dynamicsWorld = new btSoftMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); -#else - m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); +#ifndef SKIP_DEFORMABLE_BODY + m_data->m_deformablebodySolver = new btDeformableBodySolver(); + btDeformableMultiBodyConstraintSolver* solver = new btDeformableMultiBodyConstraintSolver; + m_data->m_solver = solver; + solver->setDeformableSolver(m_data->m_deformablebodySolver); + m_data->m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, solver, m_data->m_collisionConfiguration, m_data->m_deformablebodySolver); #endif } if ((0==m_data->m_dynamicsWorld) && (0==(flags&RESET_USE_DISCRETE_DYNAMICS_WORLD))) { -#ifndef SKIP_DEFORMABLE_BODY - m_data->m_deformablebodySolver = new btDeformableBodySolver(); - btDeformableMultiBodyConstraintSolver* solver = new btDeformableMultiBodyConstraintSolver; - m_data->m_solver = solver; - solver->setDeformableSolver(m_data->m_deformablebodySolver); - m_data->m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, solver, m_data->m_collisionConfiguration, m_data->m_deformablebodySolver); + m_data->m_solver = new btMultiBodyConstraintSolver; +#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD + m_data->m_dynamicsWorld = new btSoftMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); +#else + m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); #endif } diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index fa7d02f2b..feed391a8 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -567,7 +567,7 @@ enum b3NotificationType enum b3ResetSimulationFlags { - RESET_USE_SOFT_MULTIBODY_WORLD=1, + RESET_USE_DEFORMABLE_WORLD=1, RESET_USE_DISCRETE_DYNAMICS_WORLD=2, RESET_USE_SIMPLE_BROADPHASE=4, }; diff --git a/examples/pybullet/examples/deformable_anchor.py b/examples/pybullet/examples/deformable_anchor.py index 66753b0a6..666334628 100644 --- a/examples/pybullet/examples/deformable_anchor.py +++ b/examples/pybullet/examples/deformable_anchor.py @@ -2,8 +2,8 @@ import pybullet as p from time import sleep physicsClient = p.connect(p.GUI) +p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD) -#p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD) gravZ=-10 p.setGravity(0, 0, gravZ) diff --git a/examples/pybullet/examples/deformable_ball.py b/examples/pybullet/examples/deformable_ball.py index 757994ad5..4ff81b613 100644 --- a/examples/pybullet/examples/deformable_ball.py +++ b/examples/pybullet/examples/deformable_ball.py @@ -3,7 +3,7 @@ from time import sleep physicsClient = p.connect(p.GUI) -#p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD) +p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD) p.setGravity(0, 0, -10) diff --git a/examples/pybullet/examples/deformable_torus.py b/examples/pybullet/examples/deformable_torus.py index e71d0653c..ff02237d6 100644 --- a/examples/pybullet/examples/deformable_torus.py +++ b/examples/pybullet/examples/deformable_torus.py @@ -3,6 +3,8 @@ from time import sleep physicsClient = p.connect(p.GUI) +p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD) + p.setGravity(0, 0, -10) planeId = p.loadURDF("plane.urdf", [0,0,-2]) diff --git a/examples/pybullet/examples/load_soft_body.py b/examples/pybullet/examples/load_soft_body.py index 1e86d59bd..3c55ca2e6 100644 --- a/examples/pybullet/examples/load_soft_body.py +++ b/examples/pybullet/examples/load_soft_body.py @@ -2,7 +2,6 @@ import pybullet as p from time import sleep physicsClient = p.connect(p.GUI) -p.resetSimulation(p.RESET_USE_SOFT_MULTIBODY_WORLD) p.setGravity(0, 0, -10) planeId = p.loadURDF("plane.urdf", [0,0,-2]) boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index faaa971fb..0857ea0da 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -12466,7 +12466,7 @@ initpybullet(void) //PyModule_AddIntConstant(m, "CONSTRAINT_SOLVER_LCP_NNCF",eConstraintSolverLCP_NNCG); //PyModule_AddIntConstant(m, "CONSTRAINT_SOLVER_LCP_BLOCK",eConstraintSolverLCP_BLOCK_PGS); - PyModule_AddIntConstant(m, "RESET_USE_SOFT_MULTIBODY_WORLD", RESET_USE_SOFT_MULTIBODY_WORLD); + PyModule_AddIntConstant(m, "RESET_USE_DEFORMABLE_WORLD", RESET_USE_DEFORMABLE_WORLD); PyModule_AddIntConstant(m, "RESET_USE_DISCRETE_DYNAMICS_WORLD", RESET_USE_DISCRETE_DYNAMICS_WORLD); PyModule_AddIntConstant(m, "RESET_USE_SIMPLE_BROADPHASE", RESET_USE_SIMPLE_BROADPHASE);