From 29809a4471c73324642ae050cd54c76e0f0f9c5d Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Wed, 23 Nov 2016 13:00:26 -0800 Subject: [PATCH] Render depth buffer. --- .../SharedMemory/PhysicsClientExample.cpp | 20 +--- examples/SharedMemory/SharedMemoryPublic.h | 1 - examples/TinyRenderer/TinyRenderer.cpp | 91 +++++++++++++------ examples/TinyRenderer/our_gl.cpp | 20 +++- 4 files changed, 80 insertions(+), 52 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index b1bac89d0..3b60d3ce7 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -89,10 +89,10 @@ protected: virtual void resetCamera() { - float dist = 1; + float dist = 1.233281; float pitch = 193; float yaw = 25; - float targetPos[3]={0.008655,0.001998,0.679456};//-3,2.8,-2.5}; + float targetPos[3]={0.103042,-0.469102,0.631005};//-3,2.8,-2.5}; m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); } @@ -481,21 +481,6 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) } break; } - case CMD_UPDATE_LIGHT: - { - b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); - float viewMatrix[16]; - float projectionMatrix[16]; - m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); - m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); - - b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix); - b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight); - float lightDir[3] = {0.0,0.1,2.0}; - b3RequestCameraImageSetLightDirection(commandHandle, lightDir); - b3SubmitClientCommand(m_physicsClientHandle, commandHandle); - break; - } default: { b3Error("Unknown buttonId"); @@ -572,7 +557,6 @@ void PhysicsClientExample::createButtons() createButton("Load SDF",CMD_LOAD_SDF, isTrigger); createButton("Save World",CMD_SAVE_WORLD, isTrigger); createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger); - createButton("Update Light",CMD_UPDATE_LIGHT,isTrigger); createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger); createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger); createButton("Get Visual Shape Info",CMD_REQUEST_VISUAL_SHAPE_INFO, isTrigger); diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 557bdba52..d6a8e246a 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -38,7 +38,6 @@ enum EnumSharedMemoryClientCommand CMD_REQUEST_AABB_OVERLAP, CMD_SAVE_WORLD, CMD_REQUEST_VISUAL_SHAPE_INFO, - CMD_UPDATE_LIGHT, CMD_UPDATE_VISUAL_SHAPE, CMD_LOAD_TEXTURE, CMD_USER_DEBUG_DRAW, diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 55241670b..cf71eb180 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -13,7 +13,8 @@ #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btVector3.h" -const float depth = 10.f; +b3AlignedObjectArray shadowbuffer; +Matrix viewportmat; struct Shader : public IShader { @@ -100,19 +101,17 @@ struct DepthShader : public IShader { Matrix& m_modelMat; Matrix m_invModelMat; - Matrix& m_modelView1; Matrix& m_projectionMatrix; Vec3f m_localScaling; Matrix& m_lightModelView; mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS - mat<4,3,float> varying_tri_light_view; // triangle coordinates (clip coordinates), written by VS, read by FS + mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - DepthShader(Model* model, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling) + DepthShader(Model* model, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling) :m_model(model), - m_modelView1(modelView), m_lightModelView(lightModelView), m_projectionMatrix(projectionMatrix), m_modelMat(modelMat), @@ -128,17 +127,14 @@ struct DepthShader : public IShader { Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0], unScaledVert[1]*m_localScaling[1], unScaledVert[2]*m_localScaling[2]); - Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(scaledVert); + Vec4f gl_Vertex = m_projectionMatrix*m_lightModelView*embed<4>(scaledVert); varying_tri.set_col(nthvert, gl_Vertex); - Vec4f gl_VertexLightView = m_projectionMatrix*m_lightModelView*embed<4>(scaledVert); - varying_tri_light_view.set_col(nthvert, gl_VertexLightView); return gl_Vertex; } virtual bool fragment(Vec3f bar, TGAColor &color) { - Vec4f p = varying_tri_light_view*bar; - printf("coefficient: %f\n", 1.0-p[2]/depth); - color = TGAColor(255, 255, 255)*(1.0-p[2]/depth); + Vec4f p = varying_tri*bar; + color = TGAColor(255, 255, 255)*p[2]; return false; } }; @@ -157,12 +153,17 @@ struct ShadowShader : public IShader { Matrix& m_lightModelView; Vec4f m_colorRGBA; + int m_width; + int m_height; + + int m_index; + mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS - mat<4,3,float> varying_tri_light_view; // triangle coordinates (clip coordinates), written by VS, read by FS + mat<4,3,float> varying_tri_light_view; mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) + ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height) :m_model(model), m_light_dir_local(light_dir_local), m_light_color(light_color), @@ -171,7 +172,9 @@ struct ShadowShader : public IShader { m_projectionMatrix(projectionMatrix), m_modelMat(modelMat), m_localScaling(localScaling), - m_colorRGBA(colorRGBA) + m_colorRGBA(colorRGBA), + m_width(width), + m_height(height) { m_invModelMat = m_modelMat.invert_transpose(); } @@ -191,9 +194,15 @@ struct ShadowShader : public IShader { } virtual bool fragment(Vec3f bar, TGAColor &color) { - Vec4f p = varying_tri_light_view*bar; - float shadow = 1.0-p[2]/depth; - printf("shadow: %f\n", shadow); + Vec4f p = viewportmat*(varying_tri_light_view*bar); + p = p/p[3]; + float depth = p[2]; + int index_x = b3Min(m_width-1, int(p[0])); + index_x = b3Max(0, index_x); + int index_y = b3Min(m_height-1, int(p[1])); + index_y = b3Max(0, index_y); + int idx = index_x + index_y*m_width; // index in the shadowbuffer array + float shadow = 0.3+0.7*(shadowbuffer[idx]<-depth); // magic coeff to avoid z-fighting Vec3f bn = (varying_nrm*bar).normalize(); Vec2f uv = varying_uv*bar; @@ -401,37 +410,63 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) Model* model = renderData.m_model; if (0==model) return; - - renderData.m_viewportMatrix = viewport(0,0,width, height); b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0; + TGAImage tempFrame(width, height, TGAImage::RGB); TGAImage& frame = renderData.m_rgbColorBuffer; - - + shadowbuffer.resize(zbuffer.size()); + for (int i = 0; i < shadowbuffer.size(); ++i) + { + shadowbuffer[i] = -1e30f; + } { - Matrix lightViewMatrix = lookat(Vec3f(0.0,0.1,2.0), Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); + Matrix lightViewMatrix = lookat(light_dir_local, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; + Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; + viewportmat = renderData.m_viewportMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - //Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); - //DepthShader shader(model, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling); - ShadowShader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); - - //printf("Render %d triangles.\n",model->nfaces()); + + + DepthShader shader(model, lightModelViewMatrix, lightViewProjectionMatrix,renderData.m_modelMatrix, localScaling); + for (int i=0; infaces(); i++) { - for (int j=0; j<3; j++) { shader.vertex(i, j); } triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); } + /* + ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA(), width, height); + + for (int i=0; infaces(); i++) + { + for (int j=0; j<3; j++) { + shadowShader.vertex(i, j); + } + triangle(shadowShader.varying_tri, shadowShader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + } + + Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); + + //printf("Render %d triangles.\n",model->nfaces()); + for (int i=0; infaces(); i++) + { + + for (int j=0; j<3; j++) { + shader.vertex(i, j); + } + triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + } + */ + } } diff --git a/examples/TinyRenderer/our_gl.cpp b/examples/TinyRenderer/our_gl.cpp index 21300945f..c2f529597 100644 --- a/examples/TinyRenderer/our_gl.cpp +++ b/examples/TinyRenderer/our_gl.cpp @@ -4,13 +4,11 @@ #include "our_gl.h" #include "Bullet3Common/b3MinMax.h" - - - IShader::~IShader() {} Matrix viewport(int x, int y, int w, int h) { + Matrix Viewport; Viewport = Matrix::identity(); Viewport[0][3] = x+w/2.f; @@ -20,6 +18,18 @@ Matrix viewport(int x, int y, int w, int h) Viewport[1][1] = h/2.f; Viewport[2][2] = 0; return Viewport; + + /* + Matrix Viewport; + Viewport = Matrix::identity(); + Viewport[0][3] = x+w/2.f; + Viewport[1][3] = y+h/2.f; + Viewport[2][3] = .5f; + Viewport[0][0] = w/2.f; + Viewport[1][1] = h/2.f; + Viewport[2][2] = .5f; + return Viewport; + */ } Matrix projection(float coeff) { @@ -75,6 +85,7 @@ Matrix lookat(Vec3f eye, Vec3f center, Vec3f up) { ModelView[3][3] = 1.f; return ModelView; + } Vec3f barycentric(Vec2f A, Vec2f B, Vec2f C, Vec2f P) { @@ -97,8 +108,7 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zbuffer, int* segmentationMaskBuffer, const Matrix& viewPortMatrix, int objectIndex) { mat<3,4,float> pts = (viewPortMatrix*clipc).transpose(); // transposed to ease access to each of the points - - + //we don't clip triangles that cross the near plane, just discard them instead of showing artifacts if (pts[0][3]<0 || pts[1][3] <0 || pts[2][3] <0) return;