initial implementation of state logging.

see examples/pybullet/logMinitaur.py for example. Other state logging will include general robot states and VR controllers state.
This commit is contained in:
Erwin Coumans
2017-02-17 14:25:53 -08:00
parent 2b27ab2463
commit cfd35840f0
9 changed files with 402 additions and 116 deletions

View File

@@ -2467,7 +2467,7 @@ int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int o
return 0;
}
b3SharedMemoryCommandHandle b3RobotLoggingCommandInit(b3PhysicsClientHandle physClient)
b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient*)physClient;
b3Assert(cl);
@@ -2475,33 +2475,72 @@ b3SharedMemoryCommandHandle b3RobotLoggingCommandInit(b3PhysicsClientHandle phys
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
b3Assert(command);
command->m_type = CMD_ROBOT_LOGGING;
command->m_type = CMD_STATE_LOGGING;
command->m_updateFlags = 0;
command->m_stateLoggingArguments.m_numBodyUniqueIds = 0;
return (b3SharedMemoryCommandHandle)command;
}
int b3RobotLoggingStartMinitaurLog(b3SharedMemoryCommandHandle commandHandle, const char* fileName, int objectUniqueId)
int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_ROBOT_LOGGING);
if (command->m_type == CMD_ROBOT_LOGGING)
b3Assert(command->m_type == CMD_STATE_LOGGING);
if (command->m_type == CMD_STATE_LOGGING)
{
command->m_updateFlags |= ROBOT_LOGGING_START_MINITAUR_LOG;
command->m_updateFlags |= STATE_LOGGING_START_LOG;
int len = strlen(fileName);
if (len < MAX_FILENAME_LENGTH)
{
strcpy(command->m_stateLoggingArguments.m_fileName, fileName);
}
else
{
command->m_stateLoggingArguments.m_fileName[0] = 0;
}
command->m_stateLoggingArguments.m_logType = loggingType;
}
return 0;
}
int b3RobotLoggingStopMinitaurLog(b3SharedMemoryCommandHandle commandHandle)
int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle)
{
const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle;
b3Assert(status);
b3Assert(status->m_type == CMD_STATE_LOGGING_START_COMPLETED);
if (status && status->m_type == CMD_STATE_LOGGING_START_COMPLETED)
{
return status->m_stateLoggingResultArgs.m_loggingUniqueId;
}
return -1;
}
int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_ROBOT_LOGGING);
if (command->m_type == CMD_ROBOT_LOGGING)
b3Assert(command->m_type == CMD_STATE_LOGGING);
if (command->m_type == CMD_STATE_LOGGING)
{
command->m_updateFlags |= ROBOT_LOGGING_STOP_MINITAUR_LOG;
command->m_updateFlags |= STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID;
if (command->m_stateLoggingArguments.m_numBodyUniqueIds < MAX_SDF_BODIES)
{
command->m_stateLoggingArguments.m_bodyUniqueIds[command->m_stateLoggingArguments.m_numBodyUniqueIds++] = objectUniqueId;
}
}
return 0;
}
int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUid)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_STATE_LOGGING);
if (command->m_type == CMD_STATE_LOGGING)
{
command->m_updateFlags |= STATE_LOGGING_STOP_LOG;
command->m_stateLoggingArguments.m_loggingUniqueId = loggingUid;
}
return 0;
}

View File

@@ -343,10 +343,11 @@ int b3SetVRCameraRootPosition(b3SharedMemoryCommandHandle commandHandle, double
int b3SetVRCameraRootOrientation(b3SharedMemoryCommandHandle commandHandle, double rootOrn[4]);
int b3SetVRCameraTrackingObject(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId);
b3SharedMemoryCommandHandle b3RobotLoggingCommandInit(b3PhysicsClientHandle physClient);
int b3RobotLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName);
int b3RobotLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName);
int b3RobotLoggingStop(b3SharedMemoryCommandHandle commandHandle);
b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient);
int b3StateLoggingStart(b3SharedMemoryCommandHandle commandHandle, int loggingType, const char* fileName);
int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId);
int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle);
int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUniqueId);
#ifdef __cplusplus
}

View File

