Add example for projective texture.

This commit is contained in:
yunfeibai
2018-02-11 13:50:45 -08:00
parent 0bebf86b50
commit 08548e1ef0
8 changed files with 163 additions and 20 deletions

View File

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

View File

@@ -16,6 +16,7 @@ enum
B3_CREATE_SHADOWMAP_RENDERMODE, B3_CREATE_SHADOWMAP_RENDERMODE,
B3_USE_SHADOWMAP_RENDERMODE, B3_USE_SHADOWMAP_RENDERMODE,
B3_USE_SHADOWMAP_RENDERMODE_REFLECTION, B3_USE_SHADOWMAP_RENDERMODE_REFLECTION,
B3_USE_PROJECTIVE_TEXTURE_RENDERMODE,
}; };

View File

@@ -16,7 +16,9 @@ subject to the following restrictions:
///todo: make this configurable in the gui ///todo: make this configurable in the gui
bool useShadowMap = true;// true;//false;//true; bool useShadowMap = false;// true;//false;//true;
float projectiveTextureViewSize = 10;
bool useProjectiveTexture = true;
int shadowMapWidth= 4096; int shadowMapWidth= 4096;
int shadowMapHeight= 4096; int shadowMapHeight= 4096;
float shadowMapWorldSize=10; float shadowMapWorldSize=10;
@@ -225,6 +227,9 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData
b3Vector3 m_lightPos; b3Vector3 m_lightPos;
b3Vector3 m_lightSpecularIntensity; b3Vector3 m_lightSpecularIntensity;
b3Vector3 m_projectorPos;
b3Vector3 m_projectorDir;
GLuint m_defaultTexturehandle; GLuint m_defaultTexturehandle;
b3AlignedObjectArray<InternalTextureHandle> m_textureHandles; b3AlignedObjectArray<InternalTextureHandle> m_textureHandles;
@@ -1530,7 +1535,13 @@ void GLInstancingRenderer::renderScene()
//renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE_REFLECTION); //renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE_REFLECTION);
renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE); renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE);
} else }
else if (useProjectiveTexture)
{
renderSceneInternal(B3_CREATE_SHADOWMAP_RENDERMODE);
renderSceneInternal(B3_USE_PROJECTIVE_TEXTURE_RENDERMODE);
}
else
{ {
renderSceneInternal(); renderSceneInternal();
} }
@@ -1976,6 +1987,11 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
renderMode = B3_DEFAULT_RENDERMODE; renderMode = B3_DEFAULT_RENDERMODE;
} }
if (orgRenderMode==B3_USE_PROJECTIVE_TEXTURE_RENDERMODE)
{
renderMode = B3_USE_PROJECTIVE_TEXTURE_RENDERMODE;
}
// glEnable(GL_DEPTH_TEST); // glEnable(GL_DEPTH_TEST);
GLint dims[4]; GLint dims[4];
@@ -2004,6 +2020,10 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
GLfloat depthModelViewMatrix[4][4]; GLfloat depthModelViewMatrix[4][4];
//GLfloat depthModelViewMatrix2[4][4]; //GLfloat depthModelViewMatrix2[4][4];
// For projective texture mapping
float textureProjectionMatrix[4][4];
GLfloat textureModelViewMatrix[4][4];
// Compute the MVP matrix from the light's point of view // Compute the MVP matrix from the light's point of view
if (renderMode==B3_CREATE_SHADOWMAP_RENDERMODE) if (renderMode==B3_CREATE_SHADOWMAP_RENDERMODE)
{ {
@@ -2113,6 +2133,18 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
GLfloat depthBiasMVP[4][4]; GLfloat depthBiasMVP[4][4];
b3Matrix4x4Mul(biasMatrix,depthMVP,depthBiasMVP); b3Matrix4x4Mul(biasMatrix,depthMVP,depthBiasMVP);
// 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]);
GLfloat textureModelMatrix[4][4];
b3CreateDiagonalMatrix(1.f, textureModelMatrix);
b3Matrix4x4Mul(textureViewMatrix, textureModelMatrix, textureModelViewMatrix);
b3CreateOrtho(-projectiveTextureViewSize,projectiveTextureViewSize,-projectiveTextureViewSize,projectiveTextureViewSize,1,300,textureProjectionMatrix);
GLfloat textureMVP[4][4];
b3Matrix4x4Mul(textureProjectionMatrix, textureModelViewMatrix, textureMVP);
//float m_frustumZNear=0.1; //float m_frustumZNear=0.1;
//float m_frustumZFar=100.f; //float m_frustumZFar=100.f;
@@ -2459,6 +2491,75 @@ b3Assert(glGetError() ==GL_NO_ERROR);
glActiveTexture(GL_TEXTURE1); glActiveTexture(GL_TEXTURE1);
glBindTexture(GL_TEXTURE_2D,0); glBindTexture(GL_TEXTURE_2D,0);
glActiveTexture(GL_TEXTURE0);
glBindTexture(GL_TEXTURE_2D,0);
break;
}
case B3_USE_PROJECTIVE_TEXTURE_RENDERMODE:
{
if ( gfxObj->m_flags&eGfxTransparency)
{
glDepthMask(false);
glEnable (GL_BLEND);
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]);
float MVP[16];
if (reflectionPass)
{
float tmp[16];
float reflectionMatrix[16] = {1,0,0,0,
0,1,0,0,
0,0,-1,0,
0,0,0,1};
glCullFace(GL_FRONT);
b3Matrix4x4Mul16(m_data->m_viewMatrix,reflectionMatrix,tmp);
b3Matrix4x4Mul16(m_data->m_projectionMatrix,tmp,MVP);
} else
{
b3Matrix4x4Mul16(m_data->m_projectionMatrix,m_data->m_viewMatrix,MVP);
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]);
float camPos[3];
m_data->m_activeCamera->getCameraPosition(camPos);
glUniform3f(useShadow_cameraPositionIn,camPos[0],camPos[1],camPos[2]);
glUniform1f(useShadow_materialShininessIn,gfxObj->m_materialShinyNess);
glUniformMatrix4fv(useShadow_DepthBiasModelViewMatrix, 1, false, &textureMVP[0][0]);
glActiveTexture(GL_TEXTURE1);
glBindTexture(GL_TEXTURE_2D, m_data->m_shadowTexture);
glUniform1i(useShadow_shadowMap,1);
//sort transparent objects
if ( gfxObj->m_flags&eGfxTransparency)
{
int instanceId = transparentInstances[i].m_instanceId;
glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)((instanceId)*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes));
glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)((instanceId)*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE));
glVertexAttribPointer(5, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)((instanceId)*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE));
glVertexAttribPointer(6, 3, GL_FLOAT, GL_FALSE, 0, (GLvoid *)((instanceId)*3*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE));
glDrawElements(GL_TRIANGLES, indexCount, GL_UNSIGNED_INT, 0);
} else
{
glDrawElementsInstanced(GL_TRIANGLES, indexCount, GL_UNSIGNED_INT, indexOffset, gfxObj->m_numGraphicsInstances);
}
if ( gfxObj->m_flags&eGfxTransparency)
{
glDisable (GL_BLEND);
glDepthMask(true);
}
glActiveTexture(GL_TEXTURE1);
glBindTexture(GL_TEXTURE_2D,0);
glActiveTexture(GL_TEXTURE0); glActiveTexture(GL_TEXTURE0);
glBindTexture(GL_TEXTURE_2D,0); glBindTexture(GL_TEXTURE_2D,0);
break; break;

