Add shader for projective texture.

This commit is contained in:
yunfeibai 2018-02-11 21:29:02 -08:00
parent 08548e1ef0
commit 2947cd54ce
10 changed files with 85 additions and 33 deletions

View File

@ -56,7 +56,8 @@ premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingPS.h" --stringname="useShadowMapInstancingFragmentShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingVS.h" --stringname="useShadowMapInstancingVertexShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/projectiveTextureInstancingPS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/projectiveTextureInstancingPS.h" --stringname="projectiveTextureInstancingFragmentShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/projectiveTextureInstancingVS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/projectiveTextureInstancingVS.h" --stringname="projectiveTextureInstancingVertexShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../Demos3/GpuDemos/broadphase/pairsKernel.cl" --headerfile="../Demos3/GpuDemos/broadphase/pairsKernel.h" --stringname="pairsKernelsCL" stringify

View File

@ -62,6 +62,8 @@ eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWin
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h" --stringname="useShadowMapInstancingFragmentShader" stringify'
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h" --stringname="useShadowMapInstancingVertexShader" stringify'
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingPS.h" --stringname="projectiveTextureInstancingFragmentShader" stringify'
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingVS.h" --stringname="projectiveTextureInstancingVertexShader" stringify'
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenCL/broadphase/pairsKernel.cl" --headerfile="../examples/OpenCL/broadphase/pairsKernel.h" --stringname="pairsKernelsCL" stringify'

View File

@ -10,6 +10,8 @@ premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shade
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/createShadowMapInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/createShadowMapInstancingVS.h" --stringname="createShadowMapInstancingVertexShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h" --stringname="useShadowMapInstancingFragmentShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h" --stringname="useShadowMapInstancingVertexShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingPS.h" --stringname="projectiveTextureInstancingFragmentShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingVS.h" --stringname="projectiveTextureInstancingVertexShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/linesVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/linesVS.h" --stringname="linesVertexShader" stringify
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/linesPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/linesPS.h" --stringname="linesFragmentShader" stringify

View File

@ -10,7 +10,7 @@ newmtl cube
Ks 0.0000 0.0000 0.0000
Ke 0.0000 0.0000 0.0000
map_Ka cube.tga
map_Kd checker_blue.png
map_Kd cube.png

View File

