This commit is contained in:
Erwin Coumans
2017-03-30 12:39:18 -07:00
50 changed files with 1546 additions and 1304 deletions

View File

@@ -871,6 +871,16 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[])
int width = 1024;
int height=768;
if (args.CheckCmdLineFlag("width"))
{
args.GetCmdLineArgument("width",width );
}
if (args.CheckCmdLineFlag("height"))
{
args.GetCmdLineArgument("height",height);
}
#ifndef NO_OPENGL3
SimpleOpenGL3App* simpleApp=0;
sUseOpenGL2 =args.CheckCmdLineFlag("opengl2");

View File

@@ -1026,6 +1026,11 @@ struct BulletMJCFImporterInternalData
{
handled = true;
}
if (n=="site")
{
handled = true;
}
if (!handled)
{
logger->reportWarning( (sourceFileLocation(xml) + ": unknown field '" + n + "'").c_str() );
@@ -1323,6 +1328,11 @@ int BulletMJCFImporter::getRootLinkIndex() const
return "";
}
std::string BulletMJCFImporter::getBodyName() const
{
return m_data->m_fileModelName;
}
bool BulletMJCFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
{
// UrdfLink* link = m_data->getLink(linkIndex);

View File

@@ -41,6 +41,8 @@ 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;
/// 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;

View File

@@ -269,6 +269,11 @@ std::string BulletURDFImporter::getLinkName(int linkIndex) const
}
return "";
}
std::string BulletURDFImporter::getBodyName() const
{
return m_data->m_urdfParser.getModel().m_name;
}
std::string BulletURDFImporter::getJointName(int linkIndex) const
{
@@ -956,9 +961,15 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha
}
break;
}
case URDF_GEOM_PLANE:
{
b3Warning("No default visual for URDF_GEOM_PLANE");
break;
}
default:
{
b3Warning("Error: unknown visual geometry type %i\n", visual->m_geometry.m_type);
}
}
//if we have a convex, tesselate into localVertices/localIndices

View File

@@ -34,6 +34,8 @@ public:
virtual int getRootLinkIndex() const;
virtual void getLinkChildIndices(int linkIndex, btAlignedObjectArray<int>& childLinkIndices) const;
virtual std::string getBodyName() const;
virtual std::string getLinkName(int linkIndex) const;

View File

@@ -15,7 +15,6 @@ public:
virtual ~URDFImporterInterface() {}
virtual bool loadURDF(const char* fileName, bool forceFixedBase = false)=0;
virtual bool loadSDF(const char* fileName, bool forceFixedBase = false) { return false;}
@@ -27,6 +26,13 @@ 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;
//various derived class in internal source code break with new pure virtual methods, so provide some default implementation
virtual std::string getBodyName() const
{
return "";
}
/// 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;}

View File

@@ -552,7 +552,6 @@ int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandl
return 0;
}
b3SharedMemoryCommandHandle b3RequestActualStateCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;

View File

