diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index 2416b51a2..8298f4137 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -344,7 +344,7 @@ SET(BulletExampleBrowser_SRCS ../ThirdPartyLibs/stb_image/stb_image.cpp ../ThirdPartyLibs/stb_image/stb_image.h - + ../ThirdPartyLibs/stb_image/stb_image_write.cpp ../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp ../ThirdPartyLibs/tinyxml2/tinyxml2.cpp diff --git a/examples/ExampleBrowser/premake4.lua b/examples/ExampleBrowser/premake4.lua index c6474c6fd..d5f1e02fe 100644 --- a/examples/ExampleBrowser/premake4.lua +++ b/examples/ExampleBrowser/premake4.lua @@ -182,7 +182,7 @@ project "App_BulletExampleBrowser" "../MultiBody/MultiBodyConstraintFeedback.cpp", "../MultiBody/InvertedPendulumPDControl.cpp", "../RigidBody/RigidBodySoftContact.cpp", - "../ThirdPartyLibs/stb_image/*", + "../ThirdPartyLibs/stb_image/stb_image.cpp", "../ThirdPartyLibs/Wavefront/tiny_obj_loader.*", "../ThirdPartyLibs/BussIK/*", "../GyroscopicDemo/GyroscopicSetup.cpp", diff --git a/examples/OpenGLWindow/CMakeLists.txt b/examples/OpenGLWindow/CMakeLists.txt index 35ea9ff3b..91a9a014f 100644 --- a/examples/OpenGLWindow/CMakeLists.txt +++ b/examples/OpenGLWindow/CMakeLists.txt @@ -51,6 +51,7 @@ IF(BUILD_EGL) SET(OpenGLWindow_SRCS ${OpenGLWindow_SRCS} ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/glad/egl.c) ENDIF(BUILD_EGL) +SET(OpenGLWindow_SRCS ${OpenGLWindow_SRCS} ${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/stb_image/stb_image_write.cpp) ADD_LIBRARY(OpenGLWindow ${OpenGLWindow_SRCS} ${OpenGLWindow_HDRS}) diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index ddea108bb..4f0c3bd1d 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -80,6 +80,7 @@ float shadowMapWorldSize=10; #include "Shaders/linesVS.h" #include "GLRenderToTexture.h" +#include "stb_image/stb_image_write.h" @@ -1542,10 +1543,6 @@ void GLInstancingRenderer::updateCamera(int upAxis) -#ifdef STB_AGAIN // first defn in examples/OpenGLWindow/opengl_fontstashcallbacks.cpp -#define STB_IMAGE_WRITE_IMPLEMENTATION -#endif //STB_AGAIN -#include "stb_image/stb_image_write.h" void writeTextureToPng(int textureWidth, int textureHeight, const char* fileName, int numComponents) { diff --git a/examples/OpenGLWindow/opengl_fontstashcallbacks.cpp b/examples/OpenGLWindow/opengl_fontstashcallbacks.cpp index ba67c064d..13c98f54c 100644 --- a/examples/OpenGLWindow/opengl_fontstashcallbacks.cpp +++ b/examples/OpenGLWindow/opengl_fontstashcallbacks.cpp @@ -9,7 +9,6 @@ #include #include #include -#define STB_IMAGE_WRITE_IMPLEMENTATION #include "stb_image/stb_image_write.h" diff --git a/examples/OpenGLWindow/premake4.lua b/examples/OpenGLWindow/premake4.lua index e0b163678..d42247d37 100644 --- a/examples/OpenGLWindow/premake4.lua +++ b/examples/OpenGLWindow/premake4.lua @@ -25,9 +25,12 @@ "*.h", "OpenGLWindow/*.c", "OpenGLWindow/*.h", - "OpenGLWindow/GL/*.h" + "OpenGLWindow/GL/*.h", + "../ThirdPartyLibs/stb_image/stb_image_write.cpp", } + + if not os.is("Windows") then excludes { "Win32OpenGLWindow.cpp", diff --git a/examples/SharedMemory/b3PluginManager.cpp b/examples/SharedMemory/b3PluginManager.cpp index b5a34bb37..667aa59d7 100644 --- a/examples/SharedMemory/b3PluginManager.cpp +++ b/examples/SharedMemory/b3PluginManager.cpp @@ -18,13 +18,13 @@ #define B3_DYNLIB_IMPORT GetProcAddress #else #include - + typedef void* B3_DYNLIB_HANDLE; -#ifdef __APPLE__ - #define B3_DYNLIB_OPEN(path) dlopen(path, RTLD_NOW | RTLD_GLOBAL) -#else +#ifdef B3_USE_DLMOPEN #define B3_DYNLIB_OPEN(path) dlmopen(LM_ID_NEWLM, path, RTLD_LAZY) +#else + #define B3_DYNLIB_OPEN(path) dlopen(path, RTLD_NOW | RTLD_GLOBAL) #endif #define B3_DYNLIB_CLOSE dlclose #define B3_DYNLIB_IMPORT dlsym @@ -40,16 +40,16 @@ struct b3Plugin PFN_INIT m_initFunc; PFN_EXIT m_exitFunc; PFN_EXECUTE m_executeCommandFunc; - + PFN_TICK m_preTickFunc; PFN_TICK m_postTickFunc; PFN_TICK m_processNotificationsFunc; PFN_TICK m_processClientCommandsFunc; PFN_GET_RENDER_INTERFACE m_getRendererFunc; - + void* m_userPointer; - + b3Plugin() :m_pluginHandle(0), m_ownsPluginHandle(false), @@ -332,7 +332,7 @@ void b3PluginManager::tickPlugins(double timeStep, b3PluginManagerTickMode tickM { continue; } - + PFN_TICK tick = 0; switch (tickMode) { @@ -355,7 +355,7 @@ void b3PluginManager::tickPlugins(double timeStep, b3PluginManagerTickMode tickM { } } - + if (tick) { b3PluginContext context = { 0 }; @@ -437,7 +437,7 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT { b3Plugin orgPlugin; - + int pluginUniqueId = m_data->m_plugins.allocHandle(); b3PluginHandle* pluginHandle = m_data->m_plugins.getHandle(pluginUniqueId); pluginHandle->m_pluginHandle = 0; @@ -453,7 +453,7 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT pluginHandle->m_pluginHandle = 0; pluginHandle->m_pluginPath = pluginPath; pluginHandle->m_userPointer = 0; - + if (pluginHandle->m_processNotificationsFunc) { diff --git a/examples/SharedMemory/grpc/proto/createProtobufs.bat b/examples/SharedMemory/grpc/proto/createProtobufs.bat index 2aedbd55d..0ce93f055 100644 --- a/examples/SharedMemory/grpc/proto/createProtobufs.bat +++ b/examples/SharedMemory/grpc/proto/createProtobufs.bat @@ -6,6 +6,9 @@ del pybullet.grpc.pb.h ..\..\..\ThirdPartyLibs\grpc\lib\win32\protoc --proto_path=. --cpp_out=. pybullet.proto ..\..\..\ThirdPartyLibs\grpc\lib\win32\protoc.exe --plugin=protoc-gen-grpc="..\..\..\ThirdPartyLibs\grpc\lib\win32\grpc_cpp_plugin.exe" --grpc_out=. pybullet.proto +rename pybullet.grpc.pb.cc pybullet.grpc.pb.cpp +rename pybullet.pb.cc pybullet.pb.cpp + del pybullet_pb2.py del pybullet_pb2_grpc.py diff --git a/examples/SharedMemory/grpc/proto/createProtobufs.sh b/examples/SharedMemory/grpc/proto/createProtobufs.sh index 8c6807f8b..8ac6e95d2 100755 --- a/examples/SharedMemory/grpc/proto/createProtobufs.sh +++ b/examples/SharedMemory/grpc/proto/createProtobufs.sh @@ -1,19 +1,15 @@ -rm ../pybullet.pb.cpp -rm ../pybullet.pb.h -rm ../pybullet.grpc.pb.cpp -rm ../pybullet.grpc.pb.h +rm pybullet.pb.cpp +rm pybullet.pb.h +rm pybullet.grpc.pb.cpp +rm pybullet.grpc.pb.h protoc --proto_path=. --cpp_out=. pybullet.proto protoc --plugin=protoc-gen-grpc=`which grpc_cpp_plugin` --grpc_out=. pybullet.proto -mv pybullet.grpc.pb.cc ../pybullet.grpc.pb.cpp -mv pybullet.grpc.pb.h ../pybullet.grpc.pb.h -mv pybullet.pb.cc ../pybullet.pb.cpp -mv pybullet.pb.h ../pybullet.pb.h +mv pybullet.grpc.pb.cc pybullet.grpc.pb.cpp +mv pybullet.pb.cc pybullet.pb.cpp -rm ../pybullet_pb2.py -rm ../pybullet_pb2_grpc.py +rm pybullet_pb2.py +rm pybullet_pb2_grpc.py protoc --proto_path=. --python_out=. pybullet.proto python -m grpc_tools.protoc -I. --python_out=. --grpc_python_out=. pybullet.proto -mv pybullet_pb2.py ../pybullet_pb2.py -mv pybullet_pb2_grpc.py ../pybullet_pb2_grpc.py diff --git a/examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.cpp b/examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.cpp index 3ca472901..1bcfc6341 100644 --- a/examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.cpp +++ b/examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.cpp @@ -1,4 +1,12 @@ +#ifdef EGL_ADD_PYTHON_INIT +#if defined(__APPLE__) && (!defined(B3_NO_PYTHON_FRAMEWORK)) +#include +#else +#include +#endif +#endif //EGL_ADD_PYTHON_INIT + //eglRenderer plugin //see Bullet/examples/pybullet/examples/eglRendererTest.py @@ -52,3 +60,17 @@ B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_eglRendererPlugi return &obj->m_renderer; } + +#ifdef EGL_ADD_PYTHON_INIT +PyMODINIT_FUNC +#if PY_MAJOR_VERSION >= 3 +PyInit_eglRenderer(void) +#else +initeglRenderer(void) +#endif +{ +#if PY_MAJOR_VERSION >= 3 + return 0; +#endif +} +#endif //EGL_ADD_PYTHON_INIT diff --git a/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp b/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp index f97da5134..de6289ecd 100644 --- a/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp @@ -795,7 +795,7 @@ void EGLRendererVisualShapeConverter::convertVisualShapes( // register mesh to m_instancingRenderer too. int shapeIndex = m_data->m_instancingRenderer->registerShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(),B3_GL_TRIANGLES, textureIndex); - btVector3 scaling(1,1,1); + double scaling[3]={1,1,1}; visuals->m_graphicsInstanceId = m_data->m_instancingRenderer->registerGraphicsInstance(shapeIndex, &visualShape.m_localVisualFrame[0], &visualShape.m_localVisualFrame[3], &visualShape.m_rgbaColor[0],scaling); m_data->m_instancingRenderer->writeTransforms(); diff --git a/examples/SharedMemory/plugins/eglPlugin/premake4.lua b/examples/SharedMemory/plugins/eglPlugin/premake4.lua index a7f49943a..1642d665a 100644 --- a/examples/SharedMemory/plugins/eglPlugin/premake4.lua +++ b/examples/SharedMemory/plugins/eglPlugin/premake4.lua @@ -6,7 +6,7 @@ project ("pybullet_eglRendererPlugin") initEGL() includedirs {".","../../../../src", "../../../../examples", - "../../../ThirdPartyLibs", "../../examples/ThirdPartyLibs/glad"} + "../../../ThirdPartyLibs", "../../../ThirdPartyLibs/glad"} defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER", "STB_AGAIN"} hasCL = findOpenCL("clew") @@ -25,7 +25,8 @@ project ("pybullet_eglRendererPlugin") end if os.is("Linux") then - files {"../../../ThirdPartyLibs/glad/glx.c",} + files {"../../../OpenGLWindow/EGLOpenGLWindow.cpp"} + end files { diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua index 417ff1447..9d4bb28b9 100644 --- a/examples/SharedMemory/premake4.lua +++ b/examples/SharedMemory/premake4.lua @@ -98,7 +98,8 @@ myfiles = "../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp", "../ThirdPartyLibs/tinyxml2/tinyxml2.cpp", "../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", - "../ThirdPartyLibs/stb_image/stb_image.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", + "../ThirdPartyLibs/stb_image/stb_image_write.cpp", } 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/ThirdPartyLibs/stb_image/stb_image_write.cpp b/examples/ThirdPartyLibs/stb_image/stb_image_write.cpp new file mode 100644 index 000000000..2009b05d5 --- /dev/null +++ b/examples/ThirdPartyLibs/stb_image/stb_image_write.cpp @@ -0,0 +1,2 @@ +#define STB_IMAGE_WRITE_IMPLEMENTATION +#include "stb_image_write.h" \ No newline at end of file diff --git a/examples/pybullet/CMakeLists.txt b/examples/pybullet/CMakeLists.txt index f3cacc5b3..2417a3ab2 100644 --- a/examples/pybullet/CMakeLists.txt +++ b/examples/pybullet/CMakeLists.txt @@ -73,6 +73,7 @@ SET(pybullet_SRCS ../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp ../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h ../../examples/ThirdPartyLibs/stb_image/stb_image.cpp + ../../examples/ThirdPartyLibs/stb_image/stb_image_write.cpp ../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp ../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp ../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp diff --git a/examples/pybullet/examples/eglRenderTest.py b/examples/pybullet/examples/eglRenderTest.py new file mode 100644 index 000000000..6d51c4bb8 --- /dev/null +++ b/examples/pybullet/examples/eglRenderTest.py @@ -0,0 +1,47 @@ + +import pybullet as p +import time +import pkgutil +egl = pkgutil.get_loader('eglRenderer') + +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) + +p.setGravity(0,0,-10) +p.loadURDF("plane.urdf",[0,0,-1]) +p.loadURDF("r2d2.urdf") + +pixelWidth = 320 +pixelHeight = 220 +camTargetPos = [0,0,0] +camDistance = 4 +pitch = -10.0 +roll=0 +upAxisIndex = 2 + + +while (p.isConnected()): + 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/examples/testrender_egl.py b/examples/pybullet/examples/testrender_egl.py index c4947f2b9..0f0b89e03 100644 --- a/examples/pybullet/examples/testrender_egl.py +++ b/examples/pybullet/examples/testrender_egl.py @@ -9,7 +9,7 @@ import numpy as np import matplotlib.pyplot as plt import pybullet import time - +import pkgutil plt.ion() @@ -20,7 +20,9 @@ ax = plt.gca() pybullet.connect(pybullet.DIRECT) -pybullet.loadPlugin("eglRendererPlugin") +egl = pkgutil.get_loader('eglRenderer') + +pybullet.loadPlugin(egl.get_filename(), "_eglRendererPlugin") pybullet.loadURDF("plane.urdf",[0,0,-1]) pybullet.loadURDF("r2d2.urdf") @@ -64,14 +66,14 @@ while (1): #note that sending the data to matplotlib is really slow #reshape is not needed - #np_img_arr = np.reshape(rgb, (h, w, 4)) - #np_img_arr = np_img_arr*(1./255.) + np_img_arr = np.reshape(rgb, (h, w, 4)) + np_img_arr = np_img_arr*(1./255.) #show #plt.imshow(np_img_arr,interpolation='none',extent=(0,1600,0,1200)) #image = plt.imshow(np_img_arr,interpolation='none',animated=True,label="blah") - image.set_data(rgb)#np_img_arr) + image.set_data(np_img_arr) ax.plot([0]) #plt.draw() #plt.show() diff --git a/examples/pybullet/premake4.lua b/examples/pybullet/premake4.lua index 3ee6e9b82..81eb423ea 100644 --- a/examples/pybullet/premake4.lua +++ b/examples/pybullet/premake4.lua @@ -153,6 +153,7 @@ if not _OPTIONS["no-enet"] then "../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp", "../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h", "../../examples/ThirdPartyLibs/stb_image/stb_image.cpp", + "../../examples/ThirdPartyLibs/stb_image/stb_image_write.cpp", "../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp", "../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp", "../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp", 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 296572a94..73c4ecbfc 100644 --- a/setup.py +++ b/setup.py @@ -1,5 +1,4 @@ - from setuptools import find_packages from sys import platform as _platform import sys @@ -10,6 +9,26 @@ from distutils.extension import Extension from distutils.util import get_platform from glob import glob +# monkey-patch for parallel compilation +import multiprocessing +import multiprocessing.pool +def parallelCCompile(self, sources, output_dir=None, macros=None, include_dirs=None, debug=0, extra_preargs=None, extra_postargs=None, depends=None): + # those lines are copied from distutils.ccompiler.CCompiler directly + macros, objects, extra_postargs, pp_opts, build = self._setup_compile(output_dir, macros, include_dirs, sources, depends, extra_postargs) + cc_args = self._get_cc_args(pp_opts, debug, extra_preargs) + # parallel code + N = 2*multiprocessing.cpu_count()# number of parallel compilations + def _single_compile(obj): + try: src, ext = build[obj] + except KeyError: return + self._compile(obj, src, ext, cc_args, extra_postargs, pp_opts) + # convert to list, imap is evaluated on-demand + list(multiprocessing.pool.ThreadPool(N).imap(_single_compile,objects)) + return objects +import distutils.ccompiler +distutils.ccompiler.CCompiler.compile=parallelCCompile + + #see http://stackoverflow.com/a/8719066/295157 import os @@ -23,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 += '-DSTATIC_EGLRENDERER_PLUGIN ' +CXX_FLAGS += '-DBT_USE_EGL ' + +EGL_CXX_FLAGS = '' + # libraries += [current_python] @@ -50,8 +72,6 @@ sources = ["examples/pybullet/pybullet.c"]\ +["examples/TinyRenderer/tgaimage.cpp"]\ +["examples/TinyRenderer/our_gl.cpp"]\ +["examples/TinyRenderer/TinyRenderer.cpp"]\ -+["examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.cpp"]\ -+["examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp"]\ +["examples/SharedMemory/plugins/pdControlPlugin/pdControlPlugin.cpp"]\ +["examples/SharedMemory/plugins/collisionFilterPlugin/collisionFilterPlugin.cpp"]\ +["examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp"]\ @@ -86,6 +106,7 @@ sources = ["examples/pybullet/pybullet.c"]\ +["examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp"]\ +["examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp"]\ +["examples/ThirdPartyLibs/stb_image/stb_image.cpp"]\ ++["examples/ThirdPartyLibs/stb_image/stb_image_write.cpp"]\ +["examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp"]\ +["examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp"]\ +["examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp"]\ @@ -264,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"]\ @@ -388,6 +409,48 @@ sources = ["examples/pybullet/pybullet.c"]\ +["examples/ThirdPartyLibs/Gwen/Platforms/Windows.cpp"]\ +["examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.cpp"]\ + + +egl_renderer_sources = \ +["examples/SharedMemory/plugins/eglPlugin/eglRendererVisualShapeConverter.cpp"]\ ++["examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.cpp"]\ ++["examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp"]\ ++["examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp"]\ ++["examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp"]\ ++["examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp"]\ ++["examples/TinyRenderer/geometry.cpp"]\ ++["examples/TinyRenderer/model.cpp"]\ ++["examples/TinyRenderer/tgaimage.cpp"]\ ++["examples/TinyRenderer/our_gl.cpp"]\ ++["examples/TinyRenderer/TinyRenderer.cpp"]\ ++["examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp"]\ ++["examples/ThirdPartyLibs/stb_image/stb_image.cpp"]\ ++["examples/ThirdPartyLibs/stb_image/stb_image_write.cpp"]\ ++["examples/ThirdPartyLibs/tinyxml2/tinyxml2.cpp"]\ ++["examples/OpenGLWindow/SimpleCamera.cpp"]\ ++["examples/Utils/b3Clock.cpp"]\ ++["examples/Utils/b3ResourcePath.cpp"]\ ++["src/BulletCollision/CollisionShapes/btShapeHull.cpp"]\ ++["src/BulletCollision/CollisionShapes/btConvexHullShape.cpp"]\ ++["src/BulletCollision/CollisionShapes/btBoxShape.cpp"]\ ++["src/BulletCollision/CollisionShapes/btSphereShape.cpp"]\ ++["src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp"]\ ++["src/BulletCollision/CollisionShapes/btConvexShape.cpp"]\ ++["src/BulletCollision/CollisionShapes/btCollisionShape.cpp"]\ ++["src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp"]\ ++["src/BulletCollision/CollisionShapes/btConvexInternalShape.cpp"]\ ++["src/Bullet3Common/b3Logging.cpp"]\ ++["src/LinearMath/btAlignedAllocator.cpp"]\ ++["src/LinearMath/btGeometryUtil.cpp"]\ ++["src/LinearMath/btConvexHull.cpp"]\ ++["src/LinearMath/btConvexHullComputer.cpp"]\ ++["src/Bullet3Common/b3AlignedAllocator.cpp"] \ ++["examples/ThirdPartyLibs/glad/gl.c"]\ ++["examples/OpenGLWindow/GLInstancingRenderer.cpp"]\ ++["examples/OpenGLWindow/GLRenderToTexture.cpp"] \ ++["examples/OpenGLWindow/LoadShader.cpp"] \ ++["src/LinearMath/btQuickprof.cpp"] + if _platform == "linux" or _platform == "linux2": libraries = ['dl','pthread'] CXX_FLAGS += '-D_LINUX ' @@ -396,16 +459,29 @@ if _platform == "linux" or _platform == "linux2": CXX_FLAGS += '-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1 ' CXX_FLAGS += '-DDYNAMIC_LOAD_X11_FUNCTIONS ' CXX_FLAGS += '-DHAS_SOCKLEN_T ' - CXX_FLAGS += '-DBT_USE_EGL ' - CXX_FLAGS += '-fno-inline-functions-called-once' + CXX_FLAGS += '-fno-inline-functions-called-once ' + 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"]\ - +["examples/ThirdPartyLibs/glad/egl.c"]\ - +["examples/OpenGLWindow/EGLOpenGLWindow.cpp"] - + +["examples/ThirdPartyLibs/glad/glx.c"] include_dirs += ["examples/ThirdPartyLibs/optionalX11"] + if 'BT_USE_EGL' in CXX_FLAGS: + 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'] + else: + egl_renderer_sources = egl_renderer_sources\ + +["examples/OpenGLWindow/X11OpenGLWindow.cpp"]\ + +["examples/ThirdPartyLibs/glad/glx.c"] + + elif _platform == "win32": print("win32!") libraries = ['Ws2_32','Winmm','User32','Opengl32','kernel32','glu32','Gdi32','Comdlg32'] @@ -459,9 +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+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', @@ -470,11 +554,11 @@ setup( license='zlib', platforms='any', keywords=['game development', 'virtual reality', 'physics simulation', 'robotics', 'collision detection', 'opengl'], - ext_modules = [Extension("pybullet", + 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', diff --git a/test/GwenOpenGLTest/OpenGLSample.cpp b/test/GwenOpenGLTest/OpenGLSample.cpp index 4150795c9..1a609a584 100644 --- a/test/GwenOpenGLTest/OpenGLSample.cpp +++ b/test/GwenOpenGLTest/OpenGLSample.cpp @@ -356,7 +356,7 @@ int main() #ifndef _WIN32 //we need glewExperimental on Linux #endif // _WIN32 - gladLoadGLInternalLoader(); + gladLoaderLoadGL(); #endif #endif //B3_USE_GLFW //we ned to call glGetError twice, because of some Ubuntu/Intel/OpenGL issue diff --git a/test/GwenOpenGLTest/premake4.lua b/test/GwenOpenGLTest/premake4.lua index df71f70e6..6bc3a9d19 100644 --- a/test/GwenOpenGLTest/premake4.lua +++ b/test/GwenOpenGLTest/premake4.lua @@ -41,6 +41,7 @@ "../../examples/OpenGLWindow/opengl_fontstashcallbacks.h", "../../examples/Utils/b3Clock.cpp", "../../examples/Utils/b3Clock.h", + "../../examples/ThirdPartyLibs/stb_image/stb_image_write.cpp", "**.cpp", "**.h", }