added b3PhysicsParamSetInternalSimFlags command, and pybullet setInternalSimFlags API.
//Use at own risk: magic things may or my not happen when calling this API. This allows to enable/disable robot assets (samurai world, gripper, KUKA robot etc) in Physics Server (and App_PhysicsServerVR etc) 1 = create robot assets 2 = create experimental box-vr-gui Add optional command-line parameter for App_PhysicsServerVR, --norobotassets, to start with an empty world, no assets in VR (no gripper, no kuka)
This commit is contained in:
@@ -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) {
|
||||
@@ -2218,6 +2251,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."},
|
||||
|
||||
|
||||
Reference in New Issue
Block a user