diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index ca7da8509..ac5258f2f 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -2685,28 +2685,28 @@ int b3StateLoggingSetLinkIndexB(b3SharedMemoryCommandHandle commandHandle, int l return 0; } -int b3StateLoggingSetBodyIndexA(b3SharedMemoryCommandHandle commandHandle, int bodyIndexA) +int b3StateLoggingSetBodyAUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyAUniqueId) { 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_FILTER_BODY_INDEX_A; - command->m_stateLoggingArguments.m_bodyIndexA = bodyIndexA; + command->m_updateFlags |= STATE_LOGGING_FILTER_BODY_UNIQUE_ID_A; + command->m_stateLoggingArguments.m_bodyUniqueIdA = bodyAUniqueId; } return 0; } -int b3StateLoggingSetBodyIndexB(b3SharedMemoryCommandHandle commandHandle, int bodyIndexB) +int b3StateLoggingSetBodyBUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyBUniqueId) { 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_FILTER_BODY_INDEX_B; - command->m_stateLoggingArguments.m_bodyIndexB = bodyIndexB; + command->m_updateFlags |= STATE_LOGGING_FILTER_BODY_UNIQUE_ID_B; + command->m_stateLoggingArguments.m_bodyUniqueIdB = bodyBUniqueId; } return 0; } diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index b59029553..202240564 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -365,8 +365,8 @@ int b3StateLoggingAddLoggingObjectUniqueId(b3SharedMemoryCommandHandle commandHa int b3StateLoggingSetMaxLogDof(b3SharedMemoryCommandHandle commandHandle, int maxLogDof); int b3StateLoggingSetLinkIndexA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA); int b3StateLoggingSetLinkIndexB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB); -int b3StateLoggingSetBodyIndexA(b3SharedMemoryCommandHandle commandHandle, int bodyIndexA); -int b3StateLoggingSetBodyIndexB(b3SharedMemoryCommandHandle commandHandle, int bodyIndexB); +int b3StateLoggingSetBodyAUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyAUniqueId); +int b3StateLoggingSetBodyBUniqueId(b3SharedMemoryCommandHandle commandHandle, int bodyBUniqueId); int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle); int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUniqueId); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 691728a23..318c3c630 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -962,8 +962,8 @@ struct ContactPointsStateLogger : public InternalStateLogger bool m_filterLinkB; int m_linkIndexA; int m_linkIndexB; - int m_bodyIndexA; - int m_bodyIndexB; + int m_bodyUniqueIdA; + int m_bodyUniqueIdB; ContactPointsStateLogger(int loggingUniqueId, const std::string& fileName, btMultiBodyDynamicsWorld* dynamicsWorld) :m_loggingTimeStamp(0), @@ -974,8 +974,8 @@ struct ContactPointsStateLogger : public InternalStateLogger m_filterLinkB(false), m_linkIndexA(-2), m_linkIndexB(-2), - m_bodyIndexA(-1), - m_bodyIndexB(-1) + m_bodyUniqueIdA(-1), + m_bodyUniqueIdB(-1) { m_loggingUniqueId = loggingUniqueId; m_loggingType = STATE_LOGGING_CONTACT_POINTS; @@ -1062,18 +1062,18 @@ struct ContactPointsStateLogger : public InternalStateLogger btAssert(bodyA || mblA); //apply the filter, if the user provides it - if (m_bodyIndexA >= 0) + if (m_bodyUniqueIdA >= 0) { - if ((m_bodyIndexA != objectIndexA) && - (m_bodyIndexA != objectIndexB)) + if ((m_bodyUniqueIdA != objectIndexA) && + (m_bodyUniqueIdA != objectIndexB)) continue; } //apply the second object filter, if the user provides it - if (m_bodyIndexB >= 0) + if (m_bodyUniqueIdB >= 0) { - if ((m_bodyIndexB != objectIndexA) && - (m_bodyIndexB != objectIndexB)) + if ((m_bodyUniqueIdB != objectIndexA) && + (m_bodyUniqueIdB != objectIndexB)) continue; } @@ -2290,13 +2290,13 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm logger->m_filterLinkB = true; logger->m_linkIndexB = clientCmd.m_stateLoggingArguments.m_linkIndexB; } - if ((clientCmd.m_updateFlags & STATE_LOGGING_FILTER_BODY_INDEX_A) && clientCmd.m_stateLoggingArguments.m_bodyIndexA > -1) + if ((clientCmd.m_updateFlags & STATE_LOGGING_FILTER_BODY_UNIQUE_ID_A) && clientCmd.m_stateLoggingArguments.m_bodyUniqueIdA > -1) { - logger->m_bodyIndexA = clientCmd.m_stateLoggingArguments.m_bodyIndexA; + logger->m_bodyUniqueIdA = clientCmd.m_stateLoggingArguments.m_bodyUniqueIdA; } - if ((clientCmd.m_updateFlags & STATE_LOGGING_FILTER_BODY_INDEX_B) && clientCmd.m_stateLoggingArguments.m_bodyIndexB > -1) + if ((clientCmd.m_updateFlags & STATE_LOGGING_FILTER_BODY_UNIQUE_ID_B) && clientCmd.m_stateLoggingArguments.m_bodyUniqueIdB > -1) { - logger->m_bodyIndexB = clientCmd.m_stateLoggingArguments.m_bodyIndexB; + logger->m_bodyUniqueIdB = clientCmd.m_stateLoggingArguments.m_bodyUniqueIdB; } m_data->m_stateLoggers.push_back(logger); serverStatusOut.m_type = CMD_STATE_LOGGING_START_COMPLETED; diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index f3a54c2e8..f91426eb7 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -631,8 +631,8 @@ enum eStateLoggingEnums STATE_LOGGING_MAX_LOG_DOF=8, STATE_LOGGING_FILTER_LINK_INDEX_A=16, STATE_LOGGING_FILTER_LINK_INDEX_B=32, - STATE_LOGGING_FILTER_BODY_INDEX_A=64, - STATE_LOGGING_FILTER_BODY_INDEX_B=128, + STATE_LOGGING_FILTER_BODY_UNIQUE_ID_A=64, + STATE_LOGGING_FILTER_BODY_UNIQUE_ID_B=128, }; struct VRCameraState @@ -654,8 +654,8 @@ struct StateLoggingRequest int m_maxLogDof; int m_linkIndexA; // only if STATE_LOGGING_FILTER_LINK_INDEX_A flag is set int m_linkIndexB; // only if STATE_LOGGING_FILTER_LINK_INDEX_B flag is set - int m_bodyIndexA; - int m_bodyIndexB; + int m_bodyUniqueIdA; // only if STATE_LOGGING_FILTER_BODY_UNIQUE_ID_A flag is set + int m_bodyUniqueIdB; // only if STATE_LOGGING_FILTER_BODY_UNIQUE_ID_B flag is set }; struct StateLoggingResultArgs diff --git a/examples/pybullet/examples/kuka_with_cube.py b/examples/pybullet/examples/kuka_with_cube.py index db6ceb247..a4668dd49 100644 --- a/examples/pybullet/examples/kuka_with_cube.py +++ b/examples/pybullet/examples/kuka_with_cube.py @@ -48,7 +48,7 @@ p.setRealTimeSimulation(useRealTimeSimulation) trailDuration = 15 logId1 = p.startStateLogging(p.STATE_LOGGING_GENERIC_ROBOT,"LOG0001.txt",[0,1,2]) -logId2 = p.startStateLogging(p.STATE_LOGGING_CONTACT_POINTS,"LOG0002.txt",bodyIndexA=1) +logId2 = p.startStateLogging(p.STATE_LOGGING_CONTACT_POINTS,"LOG0002.txt",bodyUniqueIdA=2) for i in xrange(5): print "Body %d's name is %s." % (i, p.getBodyInfo(i)[1]) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 467bbdcb1..9cb36b849 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -2678,16 +2678,16 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb char* fileName = 0; PyObject* objectUniqueIdsObj = 0; int maxLogDof = -1; - int bodyIndexA = -1; - int bodyIndexB = -1; + int bodyUniqueIdA = -1; + int bodyUniqueIdB = -1; int linkIndexA = -2; int linkIndexB = -2; - static char* kwlist[] = {"loggingType", "fileName", "objectUniqueIds", "maxLogDof", "bodyIndexA", "bodyIndexB", "linkIndexA", "linkIndexB", "physicsClientId", NULL}; + static char* kwlist[] = {"loggingType", "fileName", "objectUniqueIds", "maxLogDof", "bodyUniqueIdA", "bodyUniqueIdB", "linkIndexA", "linkIndexB", "physicsClientId", NULL}; int physicsClientId = 0; if (!PyArg_ParseTupleAndKeywords(args, keywds, "is|Oiiiiii", kwlist, - &loggingType, &fileName, &objectUniqueIdsObj, &maxLogDof, &bodyIndexA, &bodyIndexB, &linkIndexA, &linkIndexB, &physicsClientId)) + &loggingType, &fileName, &objectUniqueIdsObj, &maxLogDof, &bodyUniqueIdA, &bodyUniqueIdB, &linkIndexA, &linkIndexB, &physicsClientId)) return NULL; sm = getPhysicsClient(physicsClientId); @@ -2723,13 +2723,13 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb b3StateLoggingSetMaxLogDof(commandHandle, maxLogDof); } - if (bodyIndexA > -1) + if (bodyUniqueIdA > -1) { - b3StateLoggingSetLinkIndexA(commandHandle, bodyIndexA); + b3StateLoggingSetBodyAUniqueId(commandHandle, bodyUniqueIdA); } - if (bodyIndexB > -1) + if (bodyUniqueIdB > -1) { - b3StateLoggingSetBodyIndexB(commandHandle, bodyIndexB); + b3StateLoggingSetBodyBUniqueId(commandHandle, bodyUniqueIdB); } if (linkIndexA > -2) {