Merge pull request #1869 from erwincoumans/master
fixes in eglRendererPlugin
This commit is contained in:
@@ -73,6 +73,15 @@
|
||||
description = "Use Midi controller to control parameters"
|
||||
}
|
||||
|
||||
|
||||
newoption
|
||||
{
|
||||
trigger = "enable_egl",
|
||||
value = false,
|
||||
description = "Build an experimental eglPlugin"
|
||||
}
|
||||
|
||||
|
||||
newoption
|
||||
{
|
||||
trigger = "enable_grpc",
|
||||
@@ -145,6 +154,13 @@
|
||||
_OPTIONS["protobuf_lib_dir"] = default_protobuf_lib_dir
|
||||
end
|
||||
|
||||
|
||||
if _OPTIONS["enable_egl"] then
|
||||
function initEGL()
|
||||
defines {"BT_USE_EGL"}
|
||||
end
|
||||
end
|
||||
|
||||
|
||||
if _OPTIONS["enable_grpc"] then
|
||||
function initGRPC()
|
||||
|
||||
@@ -12,16 +12,17 @@ set /p myvar1= < tmp1234.txt
|
||||
set myvar=c:/%myvar1%
|
||||
del tmp1234.txt
|
||||
|
||||
#you can also override and hardcode the Python path like this (just remove the # hashmark in next line)
|
||||
#SET myvar=c:\python-3.5.2
|
||||
rem you can also override and hardcode the Python path like this (just remove the # hashmark in next line)
|
||||
rem SET myvar=c:\python-3.5.2
|
||||
|
||||
cd build3
|
||||
|
||||
|
||||
premake4 --double --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
|
||||
#premake4 --double --grpc --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../binserver" vs2010
|
||||
|
||||
#premake4 --serial --audio --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
|
||||
rem premake4 --double --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../binserver" vs2010
|
||||
rem premake4 --double --enable_grpc --enable_multithreading --midi --enable_static_vr_plugin --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../binserver" vs2010
|
||||
rem premake4 --serial --audio --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
|
||||
|
||||
start vs2010
|
||||
|
||||
|
||||
@@ -599,10 +599,11 @@ void ConvertURDF2BulletInternal(
|
||||
|
||||
if (mbLinkIndex>=0) //???? double-check +/- 1
|
||||
{
|
||||
|
||||
cache.m_bulletMultiBody->getLink(mbLinkIndex).m_collider=col;
|
||||
if (flags&CUF_USE_SELF_COLLISION_EXCLUDE_PARENT)
|
||||
if (flags&CUF_USE_SELF_COLLISION_INCLUDE_PARENT)
|
||||
{
|
||||
cache.m_bulletMultiBody->getLink(mbLinkIndex).m_flags |= BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION;
|
||||
cache.m_bulletMultiBody->getLink(mbLinkIndex).m_flags &= ~BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION;
|
||||
}
|
||||
if (flags&CUF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
|
||||
{
|
||||
|
||||
@@ -31,6 +31,7 @@ enum ConvertURDFFlags {
|
||||
CUF_ENABLE_CACHED_GRAPHICS_SHAPES = 1024,
|
||||
CUF_ENABLE_SLEEPING=2048,
|
||||
CUF_INITIALIZE_SAT_FEATURES=4096,
|
||||
CUF_USE_SELF_COLLISION_INCLUDE_PARENT = 8192,
|
||||
};
|
||||
|
||||
struct UrdfVisualShapeCache
|
||||
|
||||
@@ -30,11 +30,12 @@
|
||||
|
||||
#ifdef BT_USE_EGL
|
||||
|
||||
#include <pthread.h>
|
||||
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
|
||||
|
||||
#include "OpenGLInclude.h"
|
||||
|
||||
@@ -213,7 +214,7 @@ void EGLOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) {
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
|
||||
if (!gladLoadGL(eglGetProcAddress)) {
|
||||
if (!gladLoadGL((GLADloadfunc) eglGetProcAddress)) {
|
||||
fprintf(stderr, "failed to load GL with glad.\n");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
@@ -228,8 +229,8 @@ void EGLOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) {
|
||||
const GLubyte* sl = glGetString(GL_SHADING_LANGUAGE_VERSION);
|
||||
printf("GL_SHADING_LANGUAGE_VERSION=%s\n", sl);
|
||||
|
||||
int i = pthread_getconcurrency();
|
||||
printf("pthread_getconcurrency()=%d\n", i);
|
||||
//int i = pthread_getconcurrency();
|
||||
//printf("pthread_getconcurrency()=%d\n", i);
|
||||
}
|
||||
|
||||
void EGLOpenGLWindow::closeWindow() {
|
||||
|
||||
@@ -4,6 +4,11 @@
|
||||
#include "ShapeData.h"
|
||||
|
||||
|
||||
#ifdef BT_USE_EGL
|
||||
#include "EGLOpenGLWindow.h"
|
||||
#else
|
||||
#endif //BT_USE_EGL
|
||||
|
||||
#ifdef B3_USE_GLFW
|
||||
#include "GLFWOpenGLWindow.h"
|
||||
#else
|
||||
@@ -19,10 +24,6 @@
|
||||
//let's cross the fingers it is Linux/X11
|
||||
#include "X11OpenGLWindow.h"
|
||||
#define BT_USE_X11 // for runtime backend selection, move to build?
|
||||
#ifdef BT_USE_EGL
|
||||
#include "EGLOpenGLWindow.h"
|
||||
#else
|
||||
#endif //BT_USE_EGL
|
||||
#endif //_WIN32
|
||||
#endif//__APPLE__
|
||||
#endif //B3_USE_GLFW
|
||||
|
||||
@@ -68,6 +68,11 @@
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef STATIC_EGLRENDERER_PLUGIN
|
||||
#include "plugins/eglPlugin/eglRendererPlugin.h"
|
||||
#endif//STATIC_EGLRENDERER_PLUGIN
|
||||
|
||||
|
||||
#ifndef SKIP_STATIC_TINYRENDERER_PLUGIN
|
||||
#include "plugins/tinyRendererPlugin/tinyRendererPlugin.h"
|
||||
#endif
|
||||
@@ -1709,10 +1714,22 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
}
|
||||
#endif //ENABLE_STATIC_GRPC_PLUGIN
|
||||
|
||||
#ifdef STATIC_EGLRENDERER_PLUGIN
|
||||
{
|
||||
bool initPlugin = false;
|
||||
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("eglRendererPlugin", initPlugin_eglRendererPlugin, exitPlugin_eglRendererPlugin, executePluginCommand_eglRendererPlugin,0,0,getRenderInterface_eglRendererPlugin,0, initPlugin);
|
||||
m_pluginManager.selectPluginRenderer(renderPluginId);
|
||||
}
|
||||
#endif//STATIC_EGLRENDERER_PLUGIN
|
||||
|
||||
|
||||
|
||||
#ifndef SKIP_STATIC_TINYRENDERER_PLUGIN
|
||||
{
|
||||
|
||||
int renderPluginId = m_pluginManager.registerStaticLinkedPlugin("tinyRendererPlugin", initPlugin_tinyRendererPlugin, exitPlugin_tinyRendererPlugin, executePluginCommand_tinyRendererPlugin,0,0,getRenderInterface_tinyRendererPlugin,0);
|
||||
m_pluginManager.selectPluginRenderer(renderPluginId);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@@ -830,6 +830,7 @@ enum eURDF_Flags
|
||||
URDF_ENABLE_CACHED_GRAPHICS_SHAPES=1024,
|
||||
URDF_ENABLE_SLEEPING=2048,
|
||||
URDF_INITIALIZE_SAT_FEATURES = 4096,
|
||||
URDF_USE_SELF_COLLISION_INCLUDE_PARENT = 8192,
|
||||
};
|
||||
|
||||
enum eUrdfGeomTypes //sync with UrdfParser UrdfGeomTypes
|
||||
|
||||
@@ -34,6 +34,7 @@ struct b3Plugin
|
||||
{
|
||||
B3_DYNLIB_HANDLE m_pluginHandle;
|
||||
bool m_ownsPluginHandle;
|
||||
bool m_isInitialized;
|
||||
std::string m_pluginPath;
|
||||
int m_pluginUniqueId;
|
||||
PFN_INIT m_initFunc;
|
||||
@@ -52,6 +53,7 @@ struct b3Plugin
|
||||
b3Plugin()
|
||||
:m_pluginHandle(0),
|
||||
m_ownsPluginHandle(false),
|
||||
m_isInitialized(false),
|
||||
m_pluginUniqueId(-1),
|
||||
m_initFunc(0),
|
||||
m_exitFunc(0),
|
||||
@@ -80,6 +82,7 @@ struct b3Plugin
|
||||
m_processClientCommandsFunc = 0;
|
||||
m_getRendererFunc = 0;
|
||||
m_userPointer = 0;
|
||||
m_isInitialized = false;
|
||||
}
|
||||
};
|
||||
|
||||
@@ -171,8 +174,20 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
||||
int* pluginUidPtr = m_data->m_pluginMap.find(pluginPath);
|
||||
if (pluginUidPtr)
|
||||
{
|
||||
|
||||
//already loaded
|
||||
pluginUniqueId = *pluginUidPtr;
|
||||
b3PluginHandle* plugin = m_data->m_plugins.getHandle(pluginUniqueId);
|
||||
if (!plugin->m_isInitialized)
|
||||
{
|
||||
b3PluginContext context = {0};
|
||||
context.m_userPointer = 0;
|
||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||
context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface;
|
||||
int result = plugin->m_initFunc(&context);
|
||||
plugin->m_isInitialized = true;
|
||||
plugin->m_userPointer = context.m_userPointer;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -211,16 +226,18 @@ int b3PluginManager::loadPlugin(const char* pluginPath, const char* postFixStr)
|
||||
|
||||
if (plugin->m_initFunc && plugin->m_exitFunc && plugin->m_executeCommandFunc)
|
||||
{
|
||||
|
||||
|
||||
b3PluginContext context;
|
||||
context.m_userPointer = plugin->m_userPointer;
|
||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||
context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface;
|
||||
int version = plugin->m_initFunc(&context);
|
||||
plugin->m_isInitialized = true;
|
||||
//keep the user pointer persistent
|
||||
plugin->m_userPointer = context.m_userPointer;
|
||||
if (version == SHARED_MEMORY_MAGIC_NUMBER)
|
||||
{
|
||||
|
||||
ok = true;
|
||||
plugin->m_ownsPluginHandle = true;
|
||||
plugin->m_pluginHandle = pluginHandle;
|
||||
@@ -286,7 +303,12 @@ void b3PluginManager::unloadPlugin(int pluginUniqueId)
|
||||
context.m_userPointer = plugin->m_userPointer;
|
||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||
|
||||
plugin->m_exitFunc(&context);
|
||||
if (plugin->m_isInitialized)
|
||||
{
|
||||
plugin->m_exitFunc(&context);
|
||||
plugin->m_userPointer = 0;
|
||||
plugin->m_isInitialized = false;
|
||||
}
|
||||
m_data->m_pluginMap.remove(plugin->m_pluginPath.c_str());
|
||||
m_data->m_plugins.freeHandle(pluginUniqueId);
|
||||
}
|
||||
@@ -411,7 +433,7 @@ int b3PluginManager::executePluginCommand(int pluginUniqueId, const b3PluginArgu
|
||||
}
|
||||
|
||||
|
||||
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc, PFN_TICK processClientCommandsFunc)
|
||||
int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc,PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc, PFN_TICK processClientCommandsFunc, bool initPlugin)
|
||||
{
|
||||
|
||||
b3Plugin orgPlugin;
|
||||
@@ -440,12 +462,14 @@ int b3PluginManager::registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT
|
||||
|
||||
m_data->m_pluginMap.insert(pluginPath, pluginUniqueId);
|
||||
|
||||
if (initPlugin)
|
||||
{
|
||||
b3PluginContext context = {0};
|
||||
context.m_userPointer = 0;
|
||||
context.m_physClient = (b3PhysicsClientHandle) m_data->m_physicsDirect;
|
||||
context.m_rpcCommandProcessorInterface = m_data->m_rpcCommandProcessorInterface;
|
||||
int result = pluginHandle->m_initFunc(&context);
|
||||
pluginHandle->m_isInitialized = true;
|
||||
pluginHandle->m_userPointer = context.m_userPointer;
|
||||
}
|
||||
return pluginUniqueId;
|
||||
|
||||
@@ -30,7 +30,7 @@ class b3PluginManager
|
||||
|
||||
void tickPlugins(double timeStep, b3PluginManagerTickMode tickMode);
|
||||
|
||||
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc, PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc, PFN_TICK processClientCommandsFunc);
|
||||
int registerStaticLinkedPlugin(const char* pluginPath, PFN_INIT initFunc, PFN_EXIT exitFunc, PFN_EXECUTE executeCommandFunc, PFN_TICK preTickFunc, PFN_TICK postTickFunc, PFN_GET_RENDER_INTERFACE getRendererFunc, PFN_TICK processClientCommandsFunc, bool initPlugin=true);
|
||||
void selectPluginRenderer(int pluginUniqueId);
|
||||
UrdfRenderingInterface* getRenderInterface();
|
||||
};
|
||||
|
||||
@@ -1,85 +0,0 @@
|
||||
import os
|
||||
import sys
|
||||
import time
|
||||
import subprocess
|
||||
import pybullet as p
|
||||
from pdb import set_trace
|
||||
import matplotlib.pyplot as plt
|
||||
import numpy as np
|
||||
#subprocess.call(["hardening-check", p.__file__])
|
||||
|
||||
|
||||
|
||||
p.connect(p.DIRECT)
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "debugTimings")
|
||||
|
||||
plugin = True
|
||||
if plugin:
|
||||
plugin_fn = '/home/argusm/lang/bullet3/build/lib.linux-x86_64-3.5/eglRenderer.cpython-35m-x86_64-linux-gnu.so'
|
||||
plugin = p.loadPlugin(plugin_fn,"_tinyRendererPlugin")
|
||||
if plugin < 0:
|
||||
print("\nPlugin Failed to load!\n")
|
||||
sys.exit()
|
||||
print("plugin =",plugin)
|
||||
|
||||
path = '/home/argusm/lang/bullet3/examples/pybullet/gym/pybullet_data/duck_vhacd.urdf'
|
||||
p.loadURDF(path,globalScaling=12)
|
||||
#path = '/home/argusm/lang/gym-grasping/gym_grasping/robots/models/kuka_iiwa/kuka_weiss_bolt.sdf'
|
||||
#p.loadSDF(path)
|
||||
|
||||
start = time.time()
|
||||
|
||||
camTargetPos = [0,0,0]
|
||||
upAxisIndex = 2
|
||||
nearPlane = 0.01
|
||||
farPlane = 100
|
||||
camDistance = 2
|
||||
pixelWidth = 128
|
||||
pixelHeight = 128
|
||||
fov = 60
|
||||
|
||||
plot = False
|
||||
anim = True
|
||||
if plot:
|
||||
plt.ion()
|
||||
if anim:
|
||||
import matplotlib.animation as manimation
|
||||
FFMpegWriter = manimation.writers['ffmpeg']
|
||||
metadata = dict(title='Movie Test', artist='Matplotlib',
|
||||
comment='Movie support!')
|
||||
writer = FFMpegWriter(fps=15, metadata=metadata)
|
||||
if plot or anim:
|
||||
fig = plt.figure()
|
||||
img = np.random.rand(pixelWidth,pixelHeight)
|
||||
image = plt.imshow(img,interpolation='none',animated=True,label="blah")
|
||||
ax = plt.gca()
|
||||
ax.set_axis_off()
|
||||
ax.set_aspect('equal')
|
||||
plt.subplots_adjust(wspace=0, hspace=0, left=0, bottom=0, right=1, top=1)
|
||||
|
||||
|
||||
try:
|
||||
iter = range(0,360,10)
|
||||
with writer.saving(fig, "debug.mp4", len(iter)):
|
||||
for i,yaw in enumerate(iter):
|
||||
viewMatrix = p.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, 0, yaw-90, 0, upAxisIndex)
|
||||
aspect = pixelWidth / pixelHeight;
|
||||
projectionMatrix = p.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
||||
|
||||
hight, width, img_arr, deept_arr, obj_arr = p.getCameraImage(pixelWidth,pixelHeight,viewMatrix,projectionMatrix)
|
||||
if plot:
|
||||
image.set_data(img_arr)#np_img_arr)
|
||||
ax.plot([0])
|
||||
#plt.draw()
|
||||
#plt.show()
|
||||
plt.pause(0.01)
|
||||
if anim:
|
||||
image.set_data(img_arr)#np_img_arr)
|
||||
ax.plot([0])
|
||||
writer.grab_frame()
|
||||
|
||||
if i % 100 == 0 and i > 0:
|
||||
print("FPS",100/(time.time()-start))
|
||||
start = time.time()
|
||||
finally:
|
||||
p.stopStateLogging(logId)
|
||||
@@ -1,15 +1,7 @@
|
||||
|
||||
//tinyRenderer plugin
|
||||
//eglRenderer plugin
|
||||
|
||||
/*
|
||||
import pybullet as p
|
||||
p.connect(p.GUI)
|
||||
plugin = p.loadPlugin("e:/develop/bullet3/bin/pybullet_tinyRendererPlugin_vs2010_x64_debug.dll","_tinyRendererPlugin")
|
||||
print("plugin=",plugin)
|
||||
p.loadURDF("r2d2.urdf")
|
||||
while (1):
|
||||
p.getCameraImage(320,200)
|
||||
*/
|
||||
//see Bullet/examples/pybullet/examples/eglRendererTest.py
|
||||
|
||||
#include "eglRendererPlugin.h"
|
||||
#include "eglRendererVisualShapeConverter.h"
|
||||
@@ -20,43 +12,43 @@ while (1):
|
||||
|
||||
|
||||
|
||||
struct MyRendererPluginClass
|
||||
struct EGLRendererPluginClass
|
||||
{
|
||||
|
||||
TinyRendererVisualShapeConverter m_renderer;
|
||||
MyRendererPluginClass()
|
||||
EGLRendererVisualShapeConverter m_renderer;
|
||||
EGLRendererPluginClass()
|
||||
{
|
||||
}
|
||||
virtual ~MyRendererPluginClass()
|
||||
virtual ~EGLRendererPluginClass()
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
B3_SHARED_API int initPlugin_tinyRendererPlugin(struct b3PluginContext* context)
|
||||
B3_SHARED_API int initPlugin_eglRendererPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyRendererPluginClass* obj = new MyRendererPluginClass();
|
||||
EGLRendererPluginClass* obj = new EGLRendererPluginClass();
|
||||
context->m_userPointer = obj;
|
||||
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API int executePluginCommand_tinyRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
|
||||
B3_SHARED_API int executePluginCommand_eglRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API void exitPlugin_tinyRendererPlugin(struct b3PluginContext* context)
|
||||
B3_SHARED_API void exitPlugin_eglRendererPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyRendererPluginClass* obj = (MyRendererPluginClass*) context->m_userPointer;
|
||||
EGLRendererPluginClass* obj = (EGLRendererPluginClass*) context->m_userPointer;
|
||||
delete obj;
|
||||
context->m_userPointer = 0;
|
||||
}
|
||||
|
||||
//all the APIs below are optional
|
||||
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_tinyRendererPlugin(struct b3PluginContext* context)
|
||||
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_eglRendererPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyRendererPluginClass* obj = (MyRendererPluginClass*) context->m_userPointer;
|
||||
EGLRendererPluginClass* obj = (EGLRendererPluginClass*) context->m_userPointer;
|
||||
return &obj->m_renderer;
|
||||
}
|
||||
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
#ifndef TINY_RENDERER_PLUGIN_H
|
||||
#define TINY_RENDERER_PLUGIN_H
|
||||
#ifndef EGL_RENDERER_PLUGIN_H
|
||||
#define EGL_RENDERER_PLUGIN_H
|
||||
|
||||
#include "../b3PluginAPI.h"
|
||||
|
||||
@@ -9,12 +9,12 @@ extern "C"
|
||||
#endif
|
||||
|
||||
//initPlugin, exitPlugin and executePluginCommand are required, otherwise plugin won't load
|
||||
B3_SHARED_API int initPlugin_tinyRendererPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API void exitPlugin_tinyRendererPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API int executePluginCommand_tinyRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||
B3_SHARED_API int initPlugin_eglRendererPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API void exitPlugin_eglRendererPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API int executePluginCommand_eglRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments);
|
||||
|
||||
//all the APIs below are optional
|
||||
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_tinyRendererPlugin(struct b3PluginContext* context);
|
||||
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_eglRendererPlugin(struct b3PluginContext* context);
|
||||
|
||||
|
||||
|
||||
@@ -22,4 +22,4 @@ B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_tinyRendererPlug
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif//#define TEST_PLUGIN_H
|
||||
#endif//#define EGL_RENDERER_PLUGIN_H
|
||||
|
||||
@@ -13,10 +13,6 @@ subject to the following restrictions:
|
||||
|
||||
|
||||
#include "eglRendererVisualShapeConverter.h"
|
||||
|
||||
|
||||
|
||||
|
||||
#include "../Importers/ImportURDFDemo/URDFImporterInterface.h"
|
||||
#include "btBulletCollisionCommon.h"
|
||||
#include "../Importers/ImportObjDemo/LoadMeshFromObj.h"
|
||||
@@ -38,9 +34,21 @@ subject to the following restrictions:
|
||||
#include "stb_image/stb_image.h"
|
||||
|
||||
|
||||
#include "../OpenGLWindow/EGLOpenGLWindow.h"
|
||||
#include "../OpenGLWindow/GLInstancingRenderer.h"
|
||||
#include "../OpenGLWindow/GLRenderToTexture.h"
|
||||
#ifdef _WIN32
|
||||
#include "OpenGLWindow/Win32OpenGLWindow.h"
|
||||
typedef Win32OpenGLWindow DefaultOpenGLWindow;
|
||||
#else
|
||||
#ifdef BT_USE_EGL
|
||||
#include "OpenGLWindow/EGLOpenGLWindow.h"
|
||||
typedef EGLOpenGLWindow DefaultOpenGLWindow;
|
||||
#else
|
||||
#include "OpenGLWindow/X11OpenGLWindow.h"
|
||||
typedef X11OpenGLWindow DefaultOpenGLWindow;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#include "OpenGLWindow/GLInstancingRenderer.h"
|
||||
#include "OpenGLWindow/GLRenderToTexture.h"
|
||||
|
||||
static void printGLString(const char *name, GLenum s) {
|
||||
const char *v = (const char *) glGetString(s);
|
||||
@@ -62,6 +70,7 @@ struct TinyRendererObjectArray
|
||||
btAlignedObjectArray< TinyRenderObjectData*> m_renderObjects;
|
||||
int m_objectUniqueId;
|
||||
int m_linkIndex;
|
||||
int m_graphicsInstanceId;
|
||||
btTransform m_worldTransform;
|
||||
btVector3 m_localScaling;
|
||||
|
||||
@@ -69,13 +78,14 @@ struct TinyRendererObjectArray
|
||||
{
|
||||
m_worldTransform.setIdentity();
|
||||
m_localScaling.setValue(1,1,1);
|
||||
m_graphicsInstanceId = -1;
|
||||
}
|
||||
};
|
||||
|
||||
#define START_WIDTH 640
|
||||
#define START_HEIGHT 480
|
||||
|
||||
struct TinyRendererVisualShapeConverterInternalData
|
||||
struct EGLRendererVisualShapeConverterInternalData
|
||||
{
|
||||
class CommonWindowInterface* m_window;
|
||||
class GLInstancingRenderer* m_instancingRenderer;
|
||||
@@ -111,7 +121,7 @@ struct TinyRendererVisualShapeConverterInternalData
|
||||
SimpleCamera m_camera;
|
||||
|
||||
|
||||
TinyRendererVisualShapeConverterInternalData()
|
||||
EGLRendererVisualShapeConverterInternalData()
|
||||
:m_upAxis(2),
|
||||
m_swWidth(START_WIDTH),
|
||||
m_swHeight(START_HEIGHT),
|
||||
@@ -137,7 +147,7 @@ struct TinyRendererVisualShapeConverterInternalData
|
||||
|
||||
// OpenGL window
|
||||
bool allowRetina=true;
|
||||
m_window = new EGLOpenGLWindow();
|
||||
m_window = new DefaultOpenGLWindow();
|
||||
m_window->setAllowRetina(allowRetina);
|
||||
b3gWindowConstructionInfo ci;
|
||||
ci.m_title = "Title";
|
||||
@@ -156,6 +166,8 @@ struct TinyRendererVisualShapeConverterInternalData
|
||||
glClearColor(.7f, .7f, .8f, 1.f);
|
||||
|
||||
m_window->startRendering();
|
||||
|
||||
|
||||
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
||||
@@ -165,21 +177,34 @@ struct TinyRendererVisualShapeConverterInternalData
|
||||
int maxNumObjectCapacity = 128 * 1024;
|
||||
int maxShapeCapacityInBytes = 128 * 1024 * 1024;
|
||||
m_instancingRenderer = new GLInstancingRenderer(maxNumObjectCapacity, maxShapeCapacityInBytes);
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
m_instancingRenderer->init();
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
m_instancingRenderer->resize(m_swWidth,m_swHeight);
|
||||
m_instancingRenderer->InitShaders();
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
m_instancingRenderer->setActiveCamera(&m_camera);
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
m_instancingRenderer->updateCamera();
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
m_instancingRenderer->setLightPosition(m_lightDirection);
|
||||
m_window->endRendering();
|
||||
}
|
||||
|
||||
virtual ~EGLRendererVisualShapeConverterInternalData()
|
||||
{
|
||||
delete m_instancingRenderer;
|
||||
m_window->closeWindow();
|
||||
delete m_window;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
TinyRendererVisualShapeConverter::TinyRendererVisualShapeConverter()
|
||||
EGLRendererVisualShapeConverter::EGLRendererVisualShapeConverter()
|
||||
{
|
||||
m_data = new TinyRendererVisualShapeConverterInternalData();
|
||||
m_data = new EGLRendererVisualShapeConverterInternalData();
|
||||
|
||||
float dist = 1.5;
|
||||
float pitch = -10;
|
||||
@@ -190,59 +215,60 @@ TinyRendererVisualShapeConverter::TinyRendererVisualShapeConverter()
|
||||
|
||||
|
||||
}
|
||||
TinyRendererVisualShapeConverter::~TinyRendererVisualShapeConverter()
|
||||
EGLRendererVisualShapeConverter::~EGLRendererVisualShapeConverter()
|
||||
{
|
||||
resetAll();
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::setLightDirection(float x, float y, float z)
|
||||
void EGLRendererVisualShapeConverter::setLightDirection(float x, float y, float z)
|
||||
{
|
||||
m_data->m_lightDirection.setValue(x, y, z);
|
||||
m_data->m_hasLightDirection = true;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::setLightColor(float x, float y, float z)
|
||||
void EGLRendererVisualShapeConverter::setLightColor(float x, float y, float z)
|
||||
{
|
||||
m_data->m_lightColor.setValue(x, y, z);
|
||||
m_data->m_hasLightColor = true;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::setLightDistance(float dist)
|
||||
void EGLRendererVisualShapeConverter::setLightDistance(float dist)
|
||||
{
|
||||
m_data->m_lightDistance = dist;
|
||||
m_data->m_hasLightDistance = true;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::setShadow(bool hasShadow)
|
||||
void EGLRendererVisualShapeConverter::setShadow(bool hasShadow)
|
||||
{
|
||||
m_data->m_hasShadow = hasShadow;
|
||||
}
|
||||
void TinyRendererVisualShapeConverter::setFlags(int flags)
|
||||
void EGLRendererVisualShapeConverter::setFlags(int flags)
|
||||
{
|
||||
m_data->m_flags = flags;
|
||||
}
|
||||
|
||||
|
||||
void TinyRendererVisualShapeConverter::setLightAmbientCoeff(float ambientCoeff)
|
||||
void EGLRendererVisualShapeConverter::setLightAmbientCoeff(float ambientCoeff)
|
||||
{
|
||||
m_data->m_lightAmbientCoeff = ambientCoeff;
|
||||
m_data->m_hasLightAmbientCoeff = true;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::setLightDiffuseCoeff(float diffuseCoeff)
|
||||
void EGLRendererVisualShapeConverter::setLightDiffuseCoeff(float diffuseCoeff)
|
||||
{
|
||||
m_data->m_lightDiffuseCoeff = diffuseCoeff;
|
||||
m_data->m_hasLightDiffuseCoeff = true;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::setLightSpecularCoeff(float specularCoeff)
|
||||
void EGLRendererVisualShapeConverter::setLightSpecularCoeff(float specularCoeff)
|
||||
{
|
||||
m_data->m_lightSpecularCoeff = specularCoeff;
|
||||
m_data->m_hasLightSpecularCoeff = true;
|
||||
}
|
||||
|
||||
void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture2>& texturesOut, b3VisualShapeData& visualShapeOut)
|
||||
///todo: merge into single file with TinyRendererVisualShapeConverter
|
||||
static void convertURDFToVisualShape2(const UrdfShape* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture2>& texturesOut, b3VisualShapeData& visualShapeOut)
|
||||
{
|
||||
|
||||
visualShapeOut.m_visualGeometryType = visual->m_geometry.m_type;
|
||||
@@ -609,7 +635,7 @@ static btVector4 sColors[4] =
|
||||
// If you are getting segfaults in this function it may be ecause you are
|
||||
// compliling the plugin with differently from pybullet, try complining the
|
||||
// plugin with distutils too.
|
||||
void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
void EGLRendererVisualShapeConverter::convertVisualShapes(
|
||||
int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame,
|
||||
const UrdfLink* linkPtr, const UrdfModel* model,
|
||||
int collisionObjectUniqueId, int bodyUniqueId)
|
||||
@@ -728,8 +754,8 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
visualShape.m_rgbaColor[2] = rgbaColor[2];
|
||||
visualShape.m_rgbaColor[3] = rgbaColor[3];
|
||||
{
|
||||
B3_PROFILE("convertURDFToVisualShape");
|
||||
convertURDFToVisualShape(vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices, textures, visualShape);
|
||||
B3_PROFILE("convertURDFToVisualShape2");
|
||||
convertURDFToVisualShape2(vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices, textures, visualShape);
|
||||
}
|
||||
m_data->m_visualShapes.push_back(visualShape);
|
||||
|
||||
@@ -739,14 +765,17 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
unsigned char* textureImage1=0;
|
||||
int textureWidth=0;
|
||||
int textureHeight=0;
|
||||
bool isCached = false;
|
||||
bool isCached = false;
|
||||
int textureIndex = -1;
|
||||
|
||||
if (textures.size())
|
||||
{
|
||||
textureImage1 = textures[0].textureData1;
|
||||
textureWidth = textures[0].m_width;
|
||||
textureHeight = textures[0].m_height;
|
||||
isCached = textures[0].m_isCached;
|
||||
}
|
||||
textureIndex = m_data->m_instancingRenderer->registerTexture(textureImage1, textureWidth, textureHeight);
|
||||
}
|
||||
|
||||
{
|
||||
B3_PROFILE("registerMeshShape");
|
||||
@@ -760,10 +789,11 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
B3_PROFILE("m_instancingRenderer register");
|
||||
|
||||
// register mesh to m_instancingRenderer too.
|
||||
int textureIndex = m_data->m_instancingRenderer->registerTexture(textureImage1, textureWidth, textureHeight);
|
||||
int shapeIndex = m_data->m_instancingRenderer->registerShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(),textureIndex);
|
||||
|
||||
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);
|
||||
m_data->m_instancingRenderer->registerGraphicsInstance(shapeIndex, &visualShape.m_localVisualFrame[0], &visualShape.m_localVisualFrame[3], &visualShape.m_rgbaColor[0],scaling);
|
||||
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();
|
||||
}
|
||||
}
|
||||
@@ -778,7 +808,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||
}
|
||||
}
|
||||
|
||||
int TinyRendererVisualShapeConverter::getNumVisualShapes(int bodyUniqueId)
|
||||
int EGLRendererVisualShapeConverter::getNumVisualShapes(int bodyUniqueId)
|
||||
{
|
||||
int start = -1;
|
||||
//find first one, then count how many
|
||||
@@ -810,7 +840,7 @@ int TinyRendererVisualShapeConverter::getNumVisualShapes(int bodyUniqueId)
|
||||
return count;
|
||||
}
|
||||
|
||||
int TinyRendererVisualShapeConverter::getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData)
|
||||
int EGLRendererVisualShapeConverter::getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData)
|
||||
{
|
||||
int start = -1;
|
||||
//find first one, then count how many
|
||||
@@ -837,7 +867,7 @@ int TinyRendererVisualShapeConverter::getVisualShapesData(int bodyUniqueId, int
|
||||
|
||||
|
||||
|
||||
void TinyRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4])
|
||||
void EGLRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4])
|
||||
{
|
||||
//int start = -1;
|
||||
for (int i = 0; i < m_data->m_visualShapes.size(); i++)
|
||||
@@ -874,7 +904,7 @@ void TinyRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int lin
|
||||
|
||||
|
||||
|
||||
void TinyRendererVisualShapeConverter::setUpAxis(int axis)
|
||||
void EGLRendererVisualShapeConverter::setUpAxis(int axis)
|
||||
{
|
||||
m_data->m_upAxis = axis;
|
||||
m_data->m_camera.setCameraUpAxis(axis);
|
||||
@@ -882,7 +912,7 @@ void TinyRendererVisualShapeConverter::setUpAxis(int axis)
|
||||
m_data->m_instancingRenderer->updateCamera();
|
||||
|
||||
}
|
||||
void TinyRendererVisualShapeConverter::resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ)
|
||||
void EGLRendererVisualShapeConverter::resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ)
|
||||
{
|
||||
m_data->m_camera.setCameraDistance(camDist);
|
||||
m_data->m_camera.setCameraPitch(pitch);
|
||||
@@ -892,7 +922,7 @@ void TinyRendererVisualShapeConverter::resetCamera(float camDist, float yaw, flo
|
||||
m_data->m_camera.update();
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor)
|
||||
void EGLRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor)
|
||||
{
|
||||
float farPlane = m_data->m_camera.getCameraFrustumFar();
|
||||
for(int y=0;y<m_data->m_swHeight;++y)
|
||||
@@ -908,8 +938,10 @@ void TinyRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor)
|
||||
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::render()
|
||||
void EGLRendererVisualShapeConverter::render()
|
||||
{
|
||||
m_data->m_window->endRendering();
|
||||
m_data->m_window->startRendering();
|
||||
/*
|
||||
ATTRIBUTE_ALIGNED16(float viewMat[16]);
|
||||
ATTRIBUTE_ALIGNED16(float projMat[16]);
|
||||
@@ -920,13 +952,21 @@ void TinyRendererVisualShapeConverter::render()
|
||||
cout<<viewMat[4*2 + 0]<<" "<<viewMat[4*2+1]<<" "<<viewMat[4*2+2]<<" "<<viewMat[4*2+3] << endl;
|
||||
cout<<viewMat[4*3 + 0]<<" "<<viewMat[4*3+1]<<" "<<viewMat[4*3+2]<<" "<<viewMat[4*3+3] << endl;
|
||||
*/
|
||||
|
||||
B3_PROFILE("m_instancingRenderer render");
|
||||
m_data->m_instancingRenderer->setActiveCamera(&m_data->m_camera);
|
||||
m_data->m_instancingRenderer->updateCamera();
|
||||
m_data->m_instancingRenderer->writeTransforms();
|
||||
if (m_data->m_hasLightDirection)
|
||||
{
|
||||
m_data->m_instancingRenderer->setLightPosition(m_data->m_lightDirection);
|
||||
}
|
||||
m_data->m_instancingRenderer->setActiveCamera(&m_data->m_camera);
|
||||
m_data->m_instancingRenderer->updateCamera(m_data->m_upAxis);
|
||||
|
||||
m_data->m_instancingRenderer->renderScene();
|
||||
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::render(const float viewMat[16], const float projMat[16])
|
||||
void EGLRendererVisualShapeConverter::render(const float viewMat[16], const float projMat[16])
|
||||
{
|
||||
// This code is very similar to that of
|
||||
// PhysicsServerCommandProcessor::processRequestCameraImageCommand
|
||||
@@ -934,10 +974,10 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
|
||||
|
||||
// Tiny allows rendering with viewMat, projMat explicitly, but
|
||||
// GLInstancingRender calls m_activeCamera, so set this.
|
||||
m_data->m_camera.setVRCamera(viewMat,projMat);
|
||||
m_data->m_instancingRenderer->setActiveCamera(&m_data->m_camera);
|
||||
m_data->m_instancingRenderer->updateCamera();
|
||||
m_data->m_instancingRenderer->renderScene();
|
||||
|
||||
m_data->m_camera.setVRCamera(viewMat,projMat);
|
||||
|
||||
render();
|
||||
|
||||
//cout<<viewMat[4*0 + 0]<<" "<<viewMat[4*0+1]<<" "<<viewMat[4*0+2]<<" "<<viewMat[4*0+3] << endl;
|
||||
//cout<<viewMat[4*1 + 0]<<" "<<viewMat[4*1+1]<<" "<<viewMat[4*1+2]<<" "<<viewMat[4*1+3] << endl;
|
||||
@@ -945,14 +985,14 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
|
||||
//cout<<viewMat[4*3 + 0]<<" "<<viewMat[4*3+1]<<" "<<viewMat[4*3+2]<<" "<<viewMat[4*3+3] << endl;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::getWidthAndHeight(int& width, int& height)
|
||||
void EGLRendererVisualShapeConverter::getWidthAndHeight(int& width, int& height)
|
||||
{
|
||||
width = m_data->m_swWidth;
|
||||
height = m_data->m_swHeight;
|
||||
}
|
||||
|
||||
|
||||
void TinyRendererVisualShapeConverter::setWidthAndHeight(int width, int height)
|
||||
void EGLRendererVisualShapeConverter::setWidthAndHeight(int width, int height)
|
||||
{
|
||||
m_data->m_swWidth = width;
|
||||
m_data->m_swHeight = height;
|
||||
@@ -966,7 +1006,7 @@ void TinyRendererVisualShapeConverter::setWidthAndHeight(int width, int height)
|
||||
}
|
||||
|
||||
//copied from OpenGLGuiHelper.cpp
|
||||
void TinyRendererVisualShapeConverter::copyCameraImageDataGL(
|
||||
void EGLRendererVisualShapeConverter::copyCameraImageDataGL(
|
||||
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
||||
float* depthBuffer, int depthBufferSizeInPixels,
|
||||
int* segmentationMaskBuffer, int segmentationMaskSizeInPixels,
|
||||
@@ -1079,7 +1119,7 @@ void TinyRendererVisualShapeConverter::copyCameraImageDataGL(
|
||||
}
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
||||
void EGLRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
||||
float* depthBuffer, int depthBufferSizeInPixels,
|
||||
int* segmentationMaskBuffer, int segmentationMaskSizeInPixels,
|
||||
int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied)
|
||||
@@ -1091,7 +1131,7 @@ void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixels
|
||||
startPixelIndex, widthPtr, heightPtr, numPixelsCopied);
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::removeVisualShape(int collisionObjectUniqueId)
|
||||
void EGLRendererVisualShapeConverter::removeVisualShape(int collisionObjectUniqueId)
|
||||
{
|
||||
TinyRendererObjectArray** ptrptr = m_data->m_swRenderInstances[collisionObjectUniqueId];
|
||||
if (ptrptr && *ptrptr)
|
||||
@@ -1110,7 +1150,7 @@ void TinyRendererVisualShapeConverter::removeVisualShape(int collisionObjectUniq
|
||||
}
|
||||
|
||||
|
||||
void TinyRendererVisualShapeConverter::resetAll()
|
||||
void EGLRendererVisualShapeConverter::resetAll()
|
||||
{
|
||||
for (int i=0;i<m_data->m_swRenderInstances.size();i++)
|
||||
{
|
||||
@@ -1142,7 +1182,7 @@ void TinyRendererVisualShapeConverter::resetAll()
|
||||
}
|
||||
|
||||
|
||||
void TinyRendererVisualShapeConverter::changeShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId)
|
||||
void EGLRendererVisualShapeConverter::changeShapeTexture(int objectUniqueId, int jointIndex, int shapeIndex, int textureUniqueId)
|
||||
{
|
||||
btAssert(textureUniqueId < m_data->m_textures.size());
|
||||
if (textureUniqueId >= 0 && textureUniqueId < m_data->m_textures.size())
|
||||
@@ -1170,7 +1210,7 @@ void TinyRendererVisualShapeConverter::changeShapeTexture(int objectUniqueId, in
|
||||
}
|
||||
}
|
||||
|
||||
int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int width, int height)
|
||||
int EGLRendererVisualShapeConverter::registerTexture(unsigned char* texels, int width, int height)
|
||||
{
|
||||
MyTexture2 texData;
|
||||
texData.m_width = width;
|
||||
@@ -1181,7 +1221,7 @@ int TinyRendererVisualShapeConverter::registerTexture(unsigned char* texels, int
|
||||
return m_data->m_textures.size()-1;
|
||||
}
|
||||
|
||||
int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename)
|
||||
int EGLRendererVisualShapeConverter::loadTextureFile(const char* filename)
|
||||
{
|
||||
B3_PROFILE("loadTextureFile");
|
||||
int width,height,n;
|
||||
@@ -1194,7 +1234,7 @@ int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename)
|
||||
return -1;
|
||||
}
|
||||
|
||||
void TinyRendererVisualShapeConverter::syncTransform(int collisionObjectUniqueId, const btTransform& worldTransform, const btVector3& localScaling)
|
||||
void EGLRendererVisualShapeConverter::syncTransform(int collisionObjectUniqueId, const btTransform& worldTransform, const btVector3& localScaling)
|
||||
{
|
||||
TinyRendererObjectArray** renderObjPtr = m_data->m_swRenderInstances[collisionObjectUniqueId];
|
||||
if (renderObjPtr)
|
||||
@@ -1202,5 +1242,11 @@ void TinyRendererVisualShapeConverter::syncTransform(int collisionObjectUniqueId
|
||||
TinyRendererObjectArray* renderObj = *renderObjPtr;
|
||||
renderObj->m_worldTransform = worldTransform;
|
||||
renderObj->m_localScaling = localScaling;
|
||||
if (renderObj->m_graphicsInstanceId>=0)
|
||||
{
|
||||
btVector3 pos = worldTransform.getOrigin();
|
||||
btQuaternion orn = worldTransform.getRotation();
|
||||
m_data->m_instancingRenderer->writeSingleInstanceTransformToCPU(pos, orn, renderObj->m_graphicsInstanceId);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -3,15 +3,14 @@
|
||||
|
||||
#include "../../../Importers/ImportURDFDemo/UrdfRenderingInterface.h"
|
||||
|
||||
struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
|
||||
struct EGLRendererVisualShapeConverter : public UrdfRenderingInterface
|
||||
{
|
||||
int frame = 0;
|
||||
|
||||
struct TinyRendererVisualShapeConverterInternalData* m_data;
|
||||
|
||||
struct EGLRendererVisualShapeConverterInternalData* m_data;
|
||||
|
||||
TinyRendererVisualShapeConverter();
|
||||
EGLRendererVisualShapeConverter();
|
||||
|
||||
virtual ~TinyRendererVisualShapeConverter();
|
||||
virtual ~EGLRendererVisualShapeConverter();
|
||||
|
||||
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int shapeUid, int objectIndex);
|
||||
|
||||
|
||||
@@ -3,25 +3,36 @@
|
||||
project ("pybullet_eglRendererPlugin")
|
||||
language "C++"
|
||||
kind "SharedLib"
|
||||
initEGL()
|
||||
|
||||
includedirs {".","../../../../src", "../../../../examples",
|
||||
"../../../ThirdPartyLibs"}
|
||||
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
|
||||
"../../../ThirdPartyLibs", "../../examples/ThirdPartyLibs/glad"}
|
||||
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER", "STB_AGAIN"}
|
||||
hasCL = findOpenCL("clew")
|
||||
|
||||
links{"BulletCollision", "Bullet3Common", "LinearMath"}
|
||||
|
||||
initOpenGL()
|
||||
|
||||
if os.is("Windows") then
|
||||
files {"../../../OpenGLWindow/Win32OpenGLWindow.cpp",
|
||||
"../../../OpenGLWindow/Win32GLWindow.cpp",}
|
||||
|
||||
end
|
||||
if os.is("MacOSX") then
|
||||
-- targetextension {"so"}
|
||||
links{"Cocoa.framework","Python"}
|
||||
links{"Cocoa.framework"}
|
||||
end
|
||||
|
||||
if os.is("Linux") then
|
||||
files {"../../../ThirdPartyLibs/glad/glx.c",}
|
||||
end
|
||||
|
||||
files {
|
||||
"eglRendererPlugin.cpp",
|
||||
"eglRendererPlugin.h",
|
||||
"TinyRendererVisualShapeConverter.cpp",
|
||||
"TinyRendererVisualShapeConverter.h",
|
||||
"eglRendererVisualShapeConverter.cpp",
|
||||
"eglRendererVisualShapeConverter.h",
|
||||
"../../../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
|
||||
"../../../Importers/ImportColladaDemo/LoadMeshFromCollada.h",
|
||||
"../../../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
|
||||
@@ -35,14 +46,22 @@ project ("pybullet_eglRendererPlugin")
|
||||
"../../../TinyRenderer/our_gl.cpp",
|
||||
"../../../TinyRenderer/tgaimage.cpp",
|
||||
"../../../TinyRenderer/TinyRenderer.cpp",
|
||||
"../../../ThirdPartyLibs/Wavefront/egl_obj_loader.cpp",
|
||||
"../../../ThirdPartyLibs/Wavefront/egl_obj_loader.h",
|
||||
"../../../ThirdPartyLibs/glad/gl.c",
|
||||
"../../../ThirdPartyLibs/glad/egl.c",
|
||||
"../../../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
|
||||
"../../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
|
||||
"../../../ThirdPartyLibs/stb_image/stb_image.cpp",
|
||||
"../../../ThirdPartyLibs/stb_image/stb_image.h",
|
||||
"../../../ThirdPartyLibs/eglxml2/eglxml2.cpp",
|
||||
"../../../ThirdPartyLibs/eglxml2/eglxml2.h",
|
||||
"../../../ThirdPartyLibs/tinyxml2/tinyxml2.cpp",
|
||||
"../../../ThirdPartyLibs/tinyxml2/tinyxml2.h",
|
||||
"../../../OpenGLWindow/SimpleCamera.cpp",
|
||||
"../../../OpenGLWindow/SimpleCamera.h",
|
||||
"../../../OpenGLWindow/GLInstancingRenderer.cpp",
|
||||
"../../../OpenGLWindow/GLInstancingRenderer.h",
|
||||
"../../../OpenGLWindow/LoadShader.cpp",
|
||||
"../../../OpenGLWindow/LoadShader.h",
|
||||
"../../../OpenGLWindow/GLRenderToTexture.cpp",
|
||||
"../../../OpenGLWindow/GLRenderToTexture.h",
|
||||
"../../../Utils/b3Clock.cpp",
|
||||
"../../../Utils/b3Clock.h",
|
||||
"../../../Utils/b3ResourcePath.cpp",
|
||||
|
||||
@@ -120,6 +120,10 @@ struct TinyRendererVisualShapeConverterInternalData
|
||||
m_segmentationMaskBuffer.resize(m_swWidth*m_swHeight,-1);
|
||||
}
|
||||
|
||||
virtual ~TinyRendererVisualShapeConverterInternalData()
|
||||
{
|
||||
printf("~TinyRendererVisualShapeConverterInternalData()\n");
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
|
||||
@@ -474,6 +474,10 @@ include "plugins/tinyRendererPlugin"
|
||||
include "plugins/pdControlPlugin"
|
||||
include "plugins/collisionFilterPlugin"
|
||||
|
||||
if _OPTIONS["enable_egl"] then
|
||||
include "plugins/eglPlugin"
|
||||
end
|
||||
|
||||
if _OPTIONS["enable_grpc"] then
|
||||
include "grpc"
|
||||
include "plugins/grpcPlugin"
|
||||
|
||||
@@ -15,6 +15,8 @@ ax = plt.gca()
|
||||
|
||||
|
||||
pybullet.connect(pybullet.DIRECT)
|
||||
|
||||
#pybullet.loadPlugin("eglRendererPlugin")
|
||||
pybullet.loadURDF("plane.urdf",[0,0,-1])
|
||||
pybullet.loadURDF("r2d2.urdf")
|
||||
|
||||
|
||||
86
examples/pybullet/examples/testrender_egl.py
Normal file
86
examples/pybullet/examples/testrender_egl.py
Normal file
@@ -0,0 +1,86 @@
|
||||
#using the eglRendererPlugin (hardware OpenGL acceleration)
|
||||
#using EGL on Linux and default OpenGL window on Win32.
|
||||
|
||||
#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled
|
||||
#otherwise use testrender.py (slower but compatible without numpy)
|
||||
#you can also use GUI mode, for faster OpenGL rendering (instead of TinyRender CPU)
|
||||
|
||||
import numpy as np
|
||||
import matplotlib.pyplot as plt
|
||||
import pybullet
|
||||
import time
|
||||
|
||||
|
||||
plt.ion()
|
||||
|
||||
img = np.random.rand(200, 320)
|
||||
#img = [tandard_normal((50,100))
|
||||
image = plt.imshow(img,interpolation='none',animated=True,label="blah")
|
||||
ax = plt.gca()
|
||||
|
||||
pybullet.connect(pybullet.DIRECT)
|
||||
|
||||
pybullet.loadPlugin("eglRendererPlugin")
|
||||
pybullet.loadURDF("plane.urdf",[0,0,-1])
|
||||
pybullet.loadURDF("r2d2.urdf")
|
||||
|
||||
camTargetPos = [0,0,0]
|
||||
cameraUp = [0,0,1]
|
||||
cameraPos = [1,1,1]
|
||||
pybullet.setGravity(0,0,-10)
|
||||
|
||||
pitch = -10.0
|
||||
|
||||
roll=0
|
||||
upAxisIndex = 2
|
||||
camDistance = 4
|
||||
pixelWidth = 320
|
||||
pixelHeight = 200
|
||||
nearPlane = 0.01
|
||||
farPlane = 100
|
||||
|
||||
fov = 60
|
||||
|
||||
main_start = time.time()
|
||||
while (1):
|
||||
for yaw in range (0,360,10):
|
||||
pybullet.stepSimulation()
|
||||
start = time.time()
|
||||
|
||||
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
|
||||
aspect = pixelWidth / pixelHeight;
|
||||
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
|
||||
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, shadow=1,lightDirection=[1,1,1],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
|
||||
stop = time.time()
|
||||
print ("renderImage %f" % (stop - start))
|
||||
|
||||
w=img_arr[0] #width of the image, in pixels
|
||||
h=img_arr[1] #height of the image, in pixels
|
||||
rgb=img_arr[2] #color data RGB
|
||||
dep=img_arr[3] #depth data
|
||||
|
||||
print ('width = %d height = %d' % (w,h))
|
||||
|
||||
#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.)
|
||||
|
||||
#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)
|
||||
ax.plot([0])
|
||||
#plt.draw()
|
||||
#plt.show()
|
||||
plt.pause(0.01)
|
||||
#image.draw()
|
||||
|
||||
|
||||
main_stop = time.time()
|
||||
|
||||
print ("Total time %f" % (main_stop - main_start))
|
||||
|
||||
pybullet.resetSimulation()
|
||||
@@ -9596,7 +9596,7 @@ PyMODINIT_FUNC
|
||||
#if PY_MAJOR_VERSION >= 3
|
||||
PyInit_pybullet(void)
|
||||
#else
|
||||
#ifdef BT_USE_EGL
|
||||
#ifdef BT_USE_EGL2
|
||||
initpybullet_egl(void)
|
||||
#else
|
||||
#ifdef BT_PYBULLET_GRPC
|
||||
@@ -9760,6 +9760,8 @@ 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);
|
||||
|
||||
105
setup.py
105
setup.py
@@ -1,33 +1,14 @@
|
||||
|
||||
|
||||
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
|
||||
|
||||
|
||||
# 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
|
||||
|
||||
from glob import glob
|
||||
|
||||
#see http://stackoverflow.com/a/8719066/295157
|
||||
import os
|
||||
@@ -42,7 +23,7 @@ CXX_FLAGS += '-DBT_USE_DOUBLE_PRECISION '
|
||||
CXX_FLAGS += '-DBT_ENABLE_ENET '
|
||||
CXX_FLAGS += '-DBT_ENABLE_CLSOCKET '
|
||||
CXX_FLAGS += '-DB3_DUMP_PYTHON_VERSION '
|
||||
CXX_FLAGS += '-DBT_USE_EGL ' # uncomment for EGL (old EGL versions fail)
|
||||
CXX_FLAGS += '-DSTATIC_EGLRENDERER_PLUGIN '
|
||||
|
||||
|
||||
# libraries += [current_python]
|
||||
@@ -69,6 +50,8 @@ 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"]\
|
||||
@@ -406,29 +389,26 @@ sources = ["examples/pybullet/pybullet.c"]\
|
||||
+["examples/ThirdPartyLibs/Gwen/Renderers/OpenGL_DebugFont.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 '
|
||||
CXX_FLAGS += '-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1 '
|
||||
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 '
|
||||
CXX_FLAGS += '-fno-inline-functions-called-once'
|
||||
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']
|
||||
+["examples/ThirdPartyLibs/glad/glx.c"]\
|
||||
+["examples/ThirdPartyLibs/glad/egl.c"]\
|
||||
+["examples/OpenGLWindow/EGLOpenGLWindow.cpp"]
|
||||
|
||||
include_dirs += ["examples/ThirdPartyLibs/optionalX11"]
|
||||
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"]\
|
||||
@@ -448,7 +428,7 @@ elif _platform == "darwin":
|
||||
+["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 '
|
||||
@@ -459,7 +439,6 @@ else:
|
||||
+["examples/ThirdPartyLibs/glad/gl.c"]\
|
||||
+ sources
|
||||
|
||||
|
||||
setup_py_dir = os.path.dirname(os.path.realpath(__file__))
|
||||
|
||||
need_files = []
|
||||
@@ -480,56 +459,6 @@ print("packages")
|
||||
print(find_packages('examples/pybullet/gym'))
|
||||
print("-----")
|
||||
|
||||
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/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/ThirdPartyLibs/glad/egl.c'] \
|
||||
+["examples/ThirdPartyLibs/glad/glx.c"] \
|
||||
+["examples/OpenGLWindow/GLInstancingRenderer.cpp"]\
|
||||
+["examples/OpenGLWindow/EGLOpenGLWindow.cpp"]\
|
||||
+["examples/OpenGLWindow/GLRenderToTexture.cpp"] \
|
||||
+["examples/OpenGLWindow/LoadShader.cpp"] \
|
||||
+["src/LinearMath/btQuickprof.cpp"] \
|
||||
|
||||
eglRender = Extension("eglRenderer",
|
||||
sources = egl_renderer_sources,
|
||||
libraries = libraries,
|
||||
extra_compile_args=(CXX_FLAGS+'-DBT_USE_EGL -DSTB_AGAIN -DB3_DEBUG').split(),
|
||||
include_dirs = include_dirs + ["src","examples/ThirdPartyLibs","examples/ThirdPartyLibs/glad", "examples/ThirdPartyLibs/enet/include","examples/ThirdPartyLibs/clsocket/src"]
|
||||
)
|
||||
|
||||
|
||||
setup(
|
||||
name = 'pybullet',
|
||||
version='2.1.4',
|
||||
@@ -541,11 +470,11 @@ setup(
|
||||
license='zlib',
|
||||
platforms='any',
|
||||
keywords=['game development', 'virtual reality', 'physics simulation', 'robotics', 'collision detection', 'opengl'],
|
||||
ext_modules = [eglRender, Extension("pybullet",
|
||||
ext_modules = [Extension("pybullet",
|
||||
sources = sources,
|
||||
libraries = libraries,
|
||||
extra_compile_args=CXX_FLAGS.split(),
|
||||
include_dirs = include_dirs + ["src","examples/ThirdPartyLibs","examples/ThirdPartyLibs/glad", "examples/ThirdPartyLibs/enet/include","examples/ThirdPartyLibs/clsocket/src"]
|
||||
include_dirs = include_dirs + ["src","examples", "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',
|
||||
|
||||
Reference in New Issue
Block a user