Merge pull request #1874 from erwincoumans/master

more egl plugin fixes, create stb_image_write.cpp (instead of magic defines in various source files)
This commit is contained in:
erwincoumans
2018-09-11 14:14:40 -07:00
committed by GitHub
23 changed files with 374 additions and 228 deletions

View File

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

View File

@@ -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",

View File

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

View File

@@ -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)
{

View File

@@ -9,7 +9,6 @@
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#define STB_IMAGE_WRITE_IMPLEMENTATION
#include "stb_image/stb_image_write.h"

View File

@@ -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",

View File

@@ -21,10 +21,10 @@
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

View File

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

View File

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

View File

@@ -1,4 +1,12 @@
#ifdef EGL_ADD_PYTHON_INIT
#if defined(__APPLE__) && (!defined(B3_NO_PYTHON_FRAMEWORK))
#include <Python/Python.h>
#else
#include <Python.h>
#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

View File

@@ -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();

View File

@@ -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 {

View File

@@ -99,6 +99,7 @@ myfiles =
"../ThirdPartyLibs/tinyxml2/tinyxml2.cpp",
"../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../ThirdPartyLibs/stb_image/stb_image.cpp",
"../ThirdPartyLibs/stb_image/stb_image_write.cpp",
}

View File

@@ -14,25 +14,10 @@
#include <OpenGL/OpenGL.h>
#include <OpenGL/gl.h>
#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 <GL/glew.h>
#else
#include "glad/glad.h"
#endif
#endif //NO_GLEW
#endif //GLEW_STATIC
#endif//(__APPLE__)
#endif
#endif //B3_USE_GLFW
#include "FontData.h"

View File

@@ -0,0 +1,2 @@
#define STB_IMAGE_WRITE_IMPLEMENTATION
#include "stb_image_write.h"

View File

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

View File

@@ -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)

View File

@@ -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()

View File

@@ -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",

View File

@@ -9603,7 +9603,7 @@ initpybullet_egl(void)
initpybullet_grpc(void)
#else
initpybullet(void)
#endif //BT_USE_EGL
#endif //BT_USE_EGL2
#endif //BT_PYBULLET_GRPC
#endif
{
@@ -9611,14 +9611,14 @@ initpybullet(void)
#if PY_MAJOR_VERSION >= 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

112
setup.py
View File

@@ -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',

View File

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

View File

@@ -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",
}