@@ -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++)
{
@@ -418,6 +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;
for (int i = 0; i < bf.m_multiBodies.size(); i++) {

View File

@@ -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;
}

View File

@@ -120,6 +120,7 @@ struct InteralBodyData
btMultiBody* m_multiBody;
btRigidBody* m_rigidBody;
int m_testData;
std::string m_bodyName;
btTransform m_rootLocalInertialFrame;
btAlignedObjectArray<btTransform> m_linkLocalInertialFrames;
@@ -1579,6 +1580,7 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName,
{
btScalar mass = 0;
bodyHandle->m_rootLocalInertialFrame.setIdentity();
bodyHandle->m_bodyName = u2b.getBodyName();
btVector3 localInertiaDiagonal(0,0,0);
int urdfLinkIndex = u2b.getRootLinkIndex();
u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame);
@@ -1796,6 +1798,8 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
btMultiBody* mb = creation.getBulletMultiBody();
btRigidBody* rb = creation.getRigidBody();
bodyHandle->m_bodyName = u2b.getBodyName();
if (useMultiBody)
{
@@ -2525,7 +2529,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
serverStatusOut.m_type = CMD_BODY_INFO_COMPLETED;
serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = sdfInfoArgs.m_bodyUniqueId;
serverStatusOut.m_numDataStreamBytes = streamSizeInBytes;
serverStatusOut.m_dataStreamArguments.m_bodyName[0] = 0;
InternalBodyHandle* bodyHandle = m_data->getHandle(clientCmd.m_calculateJacobianArguments.m_bodyUniqueId);
if (bodyHandle)
{
strcpy(serverStatusOut.m_dataStreamArguments.m_bodyName,bodyHandle->m_bodyName.c_str());
}
serverStatusOut.m_numDataStreamBytes = streamSizeInBytes;
hasStatus = true;
break;
@@ -2852,6 +2864,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
@@ -5217,8 +5231,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
}
default:
{
BT_PROFILE("CMD_UNKNOWN");

View File

@@ -103,6 +103,7 @@ struct BulletDataStreamArgs
{
char m_bulletFileName[MAX_FILENAME_LENGTH];
int m_bodyUniqueId;
char m_bodyName[MAX_FILENAME_LENGTH];
};
struct SetJointFeedbackArgs
@@ -364,9 +365,6 @@ struct RequestActualStateArgs
int m_bodyUniqueId;
};
struct SendActualStateArgs
{
int m_bodyUniqueId;

View File

@@ -201,6 +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
};

View File

@@ -48,6 +48,9 @@ p.setRealTimeSimulation(useRealTimeSimulation)
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.getBodyInfo(i)[1])
while 1:
if (useRealTimeSimulation):

View File

@@ -221,6 +221,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
int freeIndex = -1;
int method = eCONNECT_GUI;
int i;
char* options="";
b3PhysicsClientHandle sm = 0;
if (sNumPhysicsClients >= MAX_PHYSICS_CLIENTS)
@@ -237,15 +238,24 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
const char* hostName = "localhost";
int size = PySequence_Size(args);
if (size == 1)
static char* kwlist1[] = {"method","key", "options", NULL};
static char* kwlist2[] = {"method","hostName", "port", "options", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|is", kwlist1, &method,&key,&options))
{
if (!PyArg_ParseTuple(args, "i", &method))
int port = -1;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|sis", kwlist2, &method,&hostName, &port,&options))
{
PyErr_SetString(SpamError,
"connectPhysicsServer expected argument GUI, "
"DIRECT, SHARED_MEMORY, UDP or TCP");
return NULL;
} else
{
PyErr_Clear();
if (port>=0)
{
udpPort = port;
tcpPort = port;
}
}
}
@@ -264,45 +274,12 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P
}
}
if (size == 2)
{
if (!PyArg_ParseTuple(args, "ii", &method, &key))
{
if (!PyArg_ParseTuple(args, "is", &method, &hostName))
{
PyErr_SetString(SpamError,
"connectPhysicsServer cannot parse second argument (either integer or string)");
return NULL;
}
else
{
PyErr_Clear();
}
}
}
if (size == 3)
{
int port = -1;
if (!PyArg_ParseTuple(args, "isi", &method, &hostName, &port))
{
PyErr_SetString(SpamError,
"connectPhysicsServer 3 arguments: method, hostname, port");
return NULL;
}
if (port >= 0)
{
udpPort = port;
tcpPort = port;
}
}
switch (method)
{
case eCONNECT_GUI:
{
int argc = 0;
char* argv[1] = {0};
int argc = 2;
char* argv[2] = {"unused",options};
#ifdef __APPLE__
sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv);
@@ -1714,8 +1691,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;
}
}
@@ -5161,7 +5139,7 @@ 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,
"Provides extra information such as the Cartesian world coordinates"
" center of mass (COM) of the link, relative to the world reference"