From 23ecbab7b355b900f34e3f92b0ee55c08547be68 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 11 Sep 2018 13:24:35 -0700 Subject: [PATCH] fix setup.py and pybullet to work better with eglPlugin on Linux --- .../Gwen/Renderers/OpenGL_DebugFont.cpp | 19 +- examples/pybullet/examples/eglRenderTest.py | 31 +- examples/pybullet/pybullet.c | 312 +++++++++--------- setup.py | 62 ++-- 4 files changed, 201 insertions(+), 223 deletions(-) diff --git a/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.cpp b/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.cpp index 3b37eafbc..c65d76e36 100644 --- a/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.cpp +++ b/examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.cpp @@ -14,25 +14,10 @@ #include #include #else -#ifdef GLEW_STATIC #include "glad/gl.h" -#else -#ifdef NO_GLEW -#define GL_GLEXT_LEGACY -#include "third_party/GL/gl/include/GL/gl.h" -#include "third_party/GL/gl/include/GL/glext.h" -#else +#endif//__APPLE__ -#ifdef BT_NO_GLAD -#include -#else -#include "glad/glad.h" -#endif - -#endif //NO_GLEW -#endif //GLEW_STATIC -#endif//(__APPLE__) -#endif +#endif //B3_USE_GLFW #include "FontData.h" diff --git a/examples/pybullet/examples/eglRenderTest.py b/examples/pybullet/examples/eglRenderTest.py index 5e3143b80..6d51c4bb8 100644 --- a/examples/pybullet/examples/eglRenderTest.py +++ b/examples/pybullet/examples/eglRenderTest.py @@ -8,7 +8,7 @@ p.connect(p.DIRECT) plugin = p.loadPlugin(egl.get_filename(), "_eglRendererPlugin") print("plugin=",plugin) - + p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0) p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0) @@ -26,15 +26,22 @@ upAxisIndex = 2 while (p.isConnected()): - - for yaw in range (0,360,10) : - p.stepSimulation() - #viewMatrix = [1.0, 0.0, -0.0, 0.0, -0.0, 0.1736481785774231, -0.9848078489303589, 0.0, 0.0, 0.9848078489303589, 0.1736481785774231, 0.0, -0.0, -5.960464477539063e-08, -4.0, 1.0] - viewMatrix = p.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) - projectionMatrix = [1.0825318098068237, 0.0, 0.0, 0.0, 0.0, 1.732050895690918, 0.0, 0.0, 0.0, 0.0, -1.0002000331878662, -1.0, 0.0, 0.0, -0.020002000033855438, 0.0] - img_arr = p.getCameraImage(pixelWidth, pixelHeight, viewMatrix=viewMatrix, projectionMatrix=projectionMatrix, shadow=1,lightDirection=[1,1,1]) - #time.sleep(.1) - #print("img_arr=",img_arr) - - + for yaw in range (0,360,10) : + start = time.time() + p.stepSimulation() + stop = time.time() + print ("stepSimulation %f" % (stop - start)) + + #viewMatrix = [1.0, 0.0, -0.0, 0.0, -0.0, 0.1736481785774231, -0.9848078489303589, 0.0, 0.0, 0.9848078489303589, 0.1736481785774231, 0.0, -0.0, -5.960464477539063e-08, -4.0, 1.0] + viewMatrix = p.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) + projectionMatrix = [1.0825318098068237, 0.0, 0.0, 0.0, 0.0, 1.732050895690918, 0.0, 0.0, 0.0, 0.0, -1.0002000331878662, -1.0, 0.0, 0.0, -0.020002000033855438, 0.0] + + start = time.time() + img_arr = p.getCameraImage(pixelWidth, pixelHeight, viewMatrix=viewMatrix, projectionMatrix=projectionMatrix, shadow=1,lightDirection=[1,1,1]) + stop = time.time() + print ("renderImage %f" % (stop - start)) + #time.sleep(.1) + #print("img_arr=",img_arr) + + p.unloadPlugin(plugin) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 525422b6f..864c7cdfb 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -250,7 +250,7 @@ static int pybullet_internalGetVector3FromSequence(PyObject* seq, int index, dou } else { - item = PyTuple_GET_ITEM(seq, index); + item = PyTuple_GET_ITEM(seq, index); pybullet_internalSetVectord(item,vec); } return v; @@ -268,7 +268,7 @@ static int pybullet_internalGetVector4FromSequence(PyObject* seq, int index, dou } else { - item = PyTuple_GET_ITEM(seq, index); + item = PyTuple_GET_ITEM(seq, index); pybullet_internalSetVector4d(item,vec); } return v; @@ -338,7 +338,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P 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)) { int port = -1; @@ -385,7 +385,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P { case eCONNECT_GUI: { - + #ifdef __APPLE__ sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv); @@ -401,7 +401,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P } case eCONNECT_GUI_SERVER: { - + #ifdef __APPLE__ sm = b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(argc, argv); #else @@ -513,7 +513,7 @@ static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args, P statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); - if (statusType != CMD_SYNC_BODY_INFO_COMPLETED) + if (statusType != CMD_SYNC_BODY_INFO_COMPLETED) { printf("Connection terminated, couldn't get body info\n"); b3DisconnectSharedMemory(sm); @@ -652,7 +652,7 @@ static PyObject* pybullet_getConnectionInfo(PyObject* self, PyObject* args, PyOb static PyObject* pybullet_syncBodyInfo(PyObject* self, PyObject* args, PyObject* keywds) { - + b3PhysicsClientHandle sm = 0; int physicsClientId = 0; static char* kwlist[] = {"physicsClientId", NULL}; @@ -670,18 +670,18 @@ static PyObject* pybullet_syncBodyInfo(PyObject* self, PyObject* args, PyObject* PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - - + + command = b3InitSyncBodyInfoCommand(sm); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); - + if (statusType != CMD_SYNC_BODY_INFO_COMPLETED) { PyErr_SetString(SpamError, "Error in syncBodyzInfo command."); return NULL; } - + Py_INCREF(Py_None); return Py_None; } @@ -809,11 +809,11 @@ static PyObject* pybullet_getUserDataId(PyObject* self, PyObject* args, PyObject const char* key = ""; int userDataId; - + static char* kwlist[] = {"bodyUniqueId", "key", "linkIndex", "visualShapeIndex", "physicsClientId", NULL}; - + if (!PyArg_ParseTupleAndKeywords(args, keywds, "is|iii", kwlist, &bodyUniqueId, &key, &linkIndex, &visualShapeIndex, &physicsClientId)) { return NULL; @@ -853,11 +853,11 @@ static PyObject* pybullet_getUserData(PyObject* self, PyObject* args, PyObject* if (!b3GetUserData(sm, userDataId, &value)) { - + Py_INCREF(Py_None); return Py_None; } - if (value.m_type != USER_DATA_VALUE_TYPE_STRING) + if (value.m_type != USER_DATA_VALUE_TYPE_STRING) { PyErr_SetString(SpamError, "User data value has unknown type"); return NULL; @@ -1140,7 +1140,7 @@ static PyObject* pybullet_saveState(PyObject* self, PyObject* args, PyObject* ke } stateId = b3GetStatusGetStateId(statusHandle); - return PyInt_FromLong(stateId); + return PyInt_FromLong(stateId); } static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* keywds) @@ -1225,21 +1225,21 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO PyObject* localInertiaDiagonalObj=0; b3PhysicsClientHandle sm = 0; - + int physicsClientId = 0; static char* kwlist[] = {"bodyUniqueId", "linkIndex", "mass", "lateralFriction", "spinningFriction", "rollingFriction","restitution", "linearDamping", "angularDamping", "contactStiffness", "contactDamping", "frictionAnchor", "localInertiaDiagonal", "ccdSweptSphereRadius", "contactProcessingThreshold", "activationState", "physicsClientId", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|dddddddddiOddii", kwlist, &bodyUniqueId, &linkIndex,&mass, &lateralFriction, &spinningFriction, &rollingFriction, &restitution,&linearDamping, &angularDamping, &contactStiffness, &contactDamping, &frictionAnchor, &localInertiaDiagonalObj, &ccdSweptSphereRadius, &contactProcessingThreshold,&activationState, &physicsClientId)) { return NULL; } - + sm = getPhysicsClient(physicsClientId); if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - + if ((contactStiffness>=0 && contactDamping <0)||(contactStiffness<0 && contactDamping >=0)) { PyErr_SetString(SpamError, "Both contactStiffness and contactDamping needs to be set together."); @@ -1249,7 +1249,7 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO { b3SharedMemoryCommandHandle command = b3InitChangeDynamicsInfo(sm); b3SharedMemoryStatusHandle statusHandle; - + if (mass >= 0) { b3ChangeDynamicsInfoSetMass(command, bodyUniqueId, linkIndex, mass); @@ -1308,7 +1308,7 @@ static PyObject* pybullet_changeDynamicsInfo(PyObject* self, PyObject* args, PyO } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); } - + Py_INCREF(Py_None); return Py_None; } @@ -1320,7 +1320,7 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje int linkIndex = -2; b3PhysicsClientHandle sm = 0; - + int physicsClientId = 0; static char* kwlist[] = {"bodyUniqueId", "linkIndex", "physicsClientId", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist, &bodyUniqueId, &linkIndex, &physicsClientId)) @@ -1338,7 +1338,7 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje b3SharedMemoryCommandHandle cmd_handle; b3SharedMemoryStatusHandle status_handle; struct b3DynamicsInfo info; - + if (bodyUniqueId < 0) { @@ -1358,15 +1358,15 @@ static PyObject* pybullet_getDynamicsInfo(PyObject* self, PyObject* args, PyObje PyErr_SetString(SpamError, "getDynamicsInfo failed; invalid return status"); return NULL; } - + if (b3GetDynamicsInfo(status_handle, &info)) { - + int numFields = 10; PyObject* pyDynamicsInfo = PyTuple_New(numFields); PyTuple_SetItem(pyDynamicsInfo, 0, PyFloat_FromDouble(info.m_mass)); PyTuple_SetItem(pyDynamicsInfo, 1, PyFloat_FromDouble(info.m_lateralFrictionCoeff)); - + { PyObject* pyInertiaDiag = PyTuple_New(3); PyTuple_SetItem(pyInertiaDiag, 0, PyFloat_FromDouble(info.m_localInertialDiagonal[0])); @@ -1437,8 +1437,8 @@ static PyObject* pybullet_getPhysicsEngineParameters(PyObject* self, PyObject* a //for now, return a subset, expose more/all on request val = Py_BuildValue("{s:d,s:i,s:i,s:i,s:d,s:d,s:d}", - "fixedTimeStep", params.m_deltaTime, - "numSubSteps", params.m_numSimulationSubSteps, + "fixedTimeStep", params.m_deltaTime, + "numSubSteps", params.m_numSimulationSubSteps, "numSolverIterations", params.m_numSolverIterations, "useRealTimeSimulation", params.m_useRealTimeSimulation, "gravityAccelerationX", params.m_gravityAcceleration[0], @@ -1447,9 +1447,9 @@ static PyObject* pybullet_getPhysicsEngineParameters(PyObject* self, PyObject* a ); return val; } - //"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","restitutionVelocityThreshold", "erp", "contactERP", "frictionERP", + //"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","restitutionVelocityThreshold", "erp", "contactERP", "frictionERP", //val = Py_BuildValue("{s:i,s:i}","isConnected", isConnected, "connectionMethod", method); - + } @@ -1479,9 +1479,9 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar int enableSAT = -1; int constraintSolverType=-1; double globalCFM = -1; - + int minimumSolverIslandSize = -1; - + int physicsClientId = 0; static char* kwlist[] = {"fixedTimeStep", "numSolverIterations", "useSplitImpulse", "splitImpulsePenetrationThreshold", "numSubSteps", "collisionFilterMode", "contactBreakingThreshold", "maxNumCmdPer1ms", "enableFileCaching","restitutionVelocityThreshold", "erp", "contactERP", "frictionERP", "enableConeFriction", "deterministicOverlappingPairs", "allowedCcdPenetration", "jointFeedbackMode", "solverResidualThreshold", "contactSlop", "enableSAT", "constraintSolverType", "globalCFM", "minimumSolverIslandSize", "physicsClientId", NULL}; @@ -1829,29 +1829,29 @@ static PyObject* pybullet_loadSoftBody(PyObject* self, PyObject* args, PyObject* { int physicsClientId = 0; int flags = 0; - + static char* kwlist[] = {"fileName", "scale", "mass", "collisionMargin", "physicsClientId", NULL}; - + int bodyUniqueId= -1; const char* fileName = ""; double scale = -1; double mass = -1; double collisionMargin = -1; - + b3PhysicsClientHandle sm = 0; - + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|dddi", kwlist, &fileName, &scale, &mass, &collisionMargin, &physicsClientId)) { return NULL; } - + sm = getPhysicsClient(physicsClientId); if (sm == 0) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - + if (strlen(fileName)) { b3SharedMemoryStatusHandle statusHandle; @@ -2154,7 +2154,7 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar } { - + int numJoints; int i; b3SharedMemoryCommandHandle commandHandle; @@ -2169,7 +2169,7 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar PyObject* kdsSeq = 0; numJoints = b3GetNumJoints(sm, bodyUniqueId); - + if ((controlMode != CONTROL_MODE_VELOCITY) && (controlMode != CONTROL_MODE_TORQUE) && (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) @@ -2185,7 +2185,7 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar PyErr_SetString(SpamError, "expected a sequence of joint indices"); return NULL; } - + numControlledDofs = PySequence_Size(jointIndicesObj); if (numControlledDofs==0) { @@ -2193,7 +2193,7 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar Py_INCREF(Py_None); return Py_None; } - + { int i; for (i = 0; i < numControlledDofs; i++) @@ -2219,7 +2219,7 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar } targetVelocitiesSeq = PySequence_Fast(targetVelocitiesObj, "expected a sequence of target velocities"); } - + if (targetPositionsObj) { int num = PySequence_Size(targetPositionsObj); @@ -2233,10 +2233,10 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar PyErr_SetString(SpamError, "number of target positions should match the number of joint indices"); return NULL; } - + targetPositionsSeq = PySequence_Fast(targetPositionsObj, "expected a sequence of target positions"); } - + if (forcesObj) { int num = PySequence_Size(forcesObj); @@ -2251,15 +2251,15 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar { Py_DECREF(targetPositionsSeq); } - + PyErr_SetString(SpamError, "number of forces should match the joint indices"); return NULL; } - + forcesSeq = PySequence_Fast(forcesObj, "expected a sequence of forces"); } - + if (kpsObj) { int num = PySequence_Size(kpsObj); @@ -2282,11 +2282,11 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar PyErr_SetString(SpamError, "number of kps should match the joint indices"); return NULL; } - + kpsSeq = PySequence_Fast(kpsObj, "expected a sequence of kps"); } - + if (kdsObj) { int num = PySequence_Size(kdsObj); @@ -2309,11 +2309,11 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar { Py_DECREF(kpsSeq); } - + PyErr_SetString(SpamError, "number of kds should match the number of joint indices"); return NULL; } - + kdsSeq = PySequence_Fast(kdsObj, "expected a sequence of kds"); } @@ -2338,17 +2338,17 @@ static PyObject* pybullet_setJointMotorControlArray(PyObject* self, PyObject* ar targetPosition = pybullet_internalGetFloatFromSequence(targetPositionsSeq, i); } - + if (forcesSeq) { force = pybullet_internalGetFloatFromSequence(forcesSeq, i); } - + if (kpsSeq) { kp = pybullet_internalGetFloatFromSequence(kpsSeq, i); } - + if (kdsSeq) { kd = pybullet_internalGetFloatFromSequence(kdsSeq, i); @@ -2830,7 +2830,7 @@ static PyObject* pybullet_getAABB(PyObject* self, PyObject* args, PyObject* keyw int bodyUniqueId = -1; int linkIndex = -1; - + b3PhysicsClientHandle sm = 0; int physicsClientId = 0; static char* kwlist[] = {"bodyUniqueId", "linkIndex", "physicsClientId", NULL}; @@ -3305,7 +3305,7 @@ static PyObject* pybullet_getConstraintUniqueId(PyObject* self, PyObject* args, int physicsClientId = 0; int serialIndex = -1; b3PhysicsClientHandle sm = 0; - + static char* kwlist[] = {"serialIndex", "physicsClientId", NULL}; if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &serialIndex, &physicsClientId)) { @@ -3317,11 +3317,11 @@ static PyObject* pybullet_getConstraintUniqueId(PyObject* self, PyObject* args, PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - + { int userConstraintId = -1; userConstraintId = b3GetUserConstraintId(sm, serialIndex); - + #if PY_MAJOR_VERSION >= 3 return PyLong_FromLong(userConstraintId); #else @@ -3658,7 +3658,7 @@ static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args, PyObject* // info.m_jointDamping, // info.m_jointFriction); PyTuple_SetItem(pyListJointInfo, 0, PyInt_FromLong(info.m_jointIndex)); - + if (info.m_jointName[0]) { PyTuple_SetItem(pyListJointInfo, 1, @@ -3668,7 +3668,7 @@ static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args, PyObject* PyTuple_SetItem(pyListJointInfo, 1, PyString_FromString("not available")); } - + PyTuple_SetItem(pyListJointInfo, 2, PyInt_FromLong(info.m_jointType)); PyTuple_SetItem(pyListJointInfo, 3, PyInt_FromLong(info.m_qIndex)); PyTuple_SetItem(pyListJointInfo, 4, PyInt_FromLong(info.m_uIndex)); @@ -3687,7 +3687,7 @@ static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args, PyObject* PyFloat_FromDouble(info.m_jointMaxVelocity)); if (info.m_linkName[0]) { - + PyTuple_SetItem(pyListJointInfo, 12, PyString_FromString(info.m_linkName)); } else @@ -3889,7 +3889,7 @@ static PyObject* pybullet_getJointStates(PyObject* self, PyObject* args, PyObjec PyErr_SetString(SpamError, "expected a sequence of joint indices"); return NULL; } - + numRequestedJoints = PySequence_Size(jointIndicesObj); if (numRequestedJoints==0) { @@ -3897,8 +3897,8 @@ static PyObject* pybullet_getJointStates(PyObject* self, PyObject* args, PyObjec Py_INCREF(Py_None); return Py_None; } - - + + cmd_handle = b3RequestActualStateCommandInit(sm, bodyUniqueId); @@ -4080,7 +4080,7 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args, PyObject* PyFloat_FromDouble(linkState.m_worldLinkFrameOrientation[i])); } - + if (computeLinkVelocity) { @@ -4285,7 +4285,7 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); - + if (statusType == CMD_USER_DEBUG_DRAW_COMPLETED) { debugItemUniqueId = b3GetDebugItemUniqueId(statusHandle); @@ -4350,7 +4350,7 @@ static PyObject* pybullet_addUserDebugLine(PyObject* self, PyObject* args, PyObj res = pybullet_internalSetVectord(lineColorRGBObj, colorRGB); } - + commandHandle = b3InitUserDebugDrawAddLine3D(sm, fromXYZ, toXYZ, colorRGB, lineWidth, lifeTime); if (parentObjectUniqueId>=0) @@ -4492,7 +4492,7 @@ static PyObject* pybullet_startStateLogging(PyObject* self, PyObject* args, PyOb { b3StateLoggingSetMaxLogDof(commandHandle, maxLogDof); } - + if (bodyUniqueIdA > -1) { b3StateLoggingSetBodyAUniqueId(commandHandle, bodyUniqueIdA); @@ -4768,12 +4768,12 @@ static PyObject* pybullet_rayTestBatch(PyObject* self, PyObject* args, PyObject* return NULL; } - - + + commandHandle = b3CreateRaycastBatchCommandInit(sm); b3RaycastBatchSetNumThreads(commandHandle, numThreads); - + if (rayFromObjList) { PyObject* seqRayFromObj = PySequence_Fast(rayFromObjList, "expected a sequence of rayFrom positions"); @@ -4792,7 +4792,7 @@ static PyObject* pybullet_rayTestBatch(PyObject* self, PyObject* args, PyObject* } else { int i; - + if (lenFrom > MAX_RAY_INTERSECTION_BATCH_SIZE_STREAMING) { PyErr_SetString(SpamError, "Number of rays exceed the maximum batch size."); @@ -4807,13 +4807,13 @@ static PyObject* pybullet_rayTestBatch(PyObject* self, PyObject* args, PyObject* PyObject* rayToObj = PySequence_GetItem(seqRayToObj,i); double rayFromWorld[3]; double rayToWorld[3]; - + if ((pybullet_internalSetVectord(rayFromObj, rayFromWorld)) && (pybullet_internalSetVectord(rayToObj, rayToWorld))) { //todo: better to upload all rays at once - //b3RaycastBatchAddRay(commandHandle, rayFromWorld, rayToWorld); - b3RaycastBatchAddRays(sm, commandHandle, rayFromWorld, rayToWorld,1); + //b3RaycastBatchAddRay(commandHandle, rayFromWorld, rayToWorld); + b3RaycastBatchAddRays(sm, commandHandle, rayFromWorld, rayToWorld,1); } else { PyErr_SetString(SpamError, "Items in the from/to positions need to be an [x,y,z] list of 3 floats/doubles"); @@ -4852,7 +4852,7 @@ static PyObject* pybullet_rayTestBatch(PyObject* self, PyObject* args, PyObject* int i; b3PushProfileTiming(sm, "convertRaycastInformationToPython"); b3GetRaycastInformation(sm, &raycastInfo); - + rayHitsObj = PyTuple_New(raycastInfo.m_numRayHits); for (i = 0; i < raycastInfo.m_numRayHits; i++) { @@ -5068,7 +5068,7 @@ static PyObject* pybullet_getMouseEvents(PyObject* self, PyObject* args, PyObjec PyTuple_SetItem(mouseEventObj,3, PyInt_FromLong(mouseEventsData.m_mouseEvents[i].m_buttonIndex)); PyTuple_SetItem(mouseEventObj,4, PyInt_FromLong(mouseEventsData.m_mouseEvents[i].m_buttonState)); PyTuple_SetItem(mouseEventsObj,i,mouseEventObj); - + } return mouseEventsObj; } @@ -5456,7 +5456,7 @@ static PyObject* pybullet_getCollisionShapeData(PyObject* self, PyObject* args, PyTuple_SetItem(collisionShapeObList, 6, vec); } - + PyTuple_SetItem(pyResultList, i, collisionShapeObList); } return pyResultList; @@ -5605,7 +5605,7 @@ static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyOb PyObject* rgbaColorObj = 0; PyObject* specularColorObj = 0; - + b3PhysicsClientHandle sm = 0; static char* kwlist[] = {"objectUniqueId", "linkIndex", "shapeIndex", "textureUniqueId", "rgbaColor", "specularColor", "physicsClientId", NULL}; @@ -5664,7 +5664,7 @@ static PyObject* pybullet_changeTexture(PyObject* self, PyObject* args, PyObject int physicsClientId = 0; int width=-1; int height=-1; - + PyObject* pixelsObj = 0; b3PhysicsClientHandle sm = 0; @@ -5701,7 +5701,7 @@ static PyObject* pybullet_changeTexture(PyObject* self, PyObject* args, PyObject item = PyTuple_GET_ITEM(seqPixels, i); pixelBuffer[i] = PyLong_AsLong(item); } - } + } commandHandle = b3CreateChangeTextureCommandInit(sm,textureUniqueId, width,height,(const char*) pixelBuffer); free(pixelBuffer); @@ -6070,7 +6070,7 @@ static PyObject* pybullet_removeUserConstraint(PyObject* self, PyObject* args, P }; /* -static PyObject* pybullet_updateUserConstraint(PyObject* self, PyObject* args, PyObject *keywds) +static PyObject* pybullet_updateUserConstraint(PyObject* self, PyObject* args, PyObject *keywds) { return NULL; } @@ -6152,7 +6152,7 @@ static PyObject* pybullet_createCollisionShape(PyObject* self, PyObject* args, P PyObject* halfExtentsObj=0; static char* kwlist[] = {"shapeType","radius","halfExtents", "height", "fileName", "meshScale", "planeNormal", "flags", "collisionFramePosition", "collisionFrameOrientation", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|dOdsOOiOOi", kwlist, + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|dOdsOOiOOi", kwlist, &shapeType, &radius,&halfExtentsObj, &height, &fileName, &meshScaleObj, &planeNormalObj, &flags,&collisionFramePositionObj, &collisionFrameOrientationObj, &physicsClientId)) { return NULL; @@ -6247,8 +6247,8 @@ static PyObject* pybullet_createCollisionShapeArray(PyObject* self, PyObject* ar PyObject* flagsArray = 0; PyObject* collisionFramePositionObjArray = 0; PyObject* collisionFrameOrientationObjArray = 0; - - static char* kwlist[] = { "shapeTypes", "radii", "halfExtents", "lengths", "fileNames", "meshScales", "planeNormals", + + static char* kwlist[] = { "shapeTypes", "radii", "halfExtents", "lengths", "fileNames", "meshScales", "planeNormals", "flags", "collisionFramePositions", "collisionFrameOrientations", "physicsClientId", NULL }; if (!PyArg_ParseTupleAndKeywords(args, keywds, "O|OOOOOOOOOi", kwlist, &shapeTypeArray, &radiusArray, &halfExtentsObjArray, &lengthArray, &fileNameArray, &meshScaleObjArray, &planeNormalObjArray, &flagsArray, &collisionFramePositionObjArray, &collisionFrameOrientationObjArray, &physicsClientId)) @@ -6263,7 +6263,7 @@ static PyObject* pybullet_createCollisionShapeArray(PyObject* self, PyObject* ar } - + { b3SharedMemoryCommandHandle commandHandle = b3CreateCollisionShapeCommandInit(sm); @@ -6382,7 +6382,7 @@ static PyObject* pybullet_createCollisionShapeArray(PyObject* self, PyObject* ar { shapeIndex = b3CreateCollisionShapeAddMesh(commandHandle, fileName, meshScale); } - + } if (shapeType == GEOM_PLANE) { @@ -6461,7 +6461,7 @@ static PyObject* pybullet_createCollisionShapeArray(PyObject* self, PyObject* ar static PyObject* pybullet_createVisualShape(PyObject* self, PyObject* args, PyObject* keywds) { - + int physicsClientId = 0; b3PhysicsClientHandle sm = 0; @@ -6486,11 +6486,11 @@ static PyObject* pybullet_createVisualShape(PyObject* self, PyObject* args, PyOb double visualFramePosition[3]={0,0,0}; PyObject* visualFrameOrientationObj=0; double visualFrameOrientation[4]={0,0,0,1}; - + PyObject* halfExtentsObj=0; static char* kwlist[] = {"shapeType","radius","halfExtents", "length", "fileName", "meshScale", "planeNormal", "flags", "rgbaColor", "specularColor", "visualFramePosition", "visualFrameOrientation", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|dOdsOOiOOOOi", kwlist, + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|dOdsOOiOOOOi", kwlist, &shapeType, &radius,&halfExtentsObj, &length, &fileName, &meshScaleObj, &planeNormalObj, &flags, &rgbaColorObj, &specularColorObj, &visualFramePositionObj, &visualFrameOrientationObj, &physicsClientId)) { return NULL; @@ -6502,7 +6502,7 @@ static PyObject* pybullet_createVisualShape(PyObject* self, PyObject* args, PyOb PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - + if (shapeType>=GEOM_SPHERE) { b3SharedMemoryStatusHandle statusHandle; @@ -6520,7 +6520,7 @@ static PyObject* pybullet_createVisualShape(PyObject* self, PyObject* args, PyOb pybullet_internalSetVectord(halfExtentsObj,halfExtents); shapeIndex = b3CreateVisualShapeAddBox(commandHandle,halfExtents); } - + if (shapeType==GEOM_CAPSULE && radius>0 && length>=0) { shapeIndex = b3CreateVisualShapeAddCapsule(commandHandle,radius,length); @@ -6573,7 +6573,7 @@ static PyObject* pybullet_createVisualShape(PyObject* self, PyObject* args, PyOb b3CreateVisualShapeSetChildTransform(commandHandle, shapeIndex, visualFramePosition,visualFrameOrientation); } - + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); @@ -6610,7 +6610,7 @@ static PyObject* pybullet_createVisualShapeArray(PyObject* self, PyObject* args, static char* kwlist[] = { "shapeTypes", "radii", "halfExtents", "lengths", "fileNames", "meshScales", "planeNormals", "flags", "rgbaColors", "visualFramePositions", "visualFrameOrientations", "physicsClientId", NULL }; - + if (!PyArg_ParseTupleAndKeywords(args, keywds, "O|OOOOOOOOOOi", kwlist, &shapeTypeArray, &radiusArray, &halfExtentsObjArray, &lengthArray, &fileNameArray, &meshScaleObjArray, &planeNormalObjArray, &flagsArray, &rgbaColorArray, &visualFramePositionObjArray, &visualFrameOrientationObjArray, &physicsClientId)) { @@ -6858,17 +6858,17 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje PyObject* linkJointAxisObj=0; PyObject* linkInertialFramePositionObj=0; PyObject* linkInertialFrameOrientationObj=0; - + static char* kwlist[] = { - "baseMass","baseCollisionShapeIndex","baseVisualShapeIndex","basePosition", "baseOrientation", - "baseInertialFramePosition", "baseInertialFrameOrientation", "linkMasses","linkCollisionShapeIndices", - "linkVisualShapeIndices","linkPositions", "linkOrientations","linkInertialFramePositions","linkInertialFrameOrientations", "linkParentIndices", + "baseMass","baseCollisionShapeIndex","baseVisualShapeIndex","basePosition", "baseOrientation", + "baseInertialFramePosition", "baseInertialFrameOrientation", "linkMasses","linkCollisionShapeIndices", + "linkVisualShapeIndices","linkPositions", "linkOrientations","linkInertialFramePositions","linkInertialFrameOrientations", "linkParentIndices", "linkJointTypes","linkJointAxis", "useMaximalCoordinates", "flags", "physicsClientId", NULL}; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diiOOOOOOOOOOOOOOiii", kwlist, + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diiOOOOOOOOOOOOOOiii", kwlist, &baseMass,&baseCollisionShapeIndex,&baseVisualShapeIndex,&basePosObj, &baseOrnObj, - &baseInertialFramePositionObj, &baseInertialFrameOrientationObj,&linkMassesObj, &linkCollisionShapeIndicesObj, - &linkVisualShapeIndicesObj, &linkPositionsObj, &linkOrientationsObj,&linkInertialFramePositionObj, &linkInertialFrameOrientationObj,&linkParentIndicesObj, + &baseInertialFramePositionObj, &baseInertialFrameOrientationObj,&linkMassesObj, &linkCollisionShapeIndicesObj, + &linkVisualShapeIndicesObj, &linkPositionsObj, &linkOrientationsObj,&linkInertialFramePositionObj, &linkInertialFrameOrientationObj,&linkParentIndicesObj, &linkJointTypesObj,&linkJointAxisObj, &useMaximalCoordinates, &flags, &physicsClientId)) { return NULL; @@ -6953,11 +6953,11 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje linkParentIndex = pybullet_internalGetIntFromSequence(seqLinkParentIndices,i); linkJointType = pybullet_internalGetIntFromSequence(seqLinkJointTypes,i); - b3CreateMultiBodyLink(commandHandle, - linkMass, - linkCollisionShapeIndex, - linkVisualShapeIndex, - linkPosition, + b3CreateMultiBodyLink(commandHandle, + linkMass, + linkCollisionShapeIndex, + linkVisualShapeIndex, + linkPosition, linkOrientation, linkInertialFramePosition, linkInertialFrameOrientation, @@ -7032,7 +7032,7 @@ static PyObject* pybullet_createMultiBody(PyObject* self, PyObject* args, PyObje PyErr_SetString(SpamError, "All link arrays need to be same size."); return NULL; } - + #if 0 PyObject* seq; @@ -7161,7 +7161,7 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py int bodyUniqueIdB = -1; int linkIndexA = -2; int linkIndexB = -2; - + b3SharedMemoryCommandHandle commandHandle; struct b3ContactInformation contactPointData; b3SharedMemoryStatusHandle statusHandle; @@ -7200,7 +7200,7 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py { b3SetContactFilterLinkB( commandHandle, linkIndexB); } - + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED) @@ -7359,12 +7359,12 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec bytesPerPixel}; npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; npy_intp seg_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth}; - + pyResultList = PyTuple_New(5); - + PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); - + pyRGB = PyArray_SimpleNew(3, rgb_dims, NPY_UINT8); pyDep = PyArray_SimpleNew(2, dep_dims, NPY_FLOAT32); pySeg = PyArray_SimpleNew(2, seg_dims, NPY_INT32); @@ -7771,7 +7771,7 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args) statusType = b3GetStatusType(statusHandle); if (statusType == CMD_CAMERA_IMAGE_COMPLETED) { - + PyObject* pyResultList; // store 4 elements in this result: width, // height, rgbData, depth @@ -7780,7 +7780,7 @@ static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args) PyObject* pyDep; PyObject* pySeg; - + int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values b3GetCameraImageData(sm, &imageData); @@ -8128,7 +8128,7 @@ static PyObject* pybullet_multiplyTransforms(PyObject* self, { return NULL; } - + hasPosA = pybullet_internalSetVectord(posAObj, posA); hasOrnA = pybullet_internalSetVector4d(ornAObj, ornA); hasPosB = pybullet_internalSetVectord(posBObj, posB); @@ -8152,7 +8152,7 @@ static PyObject* pybullet_multiplyTransforms(PyObject* self, PyTuple_SetItem(pyPosOutObj, i, PyFloat_FromDouble(outPos[i])); for (i = 0; i < 4; i++) PyTuple_SetItem(pyOrnOutObj, i, PyFloat_FromDouble(outOrn[i])); - + PyTuple_SetItem(pyListOutObj, 0, pyPosOutObj); PyTuple_SetItem(pyListOutObj, 1, pyOrnOutObj); @@ -8181,7 +8181,7 @@ static PyObject* pybullet_invertTransform(PyObject* self, hasPos = pybullet_internalSetVectord(posObj, pos); hasOrn = pybullet_internalSetVector4d(ornObj, orn); - + if (hasPos && hasOrn) { double outPos[3]; @@ -8200,18 +8200,18 @@ static PyObject* pybullet_invertTransform(PyObject* self, PyTuple_SetItem(pyPosOutObj, i, PyFloat_FromDouble(outPos[i])); for (i = 0; i < 4; i++) PyTuple_SetItem(pyOrnOutObj, i, PyFloat_FromDouble(outOrn[i])); - + PyTuple_SetItem(pyListOutObj, 0, pyPosOutObj); PyTuple_SetItem(pyListOutObj, 1, pyOrnOutObj); return pyListOutObj; } - + PyErr_SetString(SpamError, "Invalid input: expected position [x,y,z] and orientation [x,y,z,w]."); return NULL; } - + /// quaternion <-> euler yaw/pitch/roll convention from URDF/SDF, see Gazebo /// https://github.com/arpg/Gazebo/blob/master/gazebo/math/Quaternion.cc @@ -8271,7 +8271,7 @@ static PyObject* pybullet_getEulerFromQuaternion(PyObject* self, sqz = quat[2] * quat[2]; squ = quat[3] * quat[3]; sarg = -2 * (quat[0] * quat[2] - quat[3] * quat[1]); - + // If the pitch angle is PI/2 or -PI/2, we can only compute // the sum roll + yaw. However, any combination that gives // the right sum will produce the correct orientation, so we @@ -8310,7 +8310,7 @@ static PyObject* pybullet_loadPlugin(PyObject* self, PyObject* args, PyObject* keywds) { int physicsClientId = 0; - + char* pluginPath = 0; char* postFix = 0; @@ -8418,7 +8418,7 @@ static PyObject* pybullet_executePluginCommand(PyObject* self, int val = pybullet_internalGetIntFromSequence(seqIntArgs,i); b3CustomCommandExecuteAddIntArgument(command, val); } - + for (i=0;i= 3 m = PyModule_Create(&moduledef); #else -#ifdef BT_USE_EGL +#ifdef BT_USE_EGL2 m = Py_InitModule3("pybullet_egl", SpamMethods, "Python bindings for Bullet"); #else #ifdef BT_PYBULLET_GRPC m = Py_InitModule3("pybullet_grpc", SpamMethods, "Python bindings for Bullet"); #else m = Py_InitModule3("pybullet", SpamMethods, "Python bindings for Bullet"); -#endif //BT_USE_EGL +#endif //BT_USE_EGL2 #endif //BT_PYBULLET_GRPC #endif @@ -9651,7 +9651,7 @@ initpybullet(void) PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY", SHARED_MEMORY_KEY); PyModule_AddIntConstant(m, "SHARED_MEMORY_KEY2", SHARED_MEMORY_KEY+1); - + PyModule_AddIntConstant(m, "JOINT_REVOLUTE", eRevoluteType); // user read PyModule_AddIntConstant(m, "JOINT_PRISMATIC", ePrismaticType); // user read PyModule_AddIntConstant(m, "JOINT_SPHERICAL", eSphericalType); // user read @@ -9659,8 +9659,8 @@ initpybullet(void) PyModule_AddIntConstant(m, "JOINT_FIXED", eFixedType); // user read PyModule_AddIntConstant(m, "JOINT_POINT2POINT", ePoint2PointType); // user read PyModule_AddIntConstant(m, "JOINT_GEAR", eGearType); // user read - - + + PyModule_AddIntConstant(m, "SENSOR_FORCE_TORQUE", eSensorForceTorqueType); // user read PyModule_AddIntConstant(m, "JOINT_FEEDBACK_IN_WORLD_SPACE", JOINT_FEEDBACK_IN_WORLD_SPACE); // user read @@ -9686,7 +9686,7 @@ initpybullet(void) //PyModule_AddIntConstant(m, "CONSTRAINT_SOLVER_LCP_LEMKE",eConstraintSolverLCP_LEMKE); //PyModule_AddIntConstant(m, "CONSTRAINT_SOLVER_LCP_NNCF",eConstraintSolverLCP_NNCG); //PyModule_AddIntConstant(m, "CONSTRAINT_SOLVER_LCP_BLOCK",eConstraintSolverLCP_BLOCK_PGS); - + PyModule_AddIntConstant(m, "VR_BUTTON_IS_DOWN", eButtonIsDown); PyModule_AddIntConstant(m, "VR_BUTTON_WAS_TRIGGERED", eButtonTriggered); PyModule_AddIntConstant(m, "VR_BUTTON_WAS_RELEASED", eButtonReleased); @@ -9713,7 +9713,7 @@ initpybullet(void) PyModule_AddIntConstant(m, "STATE_LOGGING_ALL_COMMANDS", STATE_LOGGING_ALL_COMMANDS); PyModule_AddIntConstant(m, "STATE_REPLAY_ALL_COMMANDS", STATE_REPLAY_ALL_COMMANDS); PyModule_AddIntConstant(m, "STATE_LOGGING_CUSTOM_TIMER", STATE_LOGGING_CUSTOM_TIMER); - + PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI); PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS); PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME); @@ -9761,7 +9761,7 @@ initpybullet(void) PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION", URDF_USE_SELF_COLLISION); PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_PARENT", URDF_USE_SELF_COLLISION_EXCLUDE_PARENT); PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_INCLUDE_PARENT", URDF_USE_SELF_COLLISION_INCLUDE_PARENT); - + PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS", URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS); PyModule_AddIntConstant(m, "VISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS", eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS); @@ -9808,20 +9808,20 @@ initpybullet(void) PyModule_AddIntConstant(m, "GEOM_FORCE_CONCAVE_TRIMESH", GEOM_FORCE_CONCAVE_TRIMESH); PyModule_AddIntConstant(m, "GEOM_CONCAVE_INTERNAL_EDGE", GEOM_CONCAVE_INTERNAL_EDGE); - - + + PyModule_AddIntConstant(m, "STATE_LOG_JOINT_MOTOR_TORQUES", STATE_LOG_JOINT_MOTOR_TORQUES); PyModule_AddIntConstant(m, "STATE_LOG_JOINT_USER_TORQUES", STATE_LOG_JOINT_USER_TORQUES); PyModule_AddIntConstant(m, "STATE_LOG_JOINT_TORQUES", STATE_LOG_JOINT_USER_TORQUES+STATE_LOG_JOINT_MOTOR_TORQUES); - - + + SpamError = PyErr_NewException("pybullet.error", NULL, NULL); Py_INCREF(SpamError); PyModule_AddObject(m, "error", SpamError); printf("pybullet build time: %s %s\n", __DATE__,__TIME__); - + Py_AtExit( b3pybulletExitFunc ); - + #ifdef PYBULLET_USE_NUMPY // Initialize numpy array. diff --git a/setup.py b/setup.py index 7b8ff7aed..73c4ecbfc 100644 --- a/setup.py +++ b/setup.py @@ -2,12 +2,12 @@ from setuptools import find_packages from sys import platform as _platform import sys -from glob import glob +import glob from distutils.core import setup from distutils.extension import Extension from distutils.util import get_platform - +from glob import glob # monkey-patch for parallel compilation import multiprocessing @@ -42,7 +42,10 @@ CXX_FLAGS += '-DBT_USE_DOUBLE_PRECISION ' CXX_FLAGS += '-DBT_ENABLE_ENET ' CXX_FLAGS += '-DBT_ENABLE_CLSOCKET ' CXX_FLAGS += '-DB3_DUMP_PYTHON_VERSION ' -CXX_FLAGS += '-DEGL_ADD_PYTHON_INIT ' +CXX_FLAGS += '-DBT_USE_EGL ' + +EGL_CXX_FLAGS = '' + # libraries += [current_python] @@ -282,13 +285,13 @@ sources = ["examples/pybullet/pybullet.c"]\ +["src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBody.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp"]\ -+["src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp"]\ ++["src/BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.cpp"]\ +["src/BulletDynamics/Featherstone/btMultiBodySliderConstraint.cpp"]\ +["src/BulletDynamics/Vehicle/btRaycastVehicle.cpp"]\ @@ -448,10 +451,8 @@ egl_renderer_sources = \ +["examples/OpenGLWindow/LoadShader.cpp"] \ +["src/LinearMath/btQuickprof.cpp"] - - if _platform == "linux" or _platform == "linux2": - libraries += ['dl','pthread'] + libraries = ['dl','pthread'] CXX_FLAGS += '-D_LINUX ' CXX_FLAGS += '-DGLEW_STATIC ' CXX_FLAGS += '-DGLEW_INIT_OPENGL11_FUNCTIONS=1 ' @@ -459,20 +460,19 @@ if _platform == "linux" or _platform == "linux2": CXX_FLAGS += '-DDYNAMIC_LOAD_X11_FUNCTIONS ' CXX_FLAGS += '-DHAS_SOCKLEN_T ' CXX_FLAGS += '-fno-inline-functions-called-once ' - CXX_FLAGS += '-fPIC ' # for plugins - CXX_FLAGS += '-DBT_USE_EGL ' - sources = sources + ["examples/ThirdPartyLibs/enet/unix.c"]\ - +["examples/ThirdPartyLibs/glad/gl.c"] - - include_dirs += ["examples/ThirdPartyLibs/optionalX11"] - sources = sources + ["examples/OpenGLWindow/X11OpenGLWindow.cpp"]\ - + ["examples/ThirdPartyLibs/glad/glx.c"] + EGL_CXX_FLAGS += '-DBT_USE_EGL ' + EGL_CXX_FLAGS += '-fPIC ' # for plugins + sources = sources + ["examples/ThirdPartyLibs/enet/unix.c"]\ + +["examples/OpenGLWindow/X11OpenGLWindow.cpp"]\ + +["examples/ThirdPartyLibs/glad/gl.c"]\ + +["examples/ThirdPartyLibs/glad/glx.c"] + include_dirs += ["examples/ThirdPartyLibs/optionalX11"] if 'BT_USE_EGL' in CXX_FLAGS: - # linking with bullet's Glew libraries causes segfault - # for some reason. sources += ['examples/ThirdPartyLibs/glad/egl.c'] sources += ['examples/OpenGLWindow/EGLOpenGLWindow.cpp'] + + if 'BT_USE_EGL' in EGL_CXX_FLAGS: egl_renderer_sources = egl_renderer_sources\ +["examples/OpenGLWindow/EGLOpenGLWindow.cpp"]\ +['examples/ThirdPartyLibs/glad/egl.c'] @@ -481,19 +481,16 @@ if _platform == "linux" or _platform == "linux2": +["examples/OpenGLWindow/X11OpenGLWindow.cpp"]\ +["examples/ThirdPartyLibs/glad/glx.c"] + elif _platform == "win32": print("win32!") - libraries += ['Ws2_32','Winmm','User32','Opengl32','kernel32','glu32','Gdi32','Comdlg32'] + libraries = ['Ws2_32','Winmm','User32','Opengl32','kernel32','glu32','Gdi32','Comdlg32'] CXX_FLAGS += '-DWIN32 ' CXX_FLAGS += '-DGLEW_STATIC ' sources = sources + ["examples/ThirdPartyLibs/enet/win32.c"]\ +["examples/OpenGLWindow/Win32Window.cpp"]\ +["examples/OpenGLWindow/Win32OpenGLWindow.cpp"]\ +["examples/ThirdPartyLibs/glad/gl.c"] - egl_renderer_sources = egl_renderer_sources\ - +["examples/ThirdPartyLibs/enet/win32.c"]\ - +["examples/OpenGLWindow/Win32Window.cpp"]\ - +["examples/OpenGLWindow/Win32OpenGLWindow.cpp"] elif _platform == "darwin": print("darwin!") os.environ['LDFLAGS'] = '-framework Cocoa -framework OpenGL' @@ -505,12 +502,9 @@ elif _platform == "darwin": +["examples/OpenGLWindow/MacOpenGLWindow.cpp"]\ +["examples/ThirdPartyLibs/glad/gl.c"]\ +["examples/OpenGLWindow/MacOpenGLWindowObjC.m"] - egl_renderer_sources = egl_renderer_sources\ - +["examples/OpenGLWindow/MacOpenGLWindow.cpp"]\ - +["examples/OpenGLWindow/MacOpenGLWindowObjC.m"] else: print("bsd!") - libraries += ['GL','GLEW','pthread'] + libraries = ['GL','GLEW','pthread'] os.environ['LDFLAGS'] = '-L/usr/X11R6/lib' CXX_FLAGS += '-D_BSD ' CXX_FLAGS += '-I/usr/X11R6/include ' @@ -519,13 +513,7 @@ else: sources = ["examples/ThirdPartyLibs/enet/unix.c"]\ +["examples/OpenGLWindow/X11OpenGLWindow.cpp"]\ +["examples/ThirdPartyLibs/glad/gl.c"]\ - +["examples/ThirdPartyLibs/glad/glx.c"]\ + sources - egl_renderer_sources = egl_renderer_sources\ - +["examples/OpenGLWindow/X11OpenGLWindow.cpp"]\ - +["examples/ThirdPartyLibs/glad/gl.c"]\ - +["examples/ThirdPartyLibs/glad/glx.c"] - setup_py_dir = os.path.dirname(os.path.realpath(__file__)) @@ -547,19 +535,17 @@ print("packages") print(find_packages('examples/pybullet/gym')) print("-----") - - eglRender = Extension("eglRenderer", sources = egl_renderer_sources, libraries = libraries, - extra_compile_args=(CXX_FLAGS+'-DBT_USE_EGL ').split(), + extra_compile_args=(CXX_FLAGS+EGL_CXX_FLAGS ).split(), include_dirs = include_dirs + ["src","examples", "examples/ThirdPartyLibs","examples/ThirdPartyLibs/glad", "examples/ThirdPartyLibs/enet/include","examples/ThirdPartyLibs/clsocket/src"] ) setup( name = 'pybullet', - version='2.1.4', + version='2.1.2', description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning', long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.', url='https://github.com/bulletphysics/bullet3', @@ -567,12 +553,12 @@ setup( author_email='erwincoumans@google.com', license='zlib', platforms='any', - keywords=['game development', 'virtual reality', 'physics simulation', 'robotics', 'reinforcement learning', 'collision detection', 'opengl'], + keywords=['game development', 'virtual reality', 'physics simulation', 'robotics', 'collision detection', 'opengl'], ext_modules = [eglRender, Extension("pybullet", sources = sources, libraries = libraries, extra_compile_args=CXX_FLAGS.split(), - include_dirs = include_dirs + ["src","examples", "examples/ThirdPartyLibs","examples/ThirdPartyLibs/glad", "examples/ThirdPartyLibs/enet/include","examples/ThirdPartyLibs/clsocket/src"] + include_dirs = include_dirs + ["src","examples/ThirdPartyLibs","examples/ThirdPartyLibs/glad", "examples/ThirdPartyLibs/enet/include","examples/ThirdPartyLibs/clsocket/src"] ) ], classifiers=['Development Status :: 5 - Production/Stable', 'License :: OSI Approved :: zlib/libpng License',