@ -16,9 +16,9 @@ subject to the following restrictions:
///todo: make this configurable in the gui
bool useShadowMap = false;// true;//false;//true;
bool useShadowMap = true;// true;//false;//true;
float projectiveTextureViewSize = 10;
bool useProjectiveTexture = true;
bool useProjectiveTexture = false;
int shadowMapWidth= 4096;
int shadowMapHeight= 4096;
float shadowMapWorldSize=10;
@ -74,6 +74,8 @@ float shadowMapWorldSize=10;
#include "Shaders/createShadowMapInstancingPS.h"
#include "Shaders/useShadowMapInstancingVS.h"
#include "Shaders/useShadowMapInstancingPS.h"
#include "Shaders/projectiveTextureInstancingVS.h"
#include "Shaders/projectiveTextureInstancingPS.h"
#include "Shaders/linesPS.h"
#include "Shaders/linesVS.h"
@ -250,6 +252,8 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData
{
m_lightPos=b3MakeVector3(-50,30,40);
m_lightSpecularIntensity.setValue(1,1,1);
m_projectorPos=b3MakeVector3(-50,30,40);
//clear to zero to make it obvious if the matrix is used uninitialized
for (int i=0;i<16;i++)
@ -284,6 +288,7 @@ static GLuint triangleIndexVbo=0;
static GLuint linesShader; // The line renderer
static GLuint useShadowMapInstancingShader; // The shadow instancing renderer
static GLuint createShadowMapInstancingShader; // The shadow instancing renderer
static GLuint projectiveTextureInstancingShader; // The projective texture instancing renderer
static GLuint instancingShader; // The instancing renderer
static GLuint instancingShaderPointSprite; // The point sprite instancing renderer
@ -321,6 +326,20 @@ static GLint useShadow_shadowMap = 0;
static GLint createShadow_depthMVP=0;
static GLint projectiveTexture_ViewMatrixInverse=0;
static GLint projectiveTexture_ModelViewMatrix=0;
static GLint projectiveTexture_lightSpecularIntensity = 0;
static GLint projectiveTexture_materialSpecularColor = 0;
static GLint projectiveTexture_MVP=0;
static GLint projectiveTexture_lightPosIn=0;
static GLint projectiveTexture_cameraPositionIn = 0;
static GLint projectiveTexture_materialShininessIn = 0;
static GLint projectiveTexture_ProjectionMatrix=0;
static GLint projectiveTexture_DepthBiasModelViewMatrix=0;
static GLint projectiveTexture_uniform_texture_diffuse = 0;
static GLint projectiveTexture_shadowMap = 0;
static GLint ModelViewMatrix=0;
static GLint ProjectionMatrix=0;
static GLint regularLightDirIn=0;
@ -1212,7 +1231,24 @@ void GLInstancingRenderer::InitShaders()
glGetIntegerv(GL_SMOOTH_LINE_WIDTH_RANGE, lineWidthRange);
projectiveTextureInstancingShader = gltLoadShaderPair(projectiveTextureInstancingVertexShader,projectiveTextureInstancingFragmentShader);
glLinkProgram(projectiveTextureInstancingShader);
glUseProgram(projectiveTextureInstancingShader);
projectiveTexture_ViewMatrixInverse = glGetUniformLocation(projectiveTextureInstancingShader, "ViewMatrixInverse");
projectiveTexture_ModelViewMatrix = glGetUniformLocation(projectiveTextureInstancingShader, "ModelViewMatrix");
projectiveTexture_lightSpecularIntensity = glGetUniformLocation(projectiveTextureInstancingShader, "lightSpecularIntensityIn");
projectiveTexture_materialSpecularColor = glGetUniformLocation(projectiveTextureInstancingShader, "materialSpecularColorIn");
projectiveTexture_MVP = glGetUniformLocation(projectiveTextureInstancingShader, "MVP");
projectiveTexture_ProjectionMatrix = glGetUniformLocation(projectiveTextureInstancingShader, "ProjectionMatrix");
projectiveTexture_DepthBiasModelViewMatrix = glGetUniformLocation(projectiveTextureInstancingShader, "DepthBiasModelViewProjectionMatrix");
projectiveTexture_uniform_texture_diffuse = glGetUniformLocation(projectiveTextureInstancingShader, "Diffuse");
projectiveTexture_shadowMap = glGetUniformLocation(projectiveTextureInstancingShader,"shadowMap");
projectiveTexture_lightPosIn = glGetUniformLocation(projectiveTextureInstancingShader,"lightPosIn");
projectiveTexture_cameraPositionIn = glGetUniformLocation(projectiveTextureInstancingShader,"cameraPositionIn");
projectiveTexture_materialShininessIn = glGetUniformLocation(projectiveTextureInstancingShader,"materialShininessIn");
glUseProgram(0);
useShadowMapInstancingShader = gltLoadShaderPair(useShadowMapInstancingVertexShader,useShadowMapInstancingFragmentShader);
@ -1538,7 +1574,7 @@ void GLInstancingRenderer::renderScene()
}
else if (useProjectiveTexture)
{
renderSceneInternal(B3_CREATE_SHADOWMAP_RENDERMODE);
//renderSceneInternal(B3_CREATE_SHADOWMAP_RENDERMODE);
renderSceneInternal(B3_USE_PROJECTIVE_TEXTURE_RENDERMODE);
}
else
@ -2136,9 +2172,8 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
// Compute projection matrix for texture projector
float textureViewMatrix[4][4];
b3Vector3 projectorDir = m_data->m_projectorDir.normalize();
float projectorDist = 3.0;
b3Vector3 projectorUp = b3MakeVector3(0,0,1.0);
b3CreateLookAt(m_data->m_projectorPos, m_data->m_projectorDir*projectorDist, projectorUp, &textureViewMatrix[0][0]);
float projectorDist = 0;
b3CreateLookAt(m_data->m_projectorPos,center,up, &textureViewMatrix[0][0]);
GLfloat textureModelMatrix[4][4];
b3CreateDiagonalMatrix(1.f, textureModelMatrix);
b3Matrix4x4Mul(textureViewMatrix, textureModelMatrix, textureModelViewMatrix);
@ -2497,6 +2532,7 @@ b3Assert(glGetError() ==GL_NO_ERROR);
}
case B3_USE_PROJECTIVE_TEXTURE_RENDERMODE:
{
printf("PROJECTIVE TEXTURE!!\n");
if ( gfxObj->m_flags&eGfxTransparency)
{
glDepthMask(false);
@ -2504,10 +2540,10 @@ b3Assert(glGetError() ==GL_NO_ERROR);
glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
}
glUseProgram(useShadowMapInstancingShader);
glUniformMatrix4fv(useShadow_ProjectionMatrix, 1, false, &m_data->m_projectionMatrix[0]);
glUniform3f(useShadow_lightSpecularIntensity, m_data->m_lightSpecularIntensity[0],m_data->m_lightSpecularIntensity[1],m_data->m_lightSpecularIntensity[2]);
glUniform3f(useShadow_materialSpecularColor, gfxObj->m_materialSpecularColor[0],gfxObj->m_materialSpecularColor[1],gfxObj->m_materialSpecularColor[2]);
glUseProgram(projectiveTextureInstancingShader);
glUniformMatrix4fv(projectiveTexture_ProjectionMatrix, 1, false, &m_data->m_projectionMatrix[0]);
glUniform3f(projectiveTexture_lightSpecularIntensity, m_data->m_lightSpecularIntensity[0],m_data->m_lightSpecularIntensity[1],m_data->m_lightSpecularIntensity[2]);
glUniform3f(projectiveTexture_materialSpecularColor, gfxObj->m_materialSpecularColor[0],gfxObj->m_materialSpecularColor[1],gfxObj->m_materialSpecularColor[2]);
float MVP[16];
if (reflectionPass)
@ -2526,17 +2562,17 @@ b3Assert(glGetError() ==GL_NO_ERROR);
glCullFace(GL_BACK);
}
glUniformMatrix4fv(useShadow_MVP, 1, false, &MVP[0]);
glUniform3f(useShadow_lightPosIn,m_data->m_lightPos[0],m_data->m_lightPos[1],m_data->m_lightPos[2]);
glUniformMatrix4fv(projectiveTexture_MVP, 1, false, &MVP[0]);
glUniform3f(projectiveTexture_lightPosIn,m_data->m_lightPos[0],m_data->m_lightPos[1],m_data->m_lightPos[2]);
float camPos[3];
m_data->m_activeCamera->getCameraPosition(camPos);
glUniform3f(useShadow_cameraPositionIn,camPos[0],camPos[1],camPos[2]);
glUniform1f(useShadow_materialShininessIn,gfxObj->m_materialShinyNess);
glUniform3f(projectiveTexture_cameraPositionIn,camPos[0],camPos[1],camPos[2]);
glUniform1f(projectiveTexture_materialShininessIn,gfxObj->m_materialShinyNess);
glUniformMatrix4fv(useShadow_DepthBiasModelViewMatrix, 1, false, &textureMVP[0][0]);
glUniformMatrix4fv(projectiveTexture_DepthBiasModelViewMatrix, 1, false, &textureMVP[0][0]);
glActiveTexture(GL_TEXTURE1);
glBindTexture(GL_TEXTURE_2D, m_data->m_shadowTexture);
glUniform1i(useShadow_shadowMap,1);
glUniform1i(projectiveTexture_shadowMap,1);
//sort transparent objects
if ( gfxObj->m_flags&eGfxTransparency)

