prepare state logging system (log state of robot, vr controllers after each stepSimulation)
This commit is contained in:
@@ -2583,6 +2583,58 @@ static PyObject* pybullet_removeAllUserDebugItems(PyObject* self, PyObject* args
|
||||
return Py_None;
|
||||
}
|
||||
|
||||
static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
int loggingType = -1;
|
||||
char* fileName = 0;
|
||||
PyObject* objectUniqueIdsObj = 0;
|
||||
|
||||
static char *kwlist[] = { "loggingType", "fileName", "objectUniqueIds", "physicsClientId", NULL };
|
||||
int physicsClientId = 0;
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "is|Oi", kwlist,
|
||||
&loggingType, &fileName, &objectUniqueIdsObj,&physicsClientId))
|
||||
return NULL;
|
||||
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
static PyObject* pybullet_stopStateLogging(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
PyObject* rayFromObj=0;
|
||||
PyObject* rayToObj=0;
|
||||
double from[3];
|
||||
double to[3];
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char *kwlist[] = { "loggingId", "physicsClientId", NULL };
|
||||
int physicsClientId = 0;
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "OO|i", kwlist,
|
||||
&rayFromObj, &rayToObj,&physicsClientId))
|
||||
return NULL;
|
||||
|
||||
sm = getPhysicsClient(physicsClientId);
|
||||
if (sm == 0)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
static PyObject* pybullet_rayTest(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
@@ -4960,8 +5012,14 @@ static PyMethodDef SpamMethods[] = {
|
||||
"Set properties of the VR Camera such as its root transform "
|
||||
"for teleporting or to track objects (camera inside a vehicle for example)."
|
||||
},
|
||||
|
||||
|
||||
{ "startRobotStateLogging", (PyCFunction)pybullet_startStateLogging, METH_VARARGS | METH_KEYWORDS,
|
||||
"Start logging of state, such as robot base position, orientation, joint positions etc. "
|
||||
"Specify loggingType (ROBOT_LOG_MINITAUR, ROBOT_LOG_GENERIC_ROBOT, ROBOT_LOG_VR_CONTROLLERS etc), "
|
||||
"fileName, optional objectUniqueId. Function returns int loggingUniqueId"
|
||||
},
|
||||
{ "stopRobotStateLogging", (PyCFunction)pybullet_stopStateLogging, METH_VARARGS | METH_KEYWORDS,
|
||||
"Stop logging of robot state, given a loggingUniqueId."
|
||||
},
|
||||
{ "rayTest", (PyCFunction)pybullet_rayTest, METH_VARARGS | METH_KEYWORDS,
|
||||
"Cast a ray and return the first object hit, if any. "
|
||||
"Takes two arguments (from position [x,y,z] and to position [x,y,z] in Cartesian world coordinates"
|
||||
@@ -5047,6 +5105,9 @@ initpybullet(void)
|
||||
PyModule_AddIntConstant(m, "VR_MAX_CONTROLLERS", MAX_VR_CONTROLLERS);
|
||||
PyModule_AddIntConstant(m, "VR_MAX_BUTTONS", MAX_VR_BUTTONS);
|
||||
|
||||
PyModule_AddIntConstant(m, "ROBOT_LOGGING_MINITAUR", ROBOT_LOGGING_MINITAUR);
|
||||
PyModule_AddIntConstant(m, "ROBOT_LOGGING_GENERIC_ROBOT", ROBOT_LOGGING_GENERIC_ROBOT);
|
||||
PyModule_AddIntConstant(m, "ROBOT_LOGGING_VR_CONTROLLERS", ROBOT_LOGGING_VR_CONTROLLERS);
|
||||
|
||||
SpamError = PyErr_NewException("pybullet.error", NULL, NULL);
|
||||
Py_INCREF(SpamError);
|
||||
|
||||
Reference in New Issue
Block a user