@@ -899,6 +899,20 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
{
break;
}
case CMD_STATE_LOGGING_START_COMPLETED:
{
break;
};
case CMD_STATE_LOGGING_COMPLETED:
{
break;
};
case CMD_STATE_LOGGING_FAILED:
{
b3Warning("State Logging failed");
break;
}
default: {
b3Error("Unknown server status %d\n", serverCmd.m_type);
btAssert(0);

View File

@@ -17,7 +17,7 @@
#include "BulletInverseDynamics/MultiBodyTree.hpp"
#include "IKTrajectoryHelper.h"
#include "btBulletDynamicsCommon.h"
#include "../Utils/RobotLoggingUtil.h"
#include "LinearMath/btTransform.h"
#include "../Importers/ImportMJCFDemo/BulletMJCFImporter.h"
#include "../Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.h"
@@ -420,6 +420,142 @@ struct MyOverlapFilterCallback : public btOverlapFilterCallback
};
struct InternalStateLogger
{
int m_loggingUniqueId;
int m_loggingType;
InternalStateLogger()
:m_loggingUniqueId(0),
m_loggingType(0)
{
}
virtual void stop() = 0;
virtual void logState(btScalar timeStamp)=0;
};
struct MinitaurStateLogger : public InternalStateLogger
{
int m_loggingTimeStamp;
std::string m_fileName;
int m_minitaurBodyUniqueId;
FILE* m_logFileHandle;
std::string m_structTypes;
btMultiBody* m_minitaurMultiBody;
btAlignedObjectArray<int> m_motorIdList;
MinitaurStateLogger(int loggingUniqueId, std::string fileName, btMultiBody* minitaurMultiBody, btAlignedObjectArray<int>& motorIdList)
:m_loggingTimeStamp(0),
m_logFileHandle(0),
m_minitaurMultiBody(minitaurMultiBody)
{
m_loggingType = STATE_LOGGING_MINITAUR;
m_motorIdList.resize(motorIdList.size());
for (int m=0;m<motorIdList.size();m++)
{
m_motorIdList[m] = motorIdList[m];
}
btAlignedObjectArray<std::string> structNames;
//'t', 'r', 'p', 'y', 'q0', 'q1', 'q2', 'q3', 'q4', 'q5', 'q6', 'q7', 'u0', 'u1', 'u2', 'u3', 'u4', 'u5', 'u6', 'u7', 'xd', 'mo'
structNames.push_back("t");
structNames.push_back("r");
structNames.push_back("p");
structNames.push_back("y");
structNames.push_back("q0");
structNames.push_back("q1");
structNames.push_back("q2");
structNames.push_back("q3");
structNames.push_back("q4");
structNames.push_back("q5");
structNames.push_back("q6");
structNames.push_back("q7");
structNames.push_back("u0");
structNames.push_back("u1");
structNames.push_back("u2");
structNames.push_back("u3");
structNames.push_back("u4");
structNames.push_back("u5");
structNames.push_back("u6");
structNames.push_back("u7");
structNames.push_back("dx");
structNames.push_back("mo");
m_structTypes = "IffffffffffffffffffffB";
const char* fileNameC = fileName.c_str();
m_logFileHandle = createMinitaurLogFile(fileNameC, structNames, m_structTypes);
}
virtual void stop()
{
if (m_logFileHandle)
{
closeMinitaurLogFile(m_logFileHandle);
m_logFileHandle = 0;
}
}
virtual void logState(btScalar timeStep)
{
if (m_logFileHandle)
{
btVector3 pos = m_minitaurMultiBody->getBasePos();
MinitaurLogRecord logData;
//'t', 'r', 'p', 'y', 'q0', 'q1', 'q2', 'q3', 'q4', 'q5', 'q6', 'q7', 'u0', 'u1', 'u2', 'u3', 'u4', 'u5', 'u6', 'u7', 'xd', 'mo'
btScalar motorDir[8] = {1, -1, 1, -1, -1, 1, -1, 1};
btQuaternion orn = m_minitaurMultiBody->getBaseWorldTransform().getRotation();
btMatrix3x3 mat(orn);
btScalar roll=0;
btScalar pitch=0;
btScalar yaw = 0;
mat.getEulerZYX(yaw,pitch,roll);
logData.m_values.push_back(m_loggingTimeStamp);
logData.m_values.push_back((float)roll);
logData.m_values.push_back((float)pitch);
logData.m_values.push_back((float)yaw);
for (int i=0;i<8;i++)
{
float jointAngle = (float)motorDir[i]*m_minitaurMultiBody->getJointPos(m_motorIdList[i]);
logData.m_values.push_back(jointAngle);
}
for (int i=0;i<8;i++)
{
btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)m_minitaurMultiBody->getLink(m_motorIdList[i]).m_userPtr;
if (motor && timeStep>btScalar(0))
{
btScalar force = motor->getAppliedImpulse(0)/timeStep;
logData.m_values.push_back((float)force);
}
}
//x is forward component, estimated speed forward
float xd_speed = m_minitaurMultiBody->getBaseVel()[0];
logData.m_values.push_back(xd_speed);
char mode = 6;
logData.m_values.push_back(mode);
//at the moment, appendMinitaurLogData will directly write to disk (potential delay)
//better to fill a huge memory buffer and once in a while write it to disk
appendMinitaurLogData(m_logFileHandle, m_structTypes, logData);
fflush(m_logFileHandle);
m_loggingTimeStamp++;
}
}
};
struct PhysicsServerCommandProcessorInternalData
@@ -577,7 +713,8 @@ struct PhysicsServerCommandProcessorInternalData
btAlignedObjectArray<int> m_sdfRecentLoadedBodies;
btAlignedObjectArray<InternalStateLogger*> m_stateLoggers;
int m_stateLoggersUniqueId;
struct GUIHelperInterface* m_guiHelper;
int m_sharedMemoryKey;
@@ -622,6 +759,7 @@ struct PhysicsServerCommandProcessorInternalData
m_collisionConfiguration(0),
m_dynamicsWorld(0),
m_remoteDebugDrawer(0),
m_stateLoggersUniqueId(0),
m_guiHelper(0),
m_sharedMemoryKey(SHARED_MEMORY_KEY),
m_verboseOutput(false),
@@ -764,90 +902,15 @@ void logCallback(btDynamicsWorld *world, btScalar timeStep)
proc->logObjectStates(timeStep);
}
#include "../Utils/RobotLoggingUtil.h"
void PhysicsServerCommandProcessor::logObjectStates(btScalar timeStep)
{
//quick hack
static FILE* logFile = 0;
static btScalar logTime = 0;
//printf("log state at time %f\n",logTime);
btAlignedObjectArray<std::string> structNames;
std::string structTypes;
//'t', 'r', 'p', 'y', 'q0', 'q1', 'q2', 'q3', 'q4', 'q5', 'q6', 'q7', 'u0', 'u1', 'u2', 'u3', 'u4', 'u5', 'u6', 'u7', 'xd', 'mo'
structNames.push_back("t");
structNames.push_back("r");
structNames.push_back("p");
structNames.push_back("y");
structNames.push_back("q0");
structNames.push_back("q1");
structNames.push_back("q2");
structNames.push_back("q3");
structNames.push_back("q4");
structNames.push_back("q5");
structNames.push_back("q6");
structNames.push_back("q7");
structNames.push_back("u0");
structNames.push_back("u1");
structNames.push_back("u2");
structNames.push_back("u3");
structNames.push_back("u4");
structNames.push_back("u5");
structNames.push_back("u6");
structNames.push_back("u7");
structNames.push_back("dx");
structNames.push_back("mo");
/* structNames.push_back("timeStamp");
structNames.push_back("objectId");
structNames.push_back("posX");
structNames.push_back("posY");
structNames.push_back("posZ");
*/
structTypes = "fIfff";//I = int, f = float, B char
if (logFile==0)
for (int i=0;i<m_data->m_stateLoggers.size();i++)
{
logFile = createMinitaurLogFile("d:/logTest.txt", structNames, structTypes);
m_data->m_stateLoggers[i]->logState(timeStep);
}
if (logFile)
{
for (int i=0;i<m_data->m_dynamicsWorld->getNumMultibodies();i++)
{
btMultiBody* mb = m_data->m_dynamicsWorld->getMultiBody(i);
btVector3 pos = mb->getBasePos();
MinitaurLogRecord logData;
float timeStamp = logTime;
int objectUniqueId = mb->getUserIndex2();
float posX = pos[0];
float posY = pos[1];
float posZ = pos[2];
logData.m_values.push_back(timeStamp);
logData.m_values.push_back(objectUniqueId);
logData.m_values.push_back(posX);
logData.m_values.push_back(posY);
logData.m_values.push_back(posZ);
//at the moment, appendMinitaurLogData will directly write to disk (potential delay)
//better to fill a huge memory buffer and once in a while write it to disk
appendMinitaurLogData(logFile, structTypes, logData);
}
fflush(logFile);
}
//void closeMinitaurLogFile(FILE* f);
logTime += timeStep;
}
void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
@@ -899,6 +962,17 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
m_data->m_dynamicsWorld->setInternalTickCallback(logCallback,this);
}
void PhysicsServerCommandProcessor::deleteStateLoggers()
{
for (int i=0;i<m_data->m_stateLoggers.size();i++)
{
m_data->m_stateLoggers[i]->stop();
delete m_data->m_stateLoggers[i];
}
m_data->m_stateLoggers.clear();
}
void PhysicsServerCommandProcessor::deleteCachedInverseKinematicsBodies()
{
for (int i = 0; i < m_data->m_inverseKinematicsHelpers.size(); i++)
@@ -931,6 +1005,7 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld()
{
deleteCachedInverseDynamicsBodies();
deleteCachedInverseKinematicsBodies();
deleteStateLoggers();
m_data->m_userConstraints.clear();
m_data->m_saveWorldBodyData.clear();
@@ -1544,7 +1619,85 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
}
#endif
case CMD_STATE_LOGGING:
{
serverStatusOut.m_type = CMD_STATE_LOGGING_FAILED;
hasStatus = true;
if (clientCmd.m_updateFlags & STATE_LOGGING_START_LOG)
{
if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_MINITAUR)
{
std::string fileName = clientCmd.m_stateLoggingArguments.m_fileName;
//either provide the minitaur by object unique Id, or search for first multibody with 8 motors...
if ((clientCmd.m_updateFlags & STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID)&& (clientCmd.m_stateLoggingArguments.m_numBodyUniqueIds>0))
{
int bodyUniqueId = clientCmd.m_stateLoggingArguments.m_bodyUniqueIds[0];
InteralBodyData* body = m_data->getHandle(bodyUniqueId);
if (body)
{
if (body->m_multiBody)
{
btAlignedObjectArray<std::string> motorNames;
motorNames.push_back("motor_front_leftR_joint");
motorNames.push_back("motor_front_leftL_joint");
motorNames.push_back("motor_back_leftR_joint");
motorNames.push_back("motor_back_leftL_joint");
motorNames.push_back("motor_front_rightL_joint");
motorNames.push_back("motor_front_rightR_joint");
motorNames.push_back("motor_back_rightL_joint");
motorNames.push_back("motor_back_rightR_joint");
btAlignedObjectArray<int> motorIdList;
for (int m=0;m<motorNames.size();m++)
{
for (int i=0;i<body->m_multiBody->getNumLinks();i++)
{
std::string jointName;
if (body->m_multiBody->getLink(i).m_jointName)
{
jointName = body->m_multiBody->getLink(i).m_jointName;
}
if (motorNames[m]==jointName)
{
motorIdList.push_back(i);
}
}
}
if (motorIdList.size()==8)
{
int loggerUid = m_data->m_stateLoggersUniqueId++;
MinitaurStateLogger* logger = new MinitaurStateLogger(loggerUid,fileName,body->m_multiBody, motorIdList);
m_data->m_stateLoggers.push_back(logger);
serverStatusOut.m_type = CMD_STATE_LOGGING_START_COMPLETED;
serverStatusOut.m_stateLoggingResultArgs.m_loggingUniqueId = loggerUid;
}
}
}
}
}
}
if ((clientCmd.m_updateFlags & STATE_LOGGING_STOP_LOG) && clientCmd.m_stateLoggingArguments.m_loggingUniqueId>=0)
{
serverStatusOut.m_type = CMD_STATE_LOGGING_COMPLETED;
for (int i=0;i<m_data->m_stateLoggers.size();i++)
{
if (m_data->m_stateLoggers[i]->m_loggingUniqueId==clientCmd.m_stateLoggingArguments.m_loggingUniqueId)
{
m_data->m_stateLoggers[i]->stop();
delete m_data->m_stateLoggers[i];
m_data->m_stateLoggers.removeAtIndex(i);
}
}
}
break;
}
case CMD_SET_VR_CAMERA_STATE:
{
@@ -4786,7 +4939,6 @@ void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId)
void PhysicsServerCommandProcessor::resetSimulation()
{
//clean up all data
deleteCachedInverseDynamicsBodies();
if (m_data && m_data->m_guiHelper)
{

View File

@@ -46,6 +46,7 @@ protected:
int createBodyInfoStream(int bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes);
void deleteCachedInverseDynamicsBodies();
void deleteCachedInverseKinematicsBodies();
void deleteStateLoggers();
public:
PhysicsServerCommandProcessor();

View File

@@ -613,12 +613,11 @@ enum eVRCameraEnums
VR_CAMERA_ROOT_TRACKING_OBJECT=4
};
enum eRobotLoggingEnums
enum eStateLoggingEnums
{
ROBOT_LOGGING_START_MINITAUR_LOG=1,
ROBOT_LOGGING_STOP_MINITAUR_LOG=1,
ROBOT_LOGGING_START_GENERIC_LOG=1,
ROBOT_LOGGING_STOP_GENERIC_LOG=1,
STATE_LOGGING_START_LOG=1,
STATE_LOGGING_STOP_LOG=2,
STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID=4,
};
struct VRCameraState
@@ -629,6 +628,21 @@ struct VRCameraState
};
struct StateLoggingRequest
{
char m_fileName[MAX_FILENAME_LENGTH];
int m_logType;//Minitaur, generic robot, VR states
int m_numBodyUniqueIds;////only if ROBOT_LOGGING_FILTER_OBJECT_UNIQUE_ID flag is set
int m_bodyUniqueIds[MAX_SDF_BODIES];
int m_loggingUniqueId;
};
struct StateLoggingResultArgs
{
int m_loggingUniqueId;
};
struct SharedMemoryCommand
{
int m_type;
@@ -670,6 +684,7 @@ struct SharedMemoryCommand
struct RequestRaycastIntersections m_requestRaycastIntersections;
struct LoadBunnyArgs m_loadBunnyArguments;
struct VRCameraState m_vrCameraStateArguments;
struct StateLoggingRequest m_stateLoggingArguments;
};
};
@@ -730,6 +745,8 @@ struct SharedMemoryStatus
struct b3UserConstraint m_userConstraintResultArgs;
struct SendVREvents m_sendVREvents;
struct SendRaycastHits m_raycastHits;
struct StateLoggingResultArgs m_stateLoggingResultArgs;
};
};