View File

@ -12,9 +12,11 @@ in Vert
} vert;
uniform sampler2D Diffuse;
uniform sampler2DShadow shadowMap;
uniform mat4 ViewMatrixInverse;
in vec3 lightPos,cameraPosition, normal,ambient;
in vec4 ShadowCoord;
in vec4 vertexPos;
in float materialShininess;
in vec3 lightSpecularIntensity;
@ -26,7 +28,7 @@ out vec4 color;
void main(void)
{
vec4 texel = fragment.color*texture(Diffuse,vert.texcoord.xy);
vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);
vec3 ct,cf;
float intensity,at,af;
if (fragment.color.w==0)
@ -63,7 +65,9 @@ void main(void)
}
float visibility = 1.0;
float visibility = texture(shadowMap, vec3(ShadowCoord.xy,(ShadowCoord.z)/ShadowCoord.w));
if (intensity<0.5)
visibility = 0;
intensity = 0.7*intensity + 0.3*intensity*visibility;

View File

@ -11,8 +11,10 @@ static const char* useShadowMapInstancingFragmentShader= \
" vec2 texcoord;\n"
"} vert;\n"
"uniform sampler2D Diffuse;\n"
"uniform sampler2DShadow shadowMap;\n"
"uniform mat4 ViewMatrixInverse;\n"
"in vec3 lightPos,cameraPosition, normal,ambient;\n"
"in vec4 ShadowCoord;\n"
"in vec4 vertexPos;\n"
"in float materialShininess;\n"
"in vec3 lightSpecularIntensity;\n"
@ -20,7 +22,7 @@ static const char* useShadowMapInstancingFragmentShader= \
"out vec4 color;\n"
"void main(void)\n"
"{\n"
" vec4 texel = fragment.color*texture(Diffuse,vert.texcoord.xy);\n"
" vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);\n"
" vec3 ct,cf;\n"
" float intensity,at,af;\n"
" if (fragment.color.w==0)\n"
@ -56,7 +58,9 @@ static const char* useShadowMapInstancingFragmentShader= \
" \n"
" }\n"
" \n"
" float visibility = 1.0;\n"
" float visibility = texture(shadowMap, vec3(ShadowCoord.xy,(ShadowCoord.z)/ShadowCoord.w));\n"
" if (intensity<0.5)\n"
" visibility = 0;\n"
" intensity = 0.7*intensity + 0.3*intensity*visibility;\n"
" \n"
" cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient+specularReflection*visibility;\n"

View File

