From ef85a71d4baa03b902f2ed57091ba52d12e75e70 Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Wed, 1 Jun 2016 11:04:10 -0700 Subject: [PATCH] more work on synthetic camera --- examples/SharedMemory/PhysicsClientC_API.cpp | 13 +++++-- .../SharedMemory/PhysicsClientExample.cpp | 8 +++-- .../PhysicsServerCommandProcessor.cpp | 36 ++++++++++++++++--- examples/SharedMemory/SharedMemoryCommands.h | 12 ++++++- .../TinyRendererVisualShapeConverter.cpp | 23 +++++++----- .../TinyRendererVisualShapeConverter.h | 1 + examples/TinyRenderer/TinyRenderer.cpp | 33 ++++++++++------- 7 files changed, 95 insertions(+), 31 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 40451313c..1ebf29201 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -687,13 +687,22 @@ b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physC b3Assert(command); command->m_type =CMD_REQUEST_CAMERA_IMAGE_DATA; command->m_requestPixelDataArguments.m_startPixelIndex = 0; + command->m_updateFlags = REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL; return (b3SharedMemoryCommandHandle) command; } -void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]) +void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16]) { - + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + for (int i=0;i<16;i++) + { + command->m_requestPixelDataArguments.m_projectionMatrix[i] = projectionMatrix[i]; + command->m_requestPixelDataArguments.m_viewMatrix[i] = viewMatrix[i]; + } + command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData) diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index fcdf38783..48db45fd1 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -246,8 +246,12 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) ///request an image from a simulated camera, using a software renderer. b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); - //void b3RequestCameraImageSetResolution(b3SharedMemoryCommandHandle command, int pixelWidth, int pixelHeight); - //void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]); + + float viewMatrix[16]; + float projectionMatrix[16]; + this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); + this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); + b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 330455446..3e191db58 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -971,12 +971,32 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm int startPixelIndex = clientCmd.m_requestPixelDataArguments.m_startPixelIndex; int width, height; int numPixelsCopied = 0; - - if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) + + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL)!=0) { - m_data->m_visualConverter.render(); + m_data->m_guiHelper->copyCameraImageData(0,0,0,0,0,&width,&height,0); + } + //else + { + if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) + { + printf("-------------------------------\nRendering\n"); + + + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0) + { + m_data->m_visualConverter.render( + clientCmd.m_requestPixelDataArguments.m_viewMatrix, + clientCmd.m_requestPixelDataArguments.m_projectionMatrix); + } else + { + m_data->m_visualConverter.render(); + } + + } } - m_data->m_guiHelper->copyCameraImageData(0,0,0,0,0,&width,&height,0); + + int numTotalPixels = width*height; int numRemainingPixels = numTotalPixels - startPixelIndex; @@ -990,8 +1010,14 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm float* depthBuffer = (float*)(bufferServerToClient+numRequestedPixels*4); + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL)!=0) + { + m_data->m_guiHelper->copyCameraImageData(pixelRGBA,numRequestedPixels,depthBuffer,numRequestedPixels,startPixelIndex,&width,&height,&numPixelsCopied); + } else + { + + } - m_data->m_guiHelper->copyCameraImageData(pixelRGBA,numRequestedPixels,depthBuffer,numRequestedPixels,startPixelIndex,&width,&height,&numPixelsCopied); //each pixel takes 4 RGBA values and 1 float = 8 bytes } else diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 992ac8453..42436d2b0 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -115,9 +115,19 @@ struct RequestDebugLinesArgs struct RequestPixelDataArgs { - int m_startPixelIndex; + float m_viewMatrix[16]; + float m_projectionMatrix[16]; + int m_startPixelIndex; }; +enum EnumRequestPixelDataUpdateFlags +{ + REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1, + REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL=2, +}; + + + struct SendDebugLinesArgs { int m_startingLineIndex; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 50bee85c6..ffc56e52d 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -494,10 +494,20 @@ void TinyRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor) } } - - void TinyRendererVisualShapeConverter::render() +{ + + ATTRIBUTE_ALIGNED16(float viewMat[16]); + ATTRIBUTE_ALIGNED16(float projMat[16]); + + m_data->m_camera.getCameraProjectionMatrix(projMat); + m_data->m_camera.getCameraViewMatrix(viewMat); + + render(viewMat,projMat); +} + +void TinyRendererVisualShapeConverter::render(const float viewMat[16], const float projMat[16]) { //clear the color buffer TGAColor clearColor; @@ -510,11 +520,7 @@ void TinyRendererVisualShapeConverter::render() ATTRIBUTE_ALIGNED16(btScalar modelMat[16]); - ATTRIBUTE_ALIGNED16(float viewMat[16]); - ATTRIBUTE_ALIGNED16(float projMat[16]); - - m_data->m_camera.getCameraProjectionMatrix(projMat); - m_data->m_camera.getCameraViewMatrix(viewMat); + btVector3 lightDirWorld(-5,200,-40); switch (m_data->m_upAxis) @@ -530,7 +536,7 @@ void TinyRendererVisualShapeConverter::render() lightDirWorld.normalize(); - + printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size()); for (int i=0;im_swRenderInstances.size();i++) { TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(i); @@ -568,6 +574,7 @@ void TinyRendererVisualShapeConverter::render() TinyRenderer::renderObject(*renderObj); } } + //printf("write tga \n"); m_data->m_rgbColorBuffer.write_tga_file("camera.tga"); } diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.h b/examples/SharedMemory/TinyRendererVisualShapeConverter.h index 1256641ff..634b40e1b 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.h +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.h @@ -24,6 +24,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter void resetAll(); void render(); + void render(const float viewMat[16], const float projMat[16]); }; diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 167cd77bc..8929831e2 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -12,7 +12,7 @@ #include "../OpenGLWindow/ShapeData.h" #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btVector3.h" -Vec3f light_dir_world(0,0,0); + struct Shader : public IShader { @@ -20,9 +20,12 @@ struct Shader : public IShader { Model* m_model; Vec3f m_light_dir_local; Matrix& m_modelMat; + Matrix m_invModelMat; + Matrix& m_modelView1; Matrix& m_projectionMatrix; Vec3f m_localScaling; + //Vec3f m_localNormal; 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 @@ -37,7 +40,7 @@ struct Shader : public IShader { m_modelMat(modelMat), m_localScaling(localScaling) { - + m_invModelMat = m_modelMat.invert_transpose(); } virtual Vec4f vertex(int iface, int nthvert) { @@ -47,10 +50,15 @@ struct Shader : public IShader { varying_uv.set_col(nthvert, uv); //varying_nrm.set_col(nthvert, proj<3>((m_projectionMatrix*m_modelView).invert_transpose()*embed<4>(m_model->normal(iface, nthvert), 0.f))); - varying_nrm.set_col(nthvert, proj<3>((m_modelMat).invert_transpose()*embed<4>(m_model->normal(iface, nthvert), 0.f))); + varying_nrm.set_col(nthvert, proj<3>(m_invModelMat*embed<4>(m_model->normal(iface, nthvert), 0.f))); + //m_localNormal = m_model->normal(iface, nthvert); + //varying_nrm.set_col(nthvert, m_model->normal(iface, nthvert)); + Vec3f unScaledVert = m_model->vert(iface, nthvert); + 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_modelView1*embed<4>(scaledVert); varying_tri.set_col(nthvert, gl_Vertex); //ndc_tri.set_col(nthvert, proj<3>(gl_Vertex/gl_Vertex[3])); @@ -63,7 +71,8 @@ struct Shader : public IShader { //float diff = 1;//full-bright float ambient = 0.7; - float diff = ambient+b3Min(b3Max(0.f, bn*light_dir_world),(1-ambient)); + //float diff = ambient+b3Min(b3Max(0.f, bn*light_dir_world),(1-ambient)); + float diff = ambient+b3Min(b3Max(0.f, bn*m_light_dir_local),(1-ambient)); //float diff = b3Max(0.f, n*m_light_dir_local); color = m_model->diffuse(uv)*diff; @@ -222,7 +231,7 @@ TinyRenderObjectData::~TinyRenderObjectData() void TinyRenderer::renderObject(TinyRenderObjectData& renderData) { - light_dir_world = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); + Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); Model* model = renderData.m_model; if (0==model) return; @@ -235,23 +244,21 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) //renderData.m_viewportMatrix = viewport(width/8, height/8, width*3/4, height*3/4); renderData.m_viewportMatrix = viewport(0,0,renderData.m_width,renderData.m_height); //renderData.m_projectionMatrix = projection(-1.f/(eye-center).norm()); - - b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; TGAImage& frame = renderData.m_rgbColorBuffer; - Vec3f light_dir_local = proj<3>((renderData.m_projectionMatrix*renderData.m_viewMatrix*renderData.m_modelMatrix*embed<4>(light_dir_world, 0.f))).normalize(); + { Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); Shader shader(model, light_dir_local, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling); - - - - for (int i=0; infaces(); i++) { + + printf("Render %d triangles.\n",model->nfaces()); + for (int i=0; infaces(); i++) + { for (int j=0; j<3; j++) { shader.vertex(i, j);