View File

@@ -48,7 +48,7 @@ enum EnumSharedMemoryClientCommand
CMD_REQUEST_VR_EVENTS_DATA,
CMD_SET_VR_CAMERA_STATE,
CMD_SYNC_BODY_INFO,
CMD_ROBOT_LOGGING,
CMD_STATE_LOGGING,
//don't go beyond this command!
CMD_MAX_CLIENT_COMMANDS,
@@ -123,6 +123,9 @@ enum EnumSharedMemoryServerStatus
CMD_REQUEST_RAY_CAST_INTERSECTIONS_COMPLETED,
CMD_SYNC_BODY_INFO_COMPLETED,
CMD_SYNC_BODY_INFO_FAILED,
CMD_STATE_LOGGING_COMPLETED,
CMD_STATE_LOGGING_START_COMPLETED,
CMD_STATE_LOGGING_FAILED,
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
CMD_MAX_SERVER_COMMANDS
};
@@ -304,9 +307,10 @@ enum
enum
{
ROBOT_LOGGING_MINITAUR = 0,
ROBOT_LOGGING_GENERIC_ROBOT = 1,
ROBOT_LOGGING_VR_CONTROLLERS = 2,
STATE_LOGGING_MINITAUR = 0,
STATE_LOGGING_GENERIC_ROBOT = 1,
STATE_LOGGING_VR_CONTROLLERS = 2,
STATE_LOGGING_COMMANDS = 3,
};

