revert the default world to SOFT_MULTIBODY_WORLD
This commit is contained in:
@@ -2651,24 +2651,24 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld(int flags)
|
|||||||
m_data->m_broadphase = bv;
|
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_DEFORMABLE_BODY
|
||||||
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
m_data->m_deformablebodySolver = new btDeformableBodySolver();
|
||||||
m_data->m_dynamicsWorld = new btSoftMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
btDeformableMultiBodyConstraintSolver* solver = new btDeformableMultiBodyConstraintSolver;
|
||||||
#else
|
m_data->m_solver = solver;
|
||||||
m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
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
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((0==m_data->m_dynamicsWorld) && (0==(flags&RESET_USE_DISCRETE_DYNAMICS_WORLD)))
|
if ((0==m_data->m_dynamicsWorld) && (0==(flags&RESET_USE_DISCRETE_DYNAMICS_WORLD)))
|
||||||
{
|
{
|
||||||
#ifndef SKIP_DEFORMABLE_BODY
|
m_data->m_solver = new btMultiBodyConstraintSolver;
|
||||||
m_data->m_deformablebodySolver = new btDeformableBodySolver();
|
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
||||||
btDeformableMultiBodyConstraintSolver* solver = new btDeformableMultiBodyConstraintSolver;
|
m_data->m_dynamicsWorld = new btSoftMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
||||||
m_data->m_solver = solver;
|
#else
|
||||||
solver->setDeformableSolver(m_data->m_deformablebodySolver);
|
m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
||||||
m_data->m_dynamicsWorld = new btDeformableMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, solver, m_data->m_collisionConfiguration, m_data->m_deformablebodySolver);
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -567,7 +567,7 @@ enum b3NotificationType
|
|||||||
|
|
||||||
enum b3ResetSimulationFlags
|
enum b3ResetSimulationFlags
|
||||||
{
|
{
|
||||||
RESET_USE_SOFT_MULTIBODY_WORLD=1,
|
RESET_USE_DEFORMABLE_WORLD=1,
|
||||||
RESET_USE_DISCRETE_DYNAMICS_WORLD=2,
|
RESET_USE_DISCRETE_DYNAMICS_WORLD=2,
|
||||||
RESET_USE_SIMPLE_BROADPHASE=4,
|
RESET_USE_SIMPLE_BROADPHASE=4,
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -2,8 +2,8 @@ import pybullet as p
|
|||||||
from time import sleep
|
from time import sleep
|
||||||
|
|
||||||
physicsClient = p.connect(p.GUI)
|
physicsClient = p.connect(p.GUI)
|
||||||
|
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||||
|
|
||||||
#p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
|
||||||
gravZ=-10
|
gravZ=-10
|
||||||
p.setGravity(0, 0, gravZ)
|
p.setGravity(0, 0, gravZ)
|
||||||
|
|
||||||
|
|||||||
@@ -3,7 +3,7 @@ from time import sleep
|
|||||||
|
|
||||||
physicsClient = p.connect(p.GUI)
|
physicsClient = p.connect(p.GUI)
|
||||||
|
|
||||||
#p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||||
|
|
||||||
p.setGravity(0, 0, -10)
|
p.setGravity(0, 0, -10)
|
||||||
|
|
||||||
|
|||||||
@@ -3,6 +3,8 @@ from time import sleep
|
|||||||
|
|
||||||
physicsClient = p.connect(p.GUI)
|
physicsClient = p.connect(p.GUI)
|
||||||
|
|
||||||
|
p.resetSimulation(p.RESET_USE_DEFORMABLE_WORLD)
|
||||||
|
|
||||||
p.setGravity(0, 0, -10)
|
p.setGravity(0, 0, -10)
|
||||||
|
|
||||||
planeId = p.loadURDF("plane.urdf", [0,0,-2])
|
planeId = p.loadURDF("plane.urdf", [0,0,-2])
|
||||||
|
|||||||
@@ -2,7 +2,6 @@ import pybullet as p
|
|||||||
from time import sleep
|
from time import sleep
|
||||||
|
|
||||||
physicsClient = p.connect(p.GUI)
|
physicsClient = p.connect(p.GUI)
|
||||||
p.resetSimulation(p.RESET_USE_SOFT_MULTIBODY_WORLD)
|
|
||||||
p.setGravity(0, 0, -10)
|
p.setGravity(0, 0, -10)
|
||||||
planeId = p.loadURDF("plane.urdf", [0,0,-2])
|
planeId = p.loadURDF("plane.urdf", [0,0,-2])
|
||||||
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
|
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
|
||||||
|
|||||||
@@ -12466,7 +12466,7 @@ initpybullet(void)
|
|||||||
//PyModule_AddIntConstant(m, "CONSTRAINT_SOLVER_LCP_NNCF",eConstraintSolverLCP_NNCG);
|
//PyModule_AddIntConstant(m, "CONSTRAINT_SOLVER_LCP_NNCF",eConstraintSolverLCP_NNCG);
|
||||||
//PyModule_AddIntConstant(m, "CONSTRAINT_SOLVER_LCP_BLOCK",eConstraintSolverLCP_BLOCK_PGS);
|
//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_DISCRETE_DYNAMICS_WORLD", RESET_USE_DISCRETE_DYNAMICS_WORLD);
|
||||||
PyModule_AddIntConstant(m, "RESET_USE_SIMPLE_BROADPHASE", RESET_USE_SIMPLE_BROADPHASE);
|
PyModule_AddIntConstant(m, "RESET_USE_SIMPLE_BROADPHASE", RESET_USE_SIMPLE_BROADPHASE);
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user