View File

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

View File

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

View File

@@ -91,9 +91,9 @@ void main(void)
vec4 vertexLoc = MVP* vec4((instance_position+localcoord).xyz,1); vec4 vertexLoc = MVP* vec4((instance_position+localcoord).xyz,1);
gl_Position = vertexLoc; gl_Position = vertexLoc;
ShadowCoord = DepthBiasModelViewProjectionMatrix * vec4((instance_position+localcoord).xyz,1);
fragment.color = instance_color; fragment.color = instance_color;
vert.texcoord = uvcoords; vec4 projcoords = DepthBiasModelViewProjectionMatrix * vec4((instance_position+localcoord).xyz,1);
vert.texcoord = projcoords.xy;
} }

View File

@@ -79,8 +79,8 @@ static const char* useShadowMapInstancingVertexShader= \
" \n" " \n"
" vec4 vertexLoc = MVP* vec4((instance_position+localcoord).xyz,1);\n" " vec4 vertexLoc = MVP* vec4((instance_position+localcoord).xyz,1);\n"
" gl_Position = vertexLoc;\n" " gl_Position = vertexLoc;\n"
" ShadowCoord = DepthBiasModelViewProjectionMatrix * vec4((instance_position+localcoord).xyz,1);\n"
" fragment.color = instance_color;\n" " fragment.color = instance_color;\n"
" vert.texcoord = uvcoords;\n" " vec4 projcoords = DepthBiasModelViewProjectionMatrix * vec4((instance_position+localcoord).xyz,1);\n"
" vert.texcoord = projcoords.xy;\n"
"}\n" "}\n"
; ;

View File

@@ -0,0 +1,49 @@
import pybullet as p
from time import sleep
from PIL import Image
import matplotlib.pyplot as plt
import numpy as np
physicsClient = p.connect(p.GUI)
p.setGravity(0,0,-10)
planeId = p.loadURDF("plane.urdf")
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")
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
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])
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)
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)
useRealTimeSimulation = 1
if (useRealTimeSimulation):
p.setRealTimeSimulation(1)
while 1:
if (useRealTimeSimulation):
p.setGravity(0,0,-10)
sleep(0.01) # Time in seconds.
else:
p.stepSimulation()