View File

@@ -0,0 +1,15 @@
import pybullet as p
cid = p.connect(p.SHARED_MEMORY)
if (cid < 0) :
p.connect(p.GUI)
p.loadURDF("plane.urdf")
quadruped = p.loadURDF("quadruped/quadruped.urdf")
logId = p.startStateLogging(p.STATE_LOGGING_MINITAUR,"LOG00048.TXT",[quadruped])
p.stepSimulation()
p.stepSimulation()
p.stepSimulation()
p.stepSimulation()
p.stepSimulation()
p.stopStateLogging(logId)

View File

@@ -2614,6 +2614,40 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
{
b3SharedMemoryCommandHandle commandHandle;
commandHandle = b3StateLoggingCommandInit(sm);
b3StateLoggingStart(commandHandle,loggingType,fileName);
if (objectUniqueIdsObj)
{
PyObject* seq = PySequence_Fast(objectUniqueIdsObj, "expected a sequence of object unique ids");
if (seq)
{
int len = PySequence_Size(objectUniqueIdsObj);
for (int i=0;i<len;i++)
{
int objectUid = pybullet_internalGetFloatFromSequence(seq, i);
b3StateLoggingAddLoggingObjectUniqueId(commandHandle,objectUid);
}
Py_DECREF(seq);
}
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
if (statusType==CMD_STATE_LOGGING_START_COMPLETED)
{
int loggingUniqueId = b3GetStatusLoggingUniqueId(statusHandle);
PyObject* loggingUidObj = PyInt_FromLong(loggingUniqueId);
return loggingUidObj;
}
}
Py_INCREF(Py_None);
return Py_None;
}
static PyObject* pybullet_stopStateLogging(PyObject* self, PyObject* args, PyObject *keywds)
@@ -2621,16 +2655,14 @@ static PyObject* pybullet_stopStateLogging(PyObject* self, PyObject* args, PyObj
b3SharedMemoryCommandHandle commandHandle;
b3SharedMemoryStatusHandle statusHandle;
int statusType;
PyObject* rayFromObj=0;
PyObject* rayToObj=0;
double from[3];
double to[3];
int loggingId=-1;
b3PhysicsClientHandle sm = 0;
static char *kwlist[] = { "loggingId", "physicsClientId", NULL };
int physicsClientId = 0;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "OO|i", kwlist,
&rayFromObj, &rayToObj,&physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist,
&loggingId,&physicsClientId))
return NULL;
sm = getPhysicsClient(physicsClientId);
@@ -2639,6 +2671,17 @@ static PyObject* pybullet_stopStateLogging(PyObject* self, PyObject* args, PyObj
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
if (loggingId>=0)
{
b3SharedMemoryCommandHandle commandHandle;
commandHandle = b3StateLoggingCommandInit(sm);
b3StateLoggingStop(commandHandle, loggingId);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
}
Py_INCREF(Py_None);
return Py_None;
}
@@ -5019,12 +5062,12 @@ 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,
{ "startStateLogging", (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), "
"Specify loggingType (STATE_LOG_MINITAUR, STATE_LOG_GENERIC_ROBOT, STATE_LOG_VR_CONTROLLERS etc), "
"fileName, optional objectUniqueId. Function returns int loggingUniqueId"
},
{ "stopRobotStateLogging", (PyCFunction)pybullet_stopStateLogging, METH_VARARGS | METH_KEYWORDS,
{ "stopStateLogging", (PyCFunction)pybullet_stopStateLogging, METH_VARARGS | METH_KEYWORDS,
"Stop logging of robot state, given a loggingUniqueId."
},
{ "rayTest", (PyCFunction)pybullet_rayTest, METH_VARARGS | METH_KEYWORDS,
@@ -5112,9 +5155,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);
PyModule_AddIntConstant(m, "STATE_LOGGING_MINITAUR", STATE_LOGGING_MINITAUR);
PyModule_AddIntConstant(m, "STATE_LOGGING_GENERIC_ROBOT", STATE_LOGGING_GENERIC_ROBOT);
PyModule_AddIntConstant(m, "STATE_LOGGING_VR_CONTROLLERS", STATE_LOGGING_VR_CONTROLLERS);
SpamError = PyErr_NewException("pybullet.error", NULL, NULL);
Py_INCREF(SpamError);