@ -11,6 +11,8 @@ layout (location = 5) in vec4 instance_color;
layout (location = 6) in vec3 instance_scale;
uniform mat4 ModelViewMatrix;
uniform mat4 ProjectionMatrix;
uniform mat4 DepthBiasModelViewProjectionMatrix;
uniform mat4 MVP;
uniform vec3 lightPosIn;
@ -91,9 +93,9 @@ void main(void)
vec4 vertexLoc = MVP* vec4((instance_position+localcoord).xyz,1);
gl_Position = vertexLoc;
ShadowCoord = DepthBiasModelViewProjectionMatrix * vec4((instance_position+localcoord).xyz,1);
fragment.color = instance_color;
vec4 projcoords = DepthBiasModelViewProjectionMatrix * vec4((instance_position+localcoord).xyz,1);
vert.texcoord = projcoords.xy;
vert.texcoord = uvcoords;
}

View File

@ -9,6 +9,8 @@ static const char* useShadowMapInstancingVertexShader= \
"layout (location = 4) in vec3 vertexnormal;\n"
"layout (location = 5) in vec4 instance_color;\n"
"layout (location = 6) in vec3 instance_scale;\n"
"uniform mat4 ModelViewMatrix;\n"
"uniform mat4 ProjectionMatrix;\n"
"uniform mat4 DepthBiasModelViewProjectionMatrix;\n"
"uniform mat4 MVP;\n"
"uniform vec3 lightPosIn;\n"
@ -79,8 +81,8 @@ static const char* useShadowMapInstancingVertexShader= \
" \n"
" vec4 vertexLoc = MVP* vec4((instance_position+localcoord).xyz,1);\n"
" gl_Position = vertexLoc;\n"
" ShadowCoord = DepthBiasModelViewProjectionMatrix * vec4((instance_position+localcoord).xyz,1);\n"
" fragment.color = instance_color;\n"
" vec4 projcoords = DepthBiasModelViewProjectionMatrix * vec4((instance_position+localcoord).xyz,1);\n"
" vert.texcoord = projcoords.xy;\n"
" vert.texcoord = uvcoords;\n"
"}\n"
;

View File

@ -12,11 +12,10 @@ cubeStartPos = [0,0,1]
cubeStartOrientation = p.getQuaternionFromEuler([0,0,0])
boxId = p.loadURDF("cube.urdf",cubeStartPos, cubeStartOrientation)
cubePos, cubeOrn = p.getBasePositionAndOrientation(boxId)
textureId = p.loadTexture("kcam_vga_scaled_direct.png")
textureId = p.loadTexture("checker_blue_test.png")
p.changeVisualShape(objectUniqueId=0, linkIndex=-1, textureUniqueId=textureId)
p.changeVisualShape(objectUniqueId=1, linkIndex=-1, textureUniqueId=textureId)
#p.resetDebugVisualizerCamera(cameraDistance=3, cameraYaw=30, cameraPitch=52, cameraTargetPosition=[10,0,0])
fov = 70
pixelWidth = 640
pixelHeight = 512
@ -24,17 +23,17 @@ aspect = pixelWidth / pixelHeight;
nearPlane = 0.01
farPlane = 100
projectionMatrix = p.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
viewMatrixLeft = p.computeViewMatrix(cameraEyePosition=[0.045, 3.0, 3.0], cameraTargetPosition=[0.045,0,0], cameraUpVector=[0,0,1.0])
viewMatrixRight = p.computeViewMatrix(cameraEyePosition=[-0.045, 3.0, 3.0], cameraTargetPosition=[-0.045,0,0], cameraUpVector=[0,0,1.0])
viewMatrixLeft = p.computeViewMatrix(cameraEyePosition=[0.045, 3.0, 3.0], cameraTargetPosition=[0.045,0,0], cameraUpVector=[0,0,1])
viewMatrixRight = p.computeViewMatrix(cameraEyePosition=[-0.045, 3.0, 3.0], cameraTargetPosition=[-0.045,0,0], cameraUpVector=[0,0,1])
leftImage = p.getCameraImage(width=640,height=512,viewMatrix=viewMatrixLeft,projectionMatrix=projectionMatrix,renderer=p.ER_BULLET_HARDWARE_OPENGL)
rightImage = p.getCameraImage(width=640,height=512,viewMatrix=viewMatrixRight,projectionMatrix=projectionMatrix,renderer=p.ER_BULLET_HARDWARE_OPENGL)
left_img = np.reshape(np.asarray(leftImage[2], dtype=np.float32), (512, 640, 4))
left_img /= 255
plt.imsave("left_image_new.png", left_img)
plt.imsave("left_image.png", left_img)
right_img = np.reshape(np.asarray(rightImage[2], dtype=np.float32), (512, 640, 4))
right_img /= 255
plt.imsave("right_image_new.png", right_img)
plt.imsave("right_image.png", right_img)
useRealTimeSimulation = 1