85
examples/SharedMemory/plugins/eglPlugin/bullet.py
Normal file
85
examples/SharedMemory/plugins/eglPlugin/bullet.py
Normal file
@@ -0,0 +1,85 @@
|
||||
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)
|
||||
@@ -0,0 +1,62 @@
|
||||
|
||||
//tinyRenderer 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)
|
||||
*/
|
||||
|
||||
#include "eglRendererPlugin.h"
|
||||
#include "eglRendererVisualShapeConverter.h"
|
||||
|
||||
#include "../../SharedMemoryPublic.h"
|
||||
#include "../b3PluginContext.h"
|
||||
#include <stdio.h>
|
||||
|
||||
|
||||
|
||||
struct MyRendererPluginClass
|
||||
{
|
||||
|
||||
TinyRendererVisualShapeConverter m_renderer;
|
||||
MyRendererPluginClass()
|
||||
{
|
||||
}
|
||||
virtual ~MyRendererPluginClass()
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
B3_SHARED_API int initPlugin_tinyRendererPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyRendererPluginClass* obj = new MyRendererPluginClass();
|
||||
context->m_userPointer = obj;
|
||||
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API int executePluginCommand_tinyRendererPlugin(struct b3PluginContext* context, const struct b3PluginArguments* arguments)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
B3_SHARED_API void exitPlugin_tinyRendererPlugin(struct b3PluginContext* context)
|
||||
{
|
||||
MyRendererPluginClass* obj = (MyRendererPluginClass*) 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)
|
||||
{
|
||||
MyRendererPluginClass* obj = (MyRendererPluginClass*) context->m_userPointer;
|
||||
return &obj->m_renderer;
|
||||
}
|
||||
|
||||
25
examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.h
Normal file
25
examples/SharedMemory/plugins/eglPlugin/eglRendererPlugin.h
Normal file
@@ -0,0 +1,25 @@
|
||||
#ifndef TINY_RENDERER_PLUGIN_H
|
||||
#define TINY_RENDERER_PLUGIN_H
|
||||
|
||||
#include "../b3PluginAPI.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
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);
|
||||
|
||||
//all the APIs below are optional
|
||||
B3_SHARED_API struct UrdfRenderingInterface* getRenderInterface_tinyRendererPlugin(struct b3PluginContext* context);
|
||||
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
};
|
||||
#endif
|
||||
|
||||
#endif//#define TEST_PLUGIN_H
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,65 @@
|
||||
#ifndef EGL_RENDERER_VISUAL_SHAPE_CONVERTER_H
|
||||
#define EGL_RENDERER_VISUAL_SHAPE_CONVERTER_H
|
||||
|
||||
#include "../../../Importers/ImportURDFDemo/UrdfRenderingInterface.h"
|
||||
|
||||
struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
|
||||
{
|
||||
int frame = 0;
|
||||
|
||||
struct TinyRendererVisualShapeConverterInternalData* m_data;
|
||||
|
||||
TinyRendererVisualShapeConverter();
|
||||
|
||||
virtual ~TinyRendererVisualShapeConverter();
|
||||
|
||||
virtual void convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfLink* linkPtr, const UrdfModel* model, int shapeUid, int objectIndex);
|
||||
|
||||
virtual int getNumVisualShapes(int bodyUniqueId);
|
||||
|
||||
virtual int getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData);
|
||||
|
||||
virtual void changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4]);
|
||||
|
||||
virtual void changeShapeTexture(int objectUniqueId, int linkIndex, int shapeIndex, int textureUniqueId);
|
||||
|
||||
virtual void removeVisualShape(int shapeUid);
|
||||
|
||||
virtual void setUpAxis(int axis);
|
||||
|
||||
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ);
|
||||
|
||||
virtual void clearBuffers(struct TGAColor& clearColor);
|
||||
|
||||
virtual void resetAll();
|
||||
|
||||
virtual void getWidthAndHeight(int& width, int& height);
|
||||
virtual void setWidthAndHeight(int width, int height);
|
||||
virtual void setLightDirection(float x, float y, float z);
|
||||
virtual void setLightColor(float x, float y, float z);
|
||||
virtual void setLightDistance(float dist);
|
||||
virtual void setLightAmbientCoeff(float ambientCoeff);
|
||||
virtual void setLightDiffuseCoeff(float diffuseCoeff);
|
||||
virtual void setLightSpecularCoeff(float specularCoeff);
|
||||
virtual void setShadow(bool hasShadow);
|
||||
virtual void setFlags(int flags);
|
||||
|
||||
virtual void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
|
||||
void copyCameraImageDataGL(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
|
||||
|
||||
virtual void render();
|
||||
virtual void render(const float viewMat[16], const float projMat[16]);
|
||||
|
||||
virtual int loadTextureFile(const char* filename);
|
||||
virtual int registerTexture(unsigned char* texels, int width, int height);
|
||||
|
||||
|
||||
|
||||
virtual void syncTransform(int shapeUid, const class btTransform& worldTransform, const class btVector3& localScaling);
|
||||
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
#endif //EGL_RENDERER_VISUAL_SHAPE_CONVERTER_H
|
||||
53
examples/SharedMemory/plugins/eglPlugin/premake4.lua
Normal file
53
examples/SharedMemory/plugins/eglPlugin/premake4.lua
Normal file
@@ -0,0 +1,53 @@
|
||||
|
||||
|
||||
project ("pybullet_eglRendererPlugin")
|
||||
language "C++"
|
||||
kind "SharedLib"
|
||||
|
||||
includedirs {".","../../../../src", "../../../../examples",
|
||||
"../../../ThirdPartyLibs"}
|
||||
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
|
||||
hasCL = findOpenCL("clew")
|
||||
|
||||
links{"BulletCollision", "Bullet3Common", "LinearMath"}
|
||||
|
||||
if os.is("MacOSX") then
|
||||
-- targetextension {"so"}
|
||||
links{"Cocoa.framework","Python"}
|
||||
end
|
||||
|
||||
|
||||
files {
|
||||
"eglRendererPlugin.cpp",
|
||||
"eglRendererPlugin.h",
|
||||
"TinyRendererVisualShapeConverter.cpp",
|
||||
"TinyRendererVisualShapeConverter.h",
|
||||
"../../../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
|
||||
"../../../Importers/ImportColladaDemo/LoadMeshFromCollada.h",
|
||||
"../../../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
|
||||
"../../../Importers/ImportMeshUtility/b3ImportMeshUtility.h",
|
||||
"../../../Importers/ImportObjDemo/LoadMeshFromObj.cpp",
|
||||
"../../../Importers/ImportObjDemo/LoadMeshFromObj.h",
|
||||
"../../../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
|
||||
"../../../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h",
|
||||
"../../../TinyRenderer/geometry.cpp",
|
||||
"../../../TinyRenderer/model.cpp",
|
||||
"../../../TinyRenderer/our_gl.cpp",
|
||||
"../../../TinyRenderer/tgaimage.cpp",
|
||||
"../../../TinyRenderer/TinyRenderer.cpp",
|
||||
"../../../ThirdPartyLibs/Wavefront/egl_obj_loader.cpp",
|
||||
"../../../ThirdPartyLibs/Wavefront/egl_obj_loader.h",
|
||||
"../../../ThirdPartyLibs/stb_image/stb_image.cpp",
|
||||
"../../../ThirdPartyLibs/stb_image/stb_image.h",
|
||||
"../../../ThirdPartyLibs/eglxml2/eglxml2.cpp",
|
||||
"../../../ThirdPartyLibs/eglxml2/eglxml2.h",
|
||||
"../../../OpenGLWindow/SimpleCamera.cpp",
|
||||
"../../../OpenGLWindow/SimpleCamera.h",
|
||||
"../../../Utils/b3Clock.cpp",
|
||||
"../../../Utils/b3Clock.h",
|
||||
"../../../Utils/b3ResourcePath.cpp",
|
||||
"../../../Utils/b3ResourcePath.h",
|
||||
}
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user