mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 05:40:05 +00:00
Get body name from getBodyInfo.
This commit is contained in:
parent
0a552c3ba1
commit
de3f91b64e
@ -20,6 +20,7 @@ struct BodyJointInfoCache
|
||||
{
|
||||
std::string m_baseName;
|
||||
btAlignedObjectArray<b3JointInfo> m_jointInfo;
|
||||
std::string m_bodyName;
|
||||
};
|
||||
|
||||
struct PhysicsClientSharedMemoryInternalData {
|
||||
@ -106,6 +107,7 @@ bool PhysicsClientSharedMemory::getBodyInfo(int bodyUniqueId, struct b3BodyInfo&
|
||||
{
|
||||
BodyJointInfoCache* bodyJoints = *bodyJointsPtr;
|
||||
info.m_baseName = bodyJoints->m_baseName.c_str();
|
||||
info.m_bodyName = bodyJoints->m_bodyName.c_str();
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -306,6 +308,7 @@ void PhysicsClientSharedMemory::processBodyJointInfo(int bodyUniqueId, const Sha
|
||||
|
||||
BodyJointInfoCache* bodyJoints = new BodyJointInfoCache;
|
||||
m_data->m_bodyJointMap.insert(bodyUniqueId,bodyJoints);
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
|
||||
for (int i = 0; i < bf.m_multiBodies.size(); i++)
|
||||
{
|
||||
@ -405,6 +408,7 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
|
||||
BodyJointInfoCache* bodyJoints = new BodyJointInfoCache;
|
||||
m_data->m_bodyJointMap.insert(bodyUniqueId,bodyJoints);
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
|
||||
for (int i = 0; i < bf.m_multiBodies.size(); i++) {
|
||||
|
||||
|
@ -17,6 +17,7 @@ struct BodyJointInfoCache2
|
||||
{
|
||||
std::string m_baseName;
|
||||
btAlignedObjectArray<b3JointInfo> m_jointInfo;
|
||||
std::string m_bodyName;
|
||||
};
|
||||
|
||||
|
||||
@ -605,6 +606,7 @@ void PhysicsDirect::processBodyJointInfo(int bodyUniqueId, const SharedMemorySta
|
||||
|
||||
BodyJointInfoCache2* bodyJoints = new BodyJointInfoCache2;
|
||||
m_data->m_bodyJointMap.insert(bodyUniqueId,bodyJoints);
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
|
||||
for (int i = 0; i < bf.m_multiBodies.size(); i++)
|
||||
{
|
||||
@ -931,6 +933,7 @@ bool PhysicsDirect::getBodyInfo(int bodyUniqueId, struct b3BodyInfo& info) const
|
||||
{
|
||||
BodyJointInfoCache2* bodyJoints = *bodyJointsPtr;
|
||||
info.m_baseName = bodyJoints->m_baseName.c_str();
|
||||
info.m_bodyName = bodyJoints->m_bodyName.c_str();
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -2629,6 +2629,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
serverStatusOut.m_numDataStreamBytes = m_data->m_urdfLinkNameMapper.at(m_data->m_urdfLinkNameMapper.size()-1)->m_memSerializer->getCurrentBufferSize();
|
||||
}
|
||||
serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = bodyUniqueId;
|
||||
InteralBodyData* body = m_data->getHandle(bodyUniqueId);
|
||||
strcpy(serverStatusOut.m_dataStreamArguments.m_bodyName, body->m_bodyName.c_str());
|
||||
hasStatus = true;
|
||||
|
||||
} else
|
||||
|
@ -101,6 +101,7 @@ struct BulletDataStreamArgs
|
||||
{
|
||||
char m_bulletFileName[MAX_FILENAME_LENGTH];
|
||||
int m_bodyUniqueId;
|
||||
char m_bodyName[MAX_FILENAME_LENGTH];
|
||||
};
|
||||
|
||||
struct SetJointFeedbackArgs
|
||||
|
@ -50,7 +50,7 @@ trailDuration = 15
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_GENERIC_ROBOT,"LOG0001.txt",[0,1,2])
|
||||
|
||||
for i in xrange(5):
|
||||
print "Body %d's name is %s." % (i, p.getBodyName(i)[0])
|
||||
print "Body %d's name is %s." % (i, p.getBodyInfo(i)[1])
|
||||
|
||||
while 1:
|
||||
if (useRealTimeSimulation):
|
||||
|
@ -1711,8 +1711,9 @@ static PyObject* pybullet_getBodyInfo(PyObject* self, PyObject* args, PyObject*
|
||||
struct b3BodyInfo info;
|
||||
if (b3GetBodyInfo(sm, bodyUniqueId, &info))
|
||||
{
|
||||
PyObject* pyListJointInfo = PyTuple_New(1);
|
||||
PyObject* pyListJointInfo = PyTuple_New(2);
|
||||
PyTuple_SetItem(pyListJointInfo, 0, PyString_FromString(info.m_baseName));
|
||||
PyTuple_SetItem(pyListJointInfo, 1, PyString_FromString(info.m_bodyName));
|
||||
return pyListJointInfo;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user