move stb_image/stb_image_write.cpp into a cpp file instead of random files with the magic 'STB_IMAGE_WRITE_IMPLEMENTATION' define
move setup.py back to eglRenderer extension, use pkgutil.get_loader('eglRenderer').get_filename()
disable dlmopen by default, unless B3_USE_DLMOPEN is defined.
This commit is contained in:
@@ -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
|
||||
|
||||
40
examples/pybullet/examples/eglRenderTest.py
Normal file
40
examples/pybullet/examples/eglRenderTest.py
Normal file
@@ -0,0 +1,40 @@
|
||||
|
||||
import pybullet as p
|
||||
import time
|
||||
import pkgutil
|
||||
egl = pkgutil.get_loader('eglRenderer')
|
||||
|
||||
p.connect(p.SHARED_MEMORY_SERVER)
|
||||
|
||||
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) :
|
||||
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)
|
||||
|
||||
|
||||
p.unloadPlugin(plugin)
|
||||
@@ -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")
|
||||
|
||||
|
||||
@@ -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",
|
||||
|
||||
Reference in New Issue
Block a user