egl plugin working
This commit is contained in:
@@ -38,9 +38,8 @@
|
|||||||
|
|
||||||
#include "OpenGLInclude.h"
|
#include "OpenGLInclude.h"
|
||||||
|
|
||||||
#include "EGL/egl.h"
|
#include "glad/egl.h"
|
||||||
#include "EGL/eglext.h"
|
#include "glad/gl.h"
|
||||||
#include "GL/gl.h"
|
|
||||||
|
|
||||||
#include "EGLOpenGLWindow.h"
|
#include "EGLOpenGLWindow.h"
|
||||||
|
|
||||||
@@ -165,8 +164,8 @@ void EGLOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) {
|
|||||||
fprintf(stderr, "Unable to reload EGL.\n");
|
fprintf(stderr, "Unable to reload EGL.\n");
|
||||||
exit(EXIT_FAILURE);
|
exit(EXIT_FAILURE);
|
||||||
}
|
}
|
||||||
printf("Loaded EGL %d.%d after reload.\n", egl_version / 10,
|
printf("Loaded EGL %d.%d after reload.\n", GLAD_VERSION_MAJOR(egl_version),
|
||||||
egl_version % 10);
|
GLAD_VERSION_MINOR(egl_version));
|
||||||
|
|
||||||
|
|
||||||
m_data->success = eglBindAPI(EGL_OPENGL_API);
|
m_data->success = eglBindAPI(EGL_OPENGL_API);
|
||||||
|
|||||||
@@ -1542,8 +1542,9 @@ void GLInstancingRenderer::updateCamera(int upAxis)
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef STB_AGAIN // first defn in examples/OpenGLWindow/opengl_fontstashcallbacks.cpp
|
||||||
//#define STB_IMAGE_WRITE_IMPLEMENTATION
|
#define STB_IMAGE_WRITE_IMPLEMENTATION
|
||||||
|
#endif //STB_AGAIN
|
||||||
#include "stb_image/stb_image_write.h"
|
#include "stb_image/stb_image_write.h"
|
||||||
void writeTextureToPng(int textureWidth, int textureHeight, const char* fileName, int numComponents)
|
void writeTextureToPng(int textureWidth, int textureHeight, const char* fileName, int numComponents)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -1,13 +1,21 @@
|
|||||||
import os
|
import os
|
||||||
|
import sys
|
||||||
import time
|
import time
|
||||||
import subprocess
|
import subprocess
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
|
from pdb import set_trace
|
||||||
|
import matplotlib.pyplot as plt
|
||||||
#subprocess.call(["hardening-check", p.__file__])
|
#subprocess.call(["hardening-check", p.__file__])
|
||||||
|
|
||||||
p.connect(p.DIRECT)
|
p.connect(p.DIRECT)
|
||||||
|
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "debugTimings")
|
||||||
|
|
||||||
plugin_fn = '/home/argusm/lang/bullet3/build/lib.linux-x86_64-3.5/eglRenderer.cpython-35m-x86_64-linux-gnu.so'
|
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")
|
plugin = p.loadPlugin(plugin_fn,"_tinyRendererPlugin")
|
||||||
|
if plugin < 0:
|
||||||
|
print("\nPlugin Failed to load!\n")
|
||||||
|
sys.exit()
|
||||||
|
|
||||||
print("plugin =",plugin)
|
print("plugin =",plugin)
|
||||||
|
|
||||||
path = '/home/argusm/lang/bullet3/examples/pybullet/gym/pybullet_data/r2d2.urdf'
|
path = '/home/argusm/lang/bullet3/examples/pybullet/gym/pybullet_data/r2d2.urdf'
|
||||||
@@ -16,10 +24,19 @@ path = '/home/argusm/lang/gym-grasping/gym_grasping/robots/models/kuka_iiwa/kuka
|
|||||||
p.loadSDF(path)
|
p.loadSDF(path)
|
||||||
|
|
||||||
start = time.time()
|
start = time.time()
|
||||||
for i in range(2000):
|
|
||||||
p.getCameraImage(80,80)
|
plot = False
|
||||||
if i % 100 == 0 and i > 0:
|
try:
|
||||||
print("FPS",100/(time.time()-start))
|
for i in range(10):
|
||||||
|
hight, width, img_arr, deept_arr, obj_arr = p.getCameraImage(80,80)
|
||||||
|
if plot:
|
||||||
|
plt.imshow(img_arr[:,:,:3])
|
||||||
|
plt.show()
|
||||||
|
if i % 100 == 0 and i > 0:
|
||||||
|
print("FPS",100/(time.time()-start))
|
||||||
start = time.time()
|
start = time.time()
|
||||||
|
finally:
|
||||||
|
p.stopStateLogging(logId)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -16,6 +16,7 @@ subject to the following restrictions:
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#include "../Importers/ImportURDFDemo/URDFImporterInterface.h"
|
#include "../Importers/ImportURDFDemo/URDFImporterInterface.h"
|
||||||
#include "btBulletCollisionCommon.h"
|
#include "btBulletCollisionCommon.h"
|
||||||
#include "../Importers/ImportObjDemo/LoadMeshFromObj.h"
|
#include "../Importers/ImportObjDemo/LoadMeshFromObj.h"
|
||||||
@@ -77,6 +78,9 @@ struct TinyRendererVisualShapeConverterInternalData
|
|||||||
{
|
{
|
||||||
class CommonWindowInterface* m_window;
|
class CommonWindowInterface* m_window;
|
||||||
class GLInstancingRenderer* m_instancingRenderer;
|
class GLInstancingRenderer* m_instancingRenderer;
|
||||||
|
btAlignedObjectArray<unsigned char> m_rgbaPixelBuffer1;
|
||||||
|
btAlignedObjectArray<float> m_depthBuffer1;
|
||||||
|
|
||||||
btHashMap<btHashInt,TinyRendererObjectArray*> m_swRenderInstances;
|
btHashMap<btHashInt,TinyRendererObjectArray*> m_swRenderInstances;
|
||||||
|
|
||||||
btAlignedObjectArray<b3VisualShapeData> m_visualShapes;
|
btAlignedObjectArray<b3VisualShapeData> m_visualShapes;
|
||||||
@@ -161,6 +165,8 @@ struct TinyRendererVisualShapeConverterInternalData
|
|||||||
m_instancingRenderer->init();
|
m_instancingRenderer->init();
|
||||||
m_instancingRenderer->resize(m_swWidth,m_swHeight);
|
m_instancingRenderer->resize(m_swWidth,m_swHeight);
|
||||||
m_instancingRenderer->InitShaders();
|
m_instancingRenderer->InitShaders();
|
||||||
|
m_instancingRenderer->setActiveCamera(&m_camera);
|
||||||
|
m_instancingRenderer->setLightPosition(m_lightDirection);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
@@ -492,13 +498,13 @@ void convertURDFToVisualShape(const UrdfShape* visual, const char* urdfPathPrefi
|
|||||||
break;
|
break;
|
||||||
} // case mesh
|
} // case mesh
|
||||||
|
|
||||||
case URDF_GEOM_PLANE:
|
case URDF_GEOM_PLANE:
|
||||||
// TODO: plane in tiny renderer
|
// TODO: plane in tiny renderer
|
||||||
// TODO: export visualShapeOut for external render
|
// TODO: export visualShapeOut for external render
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
b3Warning("TinyRenderer: unknown visual geometry type %i\n", visual->m_geometry.m_type);
|
b3Warning("TinyRenderer: unknown visual geometry type %i\n", visual->m_geometry.m_type);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -596,7 +602,9 @@ static btVector4 sColors[4] =
|
|||||||
//btVector4(1,1,0,1),
|
//btVector4(1,1,0,1),
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// 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 TinyRendererVisualShapeConverter::convertVisualShapes(
|
||||||
int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame,
|
int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame,
|
||||||
const UrdfLink* linkPtr, const UrdfModel* model,
|
const UrdfLink* linkPtr, const UrdfModel* model,
|
||||||
@@ -608,8 +616,6 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
|||||||
bool useVisual;
|
bool useVisual;
|
||||||
int cnt = 0;
|
int cnt = 0;
|
||||||
|
|
||||||
std::cout << "mvp " << linkPtr->m_visualArray.size() << std::endl;
|
|
||||||
|
|
||||||
if (linkPtr->m_visualArray.size() > 0)
|
if (linkPtr->m_visualArray.size() > 0)
|
||||||
{
|
{
|
||||||
useVisual = true;
|
useVisual = true;
|
||||||
@@ -636,6 +642,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
|||||||
} else {
|
} else {
|
||||||
vis = &linkPtr->m_collisionArray[v1];
|
vis = &linkPtr->m_collisionArray[v1];
|
||||||
}
|
}
|
||||||
|
// see note at function header
|
||||||
btTransform childTrans = vis->m_linkLocalFrame;
|
btTransform childTrans = vis->m_linkLocalFrame;
|
||||||
|
|
||||||
int colorIndex = linkIndex;//colObj? colObj->getBroadphaseHandle()->getUid() & 3 : 0;
|
int colorIndex = linkIndex;//colObj? colObj->getBroadphaseHandle()->getUid() & 3 : 0;
|
||||||
@@ -682,7 +689,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
|||||||
{
|
{
|
||||||
|
|
||||||
if (vis && vis->m_geometry.m_hasLocalMaterial)
|
if (vis && vis->m_geometry.m_hasLocalMaterial)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < 4; i++)
|
for (int i = 0; i < 4; i++)
|
||||||
{
|
{
|
||||||
rgbaColor[i] = vis->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[i];
|
rgbaColor[i] = vis->m_geometry.m_localMaterial.m_matColor.m_rgbaColor[i];
|
||||||
@@ -690,7 +697,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
TinyRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[collisionObjectUniqueId];
|
TinyRendererObjectArray** visualsPtr = m_data->m_swRenderInstances[collisionObjectUniqueId];
|
||||||
if (visualsPtr==0)
|
if (visualsPtr==0)
|
||||||
{
|
{
|
||||||
m_data->m_swRenderInstances.insert(collisionObjectUniqueId, new TinyRendererObjectArray);
|
m_data->m_swRenderInstances.insert(collisionObjectUniqueId, new TinyRendererObjectArray);
|
||||||
@@ -728,7 +735,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
|||||||
unsigned char* textureImage1=0;
|
unsigned char* textureImage1=0;
|
||||||
int textureWidth=0;
|
int textureWidth=0;
|
||||||
int textureHeight=0;
|
int textureHeight=0;
|
||||||
bool isCached = false;
|
bool isCached = false;
|
||||||
if (textures.size())
|
if (textures.size())
|
||||||
{
|
{
|
||||||
textureImage1 = textures[0].textureData1;
|
textureImage1 = textures[0].textureData1;
|
||||||
@@ -745,14 +752,16 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(
|
|||||||
}
|
}
|
||||||
visuals->m_renderObjects.push_back(tinyObj);
|
visuals->m_renderObjects.push_back(tinyObj);
|
||||||
|
|
||||||
|
{
|
||||||
|
B3_PROFILE("m_instancingRenderer register");
|
||||||
|
|
||||||
// register mesh to m_instancingRenderer too.
|
// register mesh to m_instancingRenderer too.
|
||||||
int textureIndex = m_data->m_instancingRenderer->registerTexture(textureImage1, textureWidth, textureHeight);
|
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(),textureIndex);
|
||||||
//m_data->m_instancingRenderer->registerGraphicsInstance(shapeIndex, &visualShape.m_localVisualFrame[0], &visualShape.m_localVisualFrame[3], &visualShape.m_rgbaColor[0]);
|
btVector3 scaling(1,1,1);
|
||||||
|
m_data->m_instancingRenderer->registerGraphicsInstance(shapeIndex, &visualShape.m_localVisualFrame[0], &visualShape.m_localVisualFrame[3], &visualShape.m_rgbaColor[0],scaling);
|
||||||
|
m_data->m_instancingRenderer->writeTransforms();
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
for (int i=0;i<textures.size();i++)
|
for (int i=0;i<textures.size();i++)
|
||||||
{
|
{
|
||||||
@@ -826,7 +835,7 @@ int TinyRendererVisualShapeConverter::getVisualShapesData(int bodyUniqueId, int
|
|||||||
|
|
||||||
void TinyRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4])
|
void TinyRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int linkIndex, int shapeIndex, const double rgbaColor[4])
|
||||||
{
|
{
|
||||||
int start = -1;
|
//int start = -1;
|
||||||
for (int i = 0; i < m_data->m_visualShapes.size(); i++)
|
for (int i = 0; i < m_data->m_visualShapes.size(); i++)
|
||||||
{
|
{
|
||||||
if (m_data->m_visualShapes[i].m_objectUniqueId == bodyUniqueId && m_data->m_visualShapes[i].m_linkIndex == linkIndex)
|
if (m_data->m_visualShapes[i].m_objectUniqueId == bodyUniqueId && m_data->m_visualShapes[i].m_linkIndex == linkIndex)
|
||||||
@@ -891,7 +900,7 @@ void TinyRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor)
|
|||||||
m_data->m_segmentationMaskBuffer[x+y*m_data->m_swWidth] = -1;
|
m_data->m_segmentationMaskBuffer[x+y*m_data->m_swWidth] = -1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TinyRendererVisualShapeConverter::render()
|
void TinyRendererVisualShapeConverter::render()
|
||||||
@@ -903,10 +912,9 @@ void TinyRendererVisualShapeConverter::render()
|
|||||||
m_data->m_camera.getCameraProjectionMatrix(projMat);
|
m_data->m_camera.getCameraProjectionMatrix(projMat);
|
||||||
m_data->m_camera.getCameraViewMatrix(viewMat);
|
m_data->m_camera.getCameraViewMatrix(viewMat);
|
||||||
|
|
||||||
render(viewMat,projMat);
|
B3_PROFILE("m_instancingRenderer render");
|
||||||
|
|
||||||
m_data->m_instancingRenderer->renderScene();
|
m_data->m_instancingRenderer->renderScene();
|
||||||
b3Warning("m_instancingRendere->renderScene");
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -924,174 +932,10 @@ void TinyRendererVisualShapeConverter::syncTransform(int collisionObjectUniqueId
|
|||||||
|
|
||||||
void TinyRendererVisualShapeConverter::render(const float viewMat[16], const float projMat[16])
|
void TinyRendererVisualShapeConverter::render(const float viewMat[16], const float projMat[16])
|
||||||
{
|
{
|
||||||
//clear the color buffer
|
// This code is very similar to that of
|
||||||
TGAColor clearColor;
|
// PhysicsServerCommandProcessor::processRequestCameraImageCommand
|
||||||
clearColor.bgra[0] = 255;
|
// maybe code from there should be moved.
|
||||||
clearColor.bgra[1] = 255;
|
b3Error("not implemeted, use render()");
|
||||||
clearColor.bgra[2] = 255;
|
|
||||||
clearColor.bgra[3] = 255;
|
|
||||||
|
|
||||||
float near = projMat[14]/(projMat[10]-1);
|
|
||||||
float far = projMat[14]/(projMat[10]+1);
|
|
||||||
|
|
||||||
m_data->m_camera.setCameraFrustumNear( near);
|
|
||||||
m_data->m_camera.setCameraFrustumFar(far);
|
|
||||||
|
|
||||||
clearBuffers(clearColor);
|
|
||||||
|
|
||||||
ATTRIBUTE_ALIGNED16(btScalar modelMat[16]);
|
|
||||||
|
|
||||||
|
|
||||||
btVector3 lightDirWorld(-5,200,-40);
|
|
||||||
if (m_data->m_hasLightDirection)
|
|
||||||
{
|
|
||||||
lightDirWorld = m_data->m_lightDirection;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
switch (m_data->m_upAxis)
|
|
||||||
{
|
|
||||||
case 1:
|
|
||||||
lightDirWorld = btVector3(-50.f, 100, 30);
|
|
||||||
break;
|
|
||||||
case 2:
|
|
||||||
lightDirWorld = btVector3(-50.f, 30, 100);
|
|
||||||
break;
|
|
||||||
default: {}
|
|
||||||
};
|
|
||||||
}
|
|
||||||
|
|
||||||
lightDirWorld.normalize();
|
|
||||||
|
|
||||||
btVector3 lightColor(1.0,1.0,1.0);
|
|
||||||
if (m_data->m_hasLightColor)
|
|
||||||
{
|
|
||||||
lightColor = m_data->m_lightColor;
|
|
||||||
}
|
|
||||||
|
|
||||||
float lightDistance = 2.0;
|
|
||||||
if (m_data->m_hasLightDistance)
|
|
||||||
{
|
|
||||||
lightDistance = m_data->m_lightDistance;
|
|
||||||
}
|
|
||||||
|
|
||||||
float lightAmbientCoeff = 0.6;
|
|
||||||
if (m_data->m_hasLightAmbientCoeff)
|
|
||||||
{
|
|
||||||
lightAmbientCoeff = m_data->m_lightAmbientCoeff;
|
|
||||||
}
|
|
||||||
|
|
||||||
float lightDiffuseCoeff = 0.35;
|
|
||||||
if (m_data->m_hasLightDiffuseCoeff)
|
|
||||||
{
|
|
||||||
lightDiffuseCoeff = m_data->m_lightDiffuseCoeff;
|
|
||||||
}
|
|
||||||
|
|
||||||
float lightSpecularCoeff = 0.05;
|
|
||||||
if (m_data->m_hasLightSpecularCoeff)
|
|
||||||
{
|
|
||||||
lightSpecularCoeff = m_data->m_lightSpecularCoeff;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (m_data->m_hasShadow)
|
|
||||||
{
|
|
||||||
for (int n=0;n<m_data->m_swRenderInstances.size();n++)
|
|
||||||
{
|
|
||||||
TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(n);
|
|
||||||
if (0==visualArrayPtr)
|
|
||||||
continue;//can this ever happen?
|
|
||||||
TinyRendererObjectArray* visualArray = *visualArrayPtr;
|
|
||||||
|
|
||||||
for (int v=0;v<visualArray->m_renderObjects.size();v++)
|
|
||||||
{
|
|
||||||
|
|
||||||
TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v];
|
|
||||||
|
|
||||||
|
|
||||||
//sync the object transform
|
|
||||||
const btTransform& tr = visualArray->m_worldTransform;
|
|
||||||
tr.getOpenGLMatrix(modelMat);
|
|
||||||
|
|
||||||
for (int i=0;i<4;i++)
|
|
||||||
{
|
|
||||||
for (int j=0;j<4;j++)
|
|
||||||
{
|
|
||||||
|
|
||||||
renderObj->m_projectionMatrix[i][j] = projMat[i+4*j];
|
|
||||||
renderObj->m_modelMatrix[i][j] = modelMat[i+4*j];
|
|
||||||
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
renderObj->m_localScaling = visualArray->m_localScaling;
|
|
||||||
renderObj->m_lightDirWorld = lightDirWorld;
|
|
||||||
renderObj->m_lightColor = lightColor;
|
|
||||||
renderObj->m_lightDistance = lightDistance;
|
|
||||||
renderObj->m_lightAmbientCoeff = lightAmbientCoeff;
|
|
||||||
renderObj->m_lightDiffuseCoeff = lightDiffuseCoeff;
|
|
||||||
renderObj->m_lightSpecularCoeff = lightSpecularCoeff;
|
|
||||||
TinyRenderer::renderObjectDepth(*renderObj);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
for (int n=0;n<m_data->m_swRenderInstances.size();n++)
|
|
||||||
{
|
|
||||||
TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(n);
|
|
||||||
if (0==visualArrayPtr)
|
|
||||||
continue;//can this ever happen?
|
|
||||||
TinyRendererObjectArray* visualArray = *visualArrayPtr;
|
|
||||||
|
|
||||||
|
|
||||||
for (int v=0;v<visualArray->m_renderObjects.size();v++)
|
|
||||||
{
|
|
||||||
|
|
||||||
TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v];
|
|
||||||
|
|
||||||
|
|
||||||
//sync the object transform
|
|
||||||
const btTransform& tr = visualArray->m_worldTransform;
|
|
||||||
tr.getOpenGLMatrix(modelMat);
|
|
||||||
|
|
||||||
for (int i=0;i<4;i++)
|
|
||||||
{
|
|
||||||
for (int j=0;j<4;j++)
|
|
||||||
{
|
|
||||||
|
|
||||||
renderObj->m_projectionMatrix[i][j] = projMat[i+4*j];
|
|
||||||
renderObj->m_modelMatrix[i][j] = modelMat[i+4*j];
|
|
||||||
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
renderObj->m_localScaling = visualArray->m_localScaling;
|
|
||||||
renderObj->m_lightDirWorld = lightDirWorld;
|
|
||||||
renderObj->m_lightColor = lightColor;
|
|
||||||
renderObj->m_lightDistance = lightDistance;
|
|
||||||
renderObj->m_lightAmbientCoeff = lightAmbientCoeff;
|
|
||||||
renderObj->m_lightDiffuseCoeff = lightDiffuseCoeff;
|
|
||||||
renderObj->m_lightSpecularCoeff = lightSpecularCoeff;
|
|
||||||
TinyRenderer::renderObject(*renderObj);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
//printf("write tga \n");
|
|
||||||
//m_data->m_rgbColorBuffer.write_tga_file("camera.tga");
|
|
||||||
// printf("flipped!\n");
|
|
||||||
m_data->m_rgbColorBuffer.flip_vertically();
|
|
||||||
|
|
||||||
//flip z-buffer and segmentation Buffer
|
|
||||||
{
|
|
||||||
int half = m_data->m_swHeight>>1;
|
|
||||||
for (int j=0; j<half; j++)
|
|
||||||
{
|
|
||||||
unsigned long l1 = j*m_data->m_swWidth;
|
|
||||||
unsigned long l2 = (m_data->m_swHeight-1-j)*m_data->m_swWidth;
|
|
||||||
for (int i=0;i<m_data->m_swWidth;i++)
|
|
||||||
{
|
|
||||||
btSwap(m_data->m_depthBuffer[l1+i],m_data->m_depthBuffer[l2+i]);
|
|
||||||
btSwap(m_data->m_shadowBuffer[l1+i],m_data->m_shadowBuffer[l2+i]);
|
|
||||||
btSwap(m_data->m_segmentationMaskBuffer[l1+i],m_data->m_segmentationMaskBuffer[l2+i]);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TinyRendererVisualShapeConverter::getWidthAndHeight(int& width, int& height)
|
void TinyRendererVisualShapeConverter::getWidthAndHeight(int& width, int& height)
|
||||||
@@ -1114,98 +958,130 @@ void TinyRendererVisualShapeConverter::setWidthAndHeight(int width, int height)
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
//copied from OpenGLGuiHelper.cpp
|
||||||
float* depthBuffer, int depthBufferSizeInPixels,
|
void TinyRendererVisualShapeConverter::copyCameraImageDataGL(
|
||||||
int* segmentationMaskBuffer, int segmentationMaskSizeInPixels,
|
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
||||||
int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied)
|
float* depthBuffer, int depthBufferSizeInPixels,
|
||||||
{
|
int* segmentationMaskBuffer, int segmentationMaskSizeInPixels,
|
||||||
int w = m_data->m_rgbColorBuffer.get_width();
|
int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied) {
|
||||||
int h = m_data->m_rgbColorBuffer.get_height();
|
|
||||||
|
int sourceWidth = m_data->m_window->getWidth()*m_data->m_window->getRetinaScale();
|
||||||
|
int sourceHeight = m_data->m_window->getHeight()*m_data->m_window->getRetinaScale();
|
||||||
|
|
||||||
if (numPixelsCopied)
|
if (numPixelsCopied)
|
||||||
*numPixelsCopied = 0;
|
*numPixelsCopied = 0;
|
||||||
|
|
||||||
if (widthPtr)
|
int numTotalPixels = (*widthPtr)*(*heightPtr);
|
||||||
*widthPtr = w;
|
|
||||||
|
|
||||||
if (heightPtr)
|
|
||||||
*heightPtr = h;
|
|
||||||
|
|
||||||
int numTotalPixels = w*h;
|
|
||||||
int numRemainingPixels = numTotalPixels - startPixelIndex;
|
int numRemainingPixels = numTotalPixels - startPixelIndex;
|
||||||
int numBytesPerPixel = 4;//RGBA
|
int numBytesPerPixel = 4;//RGBA
|
||||||
int numRequestedPixels = btMin(rgbaBufferSizeInPixels,numRemainingPixels);
|
int numRequestedPixels = btMin(rgbaBufferSizeInPixels,numRemainingPixels);
|
||||||
if (numRequestedPixels)
|
if (numRequestedPixels)
|
||||||
{
|
{
|
||||||
for (int i=0;i<numRequestedPixels;i++)
|
if (startPixelIndex==0)
|
||||||
{
|
{
|
||||||
if (depthBuffer)
|
{
|
||||||
{
|
BT_PROFILE("copy pixels");
|
||||||
float farPlane = m_data->m_camera.getCameraFrustumFar();
|
btAlignedObjectArray<unsigned char> sourceRgbaPixelBuffer;
|
||||||
float nearPlane = m_data->m_camera.getCameraFrustumNear();
|
btAlignedObjectArray<float> sourceDepthBuffer;
|
||||||
|
//copy the image into our local cache
|
||||||
// TinyRenderer returns clip coordinates, transform to eye coordinates first
|
sourceRgbaPixelBuffer.resize(sourceWidth*sourceHeight*numBytesPerPixel);
|
||||||
float z_c = -m_data->m_depthBuffer[i+startPixelIndex];
|
sourceDepthBuffer.resize(sourceWidth*sourceHeight);
|
||||||
// float distance = (farPlane - nearPlane) / (farPlane + nearPlane) * (z_c + 2. * farPlane * nearPlane / (farPlane - nearPlane));
|
{
|
||||||
|
BT_PROFILE("getScreenPixels");
|
||||||
// The depth buffer value is between 0 and 1
|
int rgbaBufferSizeInPixels = sourceRgbaPixelBuffer.size();
|
||||||
// float a = farPlane / (farPlane - nearPlane);
|
int depthBufferSizeInPixels = sourceDepthBuffer.size();
|
||||||
// float b = farPlane * nearPlane / (nearPlane - farPlane);
|
// Copied from SimpleOpenGL3App::getScreenPixels
|
||||||
// depthBuffer[i] = a + b / distance;
|
b3Assert((sourceWidth*sourceHeight*4) == rgbaBufferSizeInPixels);
|
||||||
|
//glClear(GL_COLOR_BUFFER_BIT);
|
||||||
|
b3Warning("EGL\n");
|
||||||
|
if ((sourceWidth*sourceHeight*4) == rgbaBufferSizeInPixels) // remove this if
|
||||||
|
{
|
||||||
|
glReadPixels(0,0,sourceWidth, sourceHeight, GL_RGBA, GL_UNSIGNED_BYTE, &(sourceRgbaPixelBuffer[0]));
|
||||||
|
int glstat;
|
||||||
|
glstat = glGetError();
|
||||||
|
b3Assert(glstat==GL_NO_ERROR);
|
||||||
|
}
|
||||||
|
if ((sourceWidth*sourceHeight*sizeof(float)) == depthBufferSizeInPixels)
|
||||||
|
{
|
||||||
|
glReadPixels(0,0,sourceWidth, sourceHeight, GL_DEPTH_COMPONENT, GL_FLOAT, &(sourceDepthBuffer[0]));
|
||||||
|
int glstat;
|
||||||
|
glstat = glGetError();
|
||||||
|
b3Assert(glstat==GL_NO_ERROR);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Simply the above expressions
|
m_data->m_rgbaPixelBuffer1.resize((*widthPtr)*(*heightPtr)*numBytesPerPixel);
|
||||||
depthBuffer[i] = farPlane * (nearPlane + z_c) / (2. * farPlane * nearPlane + farPlane * z_c - nearPlane * z_c);
|
m_data->m_depthBuffer1.resize((*widthPtr)*(*heightPtr));
|
||||||
}
|
//rescale and flip
|
||||||
if (segmentationMaskBuffer)
|
{
|
||||||
{
|
BT_PROFILE("resize and flip");
|
||||||
int segMask = m_data->m_segmentationMaskBuffer[i + startPixelIndex];
|
for (int j=0;j<*heightPtr;j++)
|
||||||
if ((m_data->m_flags & ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX)==0)
|
{
|
||||||
{
|
for (int i=0;i<*widthPtr;i++)
|
||||||
//if we don't explicitly request link index, clear it out
|
{
|
||||||
//object index are the lower 24bits
|
int xIndex = int(float(i)*(float(sourceWidth)/float(*widthPtr)));
|
||||||
if (segMask >= 0)
|
int yIndex = int(float(*heightPtr-1-j)*(float(sourceHeight)/float(*heightPtr)));
|
||||||
{
|
btClamp(xIndex,0,sourceWidth);
|
||||||
segMask &= ((1 << 24) - 1);
|
btClamp(yIndex,0,sourceHeight);
|
||||||
}
|
int bytesPerPixel = 4; //RGBA
|
||||||
}
|
|
||||||
segmentationMaskBuffer[i] = segMask;
|
int sourcePixelIndex = (xIndex+yIndex*sourceWidth)*bytesPerPixel;
|
||||||
}
|
int sourceDepthIndex = xIndex+yIndex*sourceWidth;
|
||||||
|
#define COPY4PIXELS 1
|
||||||
if (pixelsRGBA)
|
#ifdef COPY4PIXELS
|
||||||
{
|
int* dst = (int*)&m_data->m_rgbaPixelBuffer1[(i+j*(*widthPtr))*4+0];
|
||||||
pixelsRGBA[i*numBytesPerPixel] = m_data->m_rgbColorBuffer.buffer()[(i+startPixelIndex)*3+0];
|
int* src = (int*)&sourceRgbaPixelBuffer[sourcePixelIndex+0];
|
||||||
pixelsRGBA[i*numBytesPerPixel+1] = m_data->m_rgbColorBuffer.buffer()[(i+startPixelIndex)*3+1];
|
*dst = *src;
|
||||||
pixelsRGBA[i*numBytesPerPixel+2] = m_data->m_rgbColorBuffer.buffer()[(i+startPixelIndex)*3+2];
|
|
||||||
pixelsRGBA[i*numBytesPerPixel+3] = 255;
|
#else
|
||||||
|
m_data->m_rgbaPixelBuffer1[(i+j*widthPtr)*4+0] = sourceRgbaPixelBuffer[sourcePixelIndex+0];
|
||||||
|
m_data->m_rgbaPixelBuffer1[(i+j*widthPtr)*4+1] = sourceRgbaPixelBuffer[sourcePixelIndex+1];
|
||||||
|
m_data->m_rgbaPixelBuffer1[(i+j*widthPtr)*4+2] = sourceRgbaPixelBuffer[sourcePixelIndex+2];
|
||||||
|
m_data->m_rgbaPixelBuffer1[(i+j*widthPtr)*4+3] = 255;
|
||||||
|
#endif
|
||||||
|
if (depthBuffer)
|
||||||
|
{
|
||||||
|
m_data->m_depthBuffer1[i+j*(*widthPtr)] = sourceDepthBuffer[sourceDepthIndex];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (pixelsRGBA)
|
||||||
|
{
|
||||||
|
BT_PROFILE("copy rgba pixels");
|
||||||
|
for (int i=0;i<numRequestedPixels*numBytesPerPixel;i++)
|
||||||
|
{
|
||||||
|
pixelsRGBA[i] = m_data->m_rgbaPixelBuffer1[i+startPixelIndex*numBytesPerPixel];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (depthBuffer)
|
||||||
|
{
|
||||||
|
BT_PROFILE("copy depth buffer pixels");
|
||||||
|
for (int i=0;i<numRequestedPixels;i++)
|
||||||
|
{
|
||||||
|
depthBuffer[i] = m_data->m_depthBuffer1[i+startPixelIndex];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (numPixelsCopied)
|
if (numPixelsCopied)
|
||||||
|
{
|
||||||
*numPixelsCopied = numRequestedPixels;
|
*numPixelsCopied = numRequestedPixels;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Copied from SimpleOpenGL3App::getScreenPixels
|
void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
||||||
int width = m_data->m_instancingRenderer->getScreenWidth();
|
float* depthBuffer, int depthBufferSizeInPixels,
|
||||||
int height =m_data->m_instancingRenderer->getScreenHeight();
|
int* segmentationMaskBuffer, int segmentationMaskSizeInPixels,
|
||||||
if ((width*height*4) == rgbaBufferSizeInPixels)
|
int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied)
|
||||||
{
|
{
|
||||||
glReadPixels(0,0,width, height, GL_RGBA, GL_UNSIGNED_BYTE, pixelsRGBA);
|
B3_PROFILE("copyCameraImageDataGL");
|
||||||
int glstat;
|
copyCameraImageDataGL(pixelsRGBA, rgbaBufferSizeInPixels,
|
||||||
glstat = glGetError();
|
depthBuffer, depthBufferSizeInPixels,
|
||||||
b3Assert(glstat==GL_NO_ERROR);
|
segmentationMaskBuffer, segmentationMaskSizeInPixels,
|
||||||
}
|
startPixelIndex, widthPtr, heightPtr, numPixelsCopied);
|
||||||
if ((width*height*sizeof(float)) == depthBufferSizeInPixels)
|
|
||||||
{
|
|
||||||
glReadPixels(0,0,width, height, GL_DEPTH_COMPONENT, GL_FLOAT, depthBuffer);
|
|
||||||
int glstat;
|
|
||||||
glstat = glGetError();
|
|
||||||
b3Assert(glstat==GL_NO_ERROR);
|
|
||||||
}
|
|
||||||
b3Warning("instancingRenderer getScreenPixels");
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TinyRendererVisualShapeConverter::removeVisualShape(int collisionObjectUniqueId)
|
void TinyRendererVisualShapeConverter::removeVisualShape(int collisionObjectUniqueId)
|
||||||
|
|||||||
@@ -5,7 +5,8 @@
|
|||||||
|
|
||||||
struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
|
struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
|
||||||
{
|
{
|
||||||
|
int frame = 0;
|
||||||
|
|
||||||
struct TinyRendererVisualShapeConverterInternalData* m_data;
|
struct TinyRendererVisualShapeConverterInternalData* m_data;
|
||||||
|
|
||||||
TinyRendererVisualShapeConverter();
|
TinyRendererVisualShapeConverter();
|
||||||
@@ -44,7 +45,8 @@ struct TinyRendererVisualShapeConverter : public UrdfRenderingInterface
|
|||||||
virtual void setFlags(int flags);
|
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);
|
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();
|
||||||
virtual void render(const float viewMat[16], const float projMat[16]);
|
virtual void render(const float viewMat[16], const float projMat[16]);
|
||||||
|
|
||||||
|
|||||||
12
setup.py
12
setup.py
@@ -493,17 +493,19 @@ egl_renderer_sources = \
|
|||||||
+["src/LinearMath/btConvexHull.cpp"]\
|
+["src/LinearMath/btConvexHull.cpp"]\
|
||||||
+["src/LinearMath/btConvexHullComputer.cpp"]\
|
+["src/LinearMath/btConvexHullComputer.cpp"]\
|
||||||
+["src/Bullet3Common/b3AlignedAllocator.cpp"] \
|
+["src/Bullet3Common/b3AlignedAllocator.cpp"] \
|
||||||
+["examples/ThirdPartyLibs/glad/glad.c"]\
|
+["examples/ThirdPartyLibs/glad/gl.c"]\
|
||||||
+["examples/ThirdPartyLibs/glad/glad_glx.c"] \
|
+['examples/ThirdPartyLibs/glad/egl.c'] \
|
||||||
|
+["examples/ThirdPartyLibs/glad/glx_dyn.c"] \
|
||||||
+["examples/OpenGLWindow/GLInstancingRenderer.cpp"]\
|
+["examples/OpenGLWindow/GLInstancingRenderer.cpp"]\
|
||||||
+["examples/OpenGLWindow/EGLOpenGLWindow.cpp"]\
|
+["examples/OpenGLWindow/EGLOpenGLWindow.cpp"]\
|
||||||
+["examples/OpenGLWindow/GLRenderToTexture.cpp"]\
|
+["examples/OpenGLWindow/GLRenderToTexture.cpp"] \
|
||||||
|
+["examples/OpenGLWindow/LoadShader.cpp"] \
|
||||||
|
+["src/LinearMath/btQuickprof.cpp"] \
|
||||||
|
|
||||||
eglRender = Extension("eglRenderer",
|
eglRender = Extension("eglRenderer",
|
||||||
sources = egl_renderer_sources,
|
sources = egl_renderer_sources,
|
||||||
libraries = libraries,
|
libraries = libraries,
|
||||||
extra_compile_args=(CXX_FLAGS+'-DBT_USE_EGL ').split(),
|
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"]
|
include_dirs = include_dirs + ["src","examples/ThirdPartyLibs","examples/ThirdPartyLibs/glad", "examples/ThirdPartyLibs/enet/include","examples/ThirdPartyLibs/clsocket/src"]
|
||||||
)
|
)
|
||||||
setup(
|
setup(
|
||||||
|
|||||||
Reference in New Issue
Block a user