fix load_soft_body.py example.

add optional flags in pybullet.resetSimulation.
fix compile issue due to SKIP_DEFORMABLE_WORLD
fix issue in .obj importer (todo: replace with tiny_obj_loader)
todo: replace std::ifstream fs; by fileIO usage.
This commit is contained in:
Erwin Coumans
2019-11-14 21:20:42 -08:00
parent 8d56986206
commit 72e0e7c223
8 changed files with 349 additions and 151 deletions

View File

@@ -1,24 +1,24 @@
import pybullet as p
from time import sleep
physicsClient = p.connect(p.DIRECT)
physicsClient = p.connect(p.GUI)
p.setGravity(0, 0, -10)
planeId = p.loadURDF("plane.urdf")
boxId = p.loadURDF("cube.urdf", useMaximalCoordinates = True)
bunnyId = p.loadSoftBody("bunny.obj")
planeId = p.loadURDF("plane.urdf", [0,0,-2])
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
bunnyId = p.loadSoftBody("bunny.obj")#.obj")#.vtk")
#meshData = p.getMeshData(bunnyId)
#print("meshData=",meshData)
p.loadURDF("cube_small.urdf", [1, 0, 1])
#p.loadURDF("cube_small.urdf", [1, 0, 1])
useRealTimeSimulation = 1
if (useRealTimeSimulation):
p.setRealTimeSimulation(1)
print(p.getDynamicsInfo(planeId, -1))
print(p.getDynamicsInfo(bunnyId, 0))
#print(p.getDynamicsInfo(bunnyId, 0))
print(p.getDynamicsInfo(boxId, -1))
p.changeDynamics(boxId,-1,mass=10)
while p.isConnected():
p.setGravity(0, 0, -10)
if (useRealTimeSimulation):

View File

@@ -2050,10 +2050,11 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject*
static PyObject* pybullet_resetSimulation(PyObject* self, PyObject* args, PyObject* keywds)
{
int physicsClientId = 0;
static char* kwlist[] = {"physicsClientId", NULL};
int flags = 0;
static char* kwlist[] = {"flags", "physicsClientId", NULL};
b3PhysicsClientHandle sm = 0;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|ii", kwlist, &flags, &physicsClientId))
{
return NULL;
}
@@ -2065,9 +2066,12 @@ static PyObject* pybullet_resetSimulation(PyObject* self, PyObject* args, PyObje
}
{
b3SharedMemoryCommandHandle commandHandle;
b3SharedMemoryStatusHandle statusHandle;
commandHandle = b3InitResetSimulationCommand(sm);
b3InitResetSimulationSetFlags(commandHandle, flags);
statusHandle = b3SubmitClientCommandAndWaitStatus(
sm, b3InitResetSimulationCommand(sm));
sm, commandHandle);
}
Py_INCREF(Py_None);
return Py_None;
@@ -11721,7 +11725,7 @@ static PyMethodDef SpamMethods[] = {
{"resetSimulation", (PyCFunction)pybullet_resetSimulation, METH_VARARGS | METH_KEYWORDS,
"resetSimulation(physicsClientId=0)\n"
"Reset the simulation: remove all objects and start from an empty world."},
{"stepSimulation", (PyCFunction)pybullet_stepSimulation, METH_VARARGS | METH_KEYWORDS,
"stepSimulation(physicsClientId=0)\n"
"Step the simulation using forward dynamics."},
@@ -12376,6 +12380,10 @@ 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_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);
PyModule_AddIntConstant(m, "VR_BUTTON_IS_DOWN", eButtonIsDown);
PyModule_AddIntConstant(m, "VR_BUTTON_WAS_TRIGGERED", eButtonTriggered);
PyModule_AddIntConstant(m, "VR_BUTTON_WAS_RELEASED", eButtonReleased);