Merge pull request #842 from erwincoumans/master

added b3PhysicsParamSetInternalSimFlags command, and pybullet setInte…
This commit is contained in:
erwincoumans
2016-10-23 08:26:52 -07:00
committed by GitHub
8 changed files with 564 additions and 473 deletions

View File

@@ -497,6 +497,39 @@ static PyObject* pybullet_setRealTimeSimulation(PyObject* self,
return Py_None;
}
static PyObject* pybullet_setInternalSimFlags(PyObject* self,
PyObject* args) {
if (0 == sm) {
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
{
int enableRealTimeSimulation = 0;
int ret;
b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm);
b3SharedMemoryStatusHandle statusHandle;
if (!PyArg_ParseTuple(args, "i", &enableRealTimeSimulation)) {
PyErr_SetString(
SpamError,
"setInternalSimFlags expected a single value (integer).");
return NULL;
}
ret =
b3PhysicsParamSetInternalSimFlags(command, enableRealTimeSimulation);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
// ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED);
}
Py_INCREF(Py_None);
return Py_None;
}
// Set the gravity of the world with (x, y, z) arguments
static PyObject* pybullet_setGravity(PyObject* self, PyObject* args) {
if (0 == sm) {
@@ -2292,6 +2325,9 @@ static PyMethodDef SpamMethods[] = {
"Enable or disable real time simulation (using the real time clock,"
" RTC) in the physics server. Expects one integer argument, 0 or 1" },
{ "setInternalSimFlags", pybullet_setInternalSimFlags, METH_VARARGS,
"This is for experimental purposes, use at own risk, magic may or not happen"},
{"loadURDF", pybullet_loadURDF, METH_VARARGS,
"Create a multibody by loading a URDF file."},