mirror of
https://github.com/bulletphysics/bullet3
synced 2025-01-18 21:10:05 +00:00
Replace spaces with tabs.
This commit is contained in:
parent
66a8685816
commit
f062847038
@ -1325,7 +1325,7 @@ int BulletMJCFImporter::getRootLinkIndex() const
|
||||
|
||||
std::string BulletMJCFImporter::getBodyName() const
|
||||
{
|
||||
return m_data->m_fileModelName;
|
||||
return m_data->m_fileModelName;
|
||||
}
|
||||
|
||||
bool BulletMJCFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
|
||||
|
@ -42,7 +42,7 @@ public:
|
||||
///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range)
|
||||
virtual std::string getLinkName(int linkIndex) const;
|
||||
|
||||
virtual std::string getBodyName() const;
|
||||
virtual std::string getBodyName() const;
|
||||
|
||||
/// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const;
|
||||
|
@ -272,7 +272,7 @@ std::string BulletURDFImporter::getLinkName(int linkIndex) const
|
||||
|
||||
std::string BulletURDFImporter::getBodyName() const
|
||||
{
|
||||
return m_data->m_urdfParser.getModel().m_name;
|
||||
return m_data->m_urdfParser.getModel().m_name;
|
||||
}
|
||||
|
||||
std::string BulletURDFImporter::getJointName(int linkIndex) const
|
||||
|
@ -35,7 +35,7 @@ public:
|
||||
|
||||
virtual void getLinkChildIndices(int linkIndex, btAlignedObjectArray<int>& childLinkIndices) const;
|
||||
|
||||
virtual std::string getBodyName() const;
|
||||
virtual std::string getBodyName() const;
|
||||
|
||||
virtual std::string getLinkName(int linkIndex) const;
|
||||
|
||||
|
@ -28,7 +28,7 @@ public:
|
||||
///pure virtual interfaces, precondition is a valid linkIndex (you can assert/terminate if the linkIndex is out of range)
|
||||
virtual std::string getLinkName(int linkIndex) const =0;
|
||||
|
||||
virtual std::string getBodyName() const = 0;
|
||||
virtual std::string getBodyName() const = 0;
|
||||
|
||||
/// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const { return false;}
|
||||
|
@ -20,7 +20,7 @@ struct BodyJointInfoCache
|
||||
{
|
||||
std::string m_baseName;
|
||||
btAlignedObjectArray<b3JointInfo> m_jointInfo;
|
||||
std::string m_bodyName;
|
||||
std::string m_bodyName;
|
||||
};
|
||||
|
||||
struct PhysicsClientSharedMemoryInternalData {
|
||||
@ -107,7 +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();
|
||||
info.m_bodyName = bodyJoints->m_bodyName.c_str();
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -308,7 +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;
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
|
||||
for (int i = 0; i < bf.m_multiBodies.size(); i++)
|
||||
{
|
||||
@ -421,7 +421,7 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
|
||||
BodyJointInfoCache* bodyJoints = new BodyJointInfoCache;
|
||||
m_data->m_bodyJointMap.insert(bodyUniqueId,bodyJoints);
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
|
||||
for (int i = 0; i < bf.m_multiBodies.size(); i++) {
|
||||
|
||||
|
@ -17,7 +17,7 @@ struct BodyJointInfoCache2
|
||||
{
|
||||
std::string m_baseName;
|
||||
btAlignedObjectArray<b3JointInfo> m_jointInfo;
|
||||
std::string m_bodyName;
|
||||
std::string m_bodyName;
|
||||
};
|
||||
|
||||
|
||||
@ -606,7 +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;
|
||||
bodyJoints->m_bodyName = serverCmd.m_dataStreamArguments.m_bodyName;
|
||||
|
||||
for (int i = 0; i < bf.m_multiBodies.size(); i++)
|
||||
{
|
||||
@ -933,7 +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();
|
||||
info.m_bodyName = bodyJoints->m_bodyName.c_str();
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -120,7 +120,7 @@ struct InteralBodyData
|
||||
btMultiBody* m_multiBody;
|
||||
btRigidBody* m_rigidBody;
|
||||
int m_testData;
|
||||
std::string m_bodyName;
|
||||
std::string m_bodyName;
|
||||
|
||||
btTransform m_rootLocalInertialFrame;
|
||||
btAlignedObjectArray<btTransform> m_linkLocalInertialFrames;
|
||||
@ -1608,8 +1608,8 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
|
||||
btMultiBody* mb = creation.getBulletMultiBody();
|
||||
btRigidBody* rb = creation.getRigidBody();
|
||||
|
||||
bodyHandle->m_bodyName = u2b.getBodyName();
|
||||
|
||||
bodyHandle->m_bodyName = u2b.getBodyName();
|
||||
|
||||
if (useMultiBody)
|
||||
{
|
||||
@ -2653,8 +2653,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());
|
||||
InteralBodyData* body = m_data->getHandle(bodyUniqueId);
|
||||
strcpy(serverStatusOut.m_dataStreamArguments.m_bodyName, body->m_bodyName.c_str());
|
||||
hasStatus = true;
|
||||
|
||||
} else
|
||||
|
@ -103,7 +103,7 @@ struct BulletDataStreamArgs
|
||||
{
|
||||
char m_bulletFileName[MAX_FILENAME_LENGTH];
|
||||
int m_bodyUniqueId;
|
||||
char m_bodyName[MAX_FILENAME_LENGTH];
|
||||
char m_bodyName[MAX_FILENAME_LENGTH];
|
||||
};
|
||||
|
||||
struct SetJointFeedbackArgs
|
||||
|
@ -201,7 +201,7 @@ struct b3UserConstraint
|
||||
struct b3BodyInfo
|
||||
{
|
||||
const char* m_baseName;
|
||||
const char* m_bodyName; // for btRigidBody, it does not have a base, but can still have a body name from urdf
|
||||
const char* m_bodyName; // for btRigidBody, it does not have a base, but can still have a body name from urdf
|
||||
};
|
||||
|
||||
|
||||
|
@ -1716,7 +1716,7 @@ static PyObject* pybullet_getBodyInfo(PyObject* self, PyObject* args, PyObject*
|
||||
{
|
||||
PyObject* pyListJointInfo = PyTuple_New(2);
|
||||
PyTuple_SetItem(pyListJointInfo, 0, PyString_FromString(info.m_baseName));
|
||||
PyTuple_SetItem(pyListJointInfo, 1, PyString_FromString(info.m_bodyName));
|
||||
PyTuple_SetItem(pyListJointInfo, 1, PyString_FromString(info.m_bodyName));
|
||||
return pyListJointInfo;
|
||||
}
|
||||
}
|
||||
@ -5146,8 +5146,8 @@ static PyMethodDef SpamMethods[] = {
|
||||
|
||||
{"getJointState", (PyCFunction)pybullet_getJointState, METH_VARARGS | METH_KEYWORDS,
|
||||
"Get the state (position, velocity etc) for a joint on a body."},
|
||||
|
||||
{"getLinkState", (PyCFunction)pybullet_getLinkState, METH_VARARGS | METH_KEYWORDS,
|
||||
|
||||
{"getLinkState", (PyCFunction)pybullet_getLinkState, METH_VARARGS | METH_KEYWORDS,
|
||||
"Provides extra information such as the Cartesian world coordinates"
|
||||
" center of mass (COM) of the link, relative to the world reference"
|
||||
" frame."},
|
||||
|
Loading…
Reference in New Issue
Block a user