Implemented specular reflective lighting for OpenGL 3.x, everything looks shiny (will add APIs to make it less shiny ;-)

Remove roof from kitchens/1.sdf, otherwise shadows and shinyness won't work (light is outside the room, bouncing against roof-top)
Make kuka_iiwa/model.urdf more smooth, use .obj for per-vertex normals (using Blender, import STL, export OBJ, enable triangles, normals and Z-UP, Y forward)
This commit is contained in:
Erwin Coumans
2017-05-31 20:32:45 -07:00
parent 83f910711a
commit 3157093125
8 changed files with 174 additions and 76 deletions

View File

@@ -4291,45 +4291,7 @@
</visual>
</link>
</model>
<model name='part110.obj'>
<static>1</static>
<pose frame=''>-12.0 -13.9 0 0 0 0</pose>
<link name='link_d110'>
<inertial>
<mass>0</mass>
<inertia>
<ixx>0.166667</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.166667</iyy>
<iyz>0</iyz>
<izz>0.166667</izz>
</inertia>
</inertial>
<collision concave='yes' name='collision_110'>
<geometry>
<mesh>
<scale>.1 .1 .1</scale>
<uri>fatihrmutfak/part110.obj</uri>
</mesh>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<mesh>
<scale>.1 .1 .1</scale>
<uri>fatihrmutfak/part110.obj</uri>
</mesh>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1.000000 1.000000 1.000000 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<emissive>0 0 0 0</emissive>
</material>
</visual>
</link>
</model>
<model name='part111.obj'>
<static>1</static>
<pose frame=''>-12.0 -13.9 0 0 0 0</pose>

View File

@@ -70,7 +70,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/link_0.stl"/>
<mesh filename="meshes/link_0.obj"/>
</geometry>
<material name="Grey"/>
</visual>
@@ -99,7 +99,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/link_1.stl"/>
<mesh filename="meshes/link_1.obj"/>
</geometry>
<material name="Blue"/>
</visual>
@@ -128,7 +128,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/link_2.stl"/>
<mesh filename="meshes/link_2.obj"/>
</geometry>
<material name="Blue"/>
</visual>
@@ -157,7 +157,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/link_3.stl"/>
<mesh filename="meshes/link_3.obj"/>
</geometry>
<material name="Orange"/>
</visual>
@@ -186,7 +186,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/link_4.stl"/>
<mesh filename="meshes/link_4.obj"/>
</geometry>
<material name="Blue"/>
</visual>
@@ -215,7 +215,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/link_5.stl"/>
<mesh filename="meshes/link_5.obj"/>
</geometry>
<material name="Blue"/>
</visual>
@@ -244,7 +244,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/link_6.stl"/>
<mesh filename="meshes/link_6.obj"/>
</geometry>
<material name="Orange"/>
</visual>
@@ -273,7 +273,7 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/link_7.stl"/>
<mesh filename="meshes/link_7.obj"/>
</geometry>
<material name="Grey"/>
</visual>

View File

@@ -129,6 +129,8 @@ struct b3GraphicsInstance
int m_instanceOffset;
int m_vertexArrayOffset;
int m_primitiveType;
float m_materialShinyNess;
b3Vector3 m_materialSpecularColor;
b3GraphicsInstance()
:m_cube_vao(-1),
@@ -139,7 +141,9 @@ struct b3GraphicsInstance
m_numGraphicsInstances(0),
m_instanceOffset(0),
m_vertexArrayOffset(0),
m_primitiveType(B3_GL_TRIANGLES)
m_primitiveType(B3_GL_TRIANGLES),
m_materialShinyNess(81),
m_materialSpecularColor(b3MakeVector3(1,1,1))
{
}
@@ -204,8 +208,10 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData
GLfloat m_projectionMatrix[16];
GLfloat m_viewMatrix[16];
GLfloat m_viewMatrixInverse[16];
b3Vector3 m_lightPos;
b3Vector3 m_lightSpecularIntensity;
GLuint m_defaultTexturehandle;
b3AlignedObjectArray<InternalTextureHandle> m_textureHandles;
@@ -226,12 +232,14 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData
m_renderFrameBuffer(0)
{
m_lightPos=b3MakeVector3(-50,30,40);
m_lightSpecularIntensity.setValue(1,1,1);
//clear to zero to make it obvious if the matrix is used uninitialized
for (int i=0;i<16;i++)
{
m_projectionMatrix[i]=0;
m_viewMatrix[i]=0;
m_viewMatrixInverse[i]=0;
}
}
@@ -280,9 +288,14 @@ GLuint linesVertexArrayObject=0;
GLuint linesIndexVbo = 0;
static GLint useShadow_ViewMatrixInverse=0;
static GLint useShadow_ModelViewMatrix=0;
static GLint useShadow_lightSpecularIntensity = 0;
static GLint useShadow_materialSpecularColor = 0;
static GLint useShadow_MVP=0;
static GLint useShadow_lightDirIn=0;
static GLint useShadow_lightPosIn=0;
static GLint useShadow_cameraPositionIn = 0;
static GLint useShadow_materialShininessIn = 0;
static GLint useShadow_ProjectionMatrix=0;
static GLint useShadow_DepthBiasModelViewMatrix=0;
@@ -1103,13 +1116,18 @@ void GLInstancingRenderer::InitShaders()
glLinkProgram(useShadowMapInstancingShader);
glUseProgram(useShadowMapInstancingShader);
useShadow_ViewMatrixInverse = glGetUniformLocation(useShadowMapInstancingShader, "ViewMatrixInverse");
useShadow_ModelViewMatrix = glGetUniformLocation(useShadowMapInstancingShader, "ModelViewMatrix");
useShadow_lightSpecularIntensity = glGetUniformLocation(useShadowMapInstancingShader, "lightSpecularIntensityIn");
useShadow_materialSpecularColor = glGetUniformLocation(useShadowMapInstancingShader, "materialSpecularColorIn");
useShadow_MVP = glGetUniformLocation(useShadowMapInstancingShader, "MVP");
useShadow_ProjectionMatrix = glGetUniformLocation(useShadowMapInstancingShader, "ProjectionMatrix");
useShadow_DepthBiasModelViewMatrix = glGetUniformLocation(useShadowMapInstancingShader, "DepthBiasModelViewProjectionMatrix");
useShadow_uniform_texture_diffuse = glGetUniformLocation(useShadowMapInstancingShader, "Diffuse");
useShadow_shadowMap = glGetUniformLocation(useShadowMapInstancingShader,"shadowMap");
useShadow_lightDirIn = glGetUniformLocation(useShadowMapInstancingShader,"lightDirIn");
useShadow_lightPosIn = glGetUniformLocation(useShadowMapInstancingShader,"lightPosIn");
useShadow_cameraPositionIn = glGetUniformLocation(useShadowMapInstancingShader,"cameraPositionIn");
useShadow_materialShininessIn = glGetUniformLocation(useShadowMapInstancingShader,"materialShininessIn");
createShadowMapInstancingShader = gltLoadShaderPair(createShadowMapInstancingVertexShader,createShadowMapInstancingFragmentShader);
glLinkProgram(createShadowMapInstancingShader);
@@ -1276,6 +1294,15 @@ void GLInstancingRenderer::setActiveCamera(CommonCameraInterface* cam)
m_data->m_activeCamera = cam;
}
void GLInstancingRenderer::setLightSpecularIntensity(const float lightSpecularIntensity[3])
{
m_data->m_lightSpecularIntensity[0] = lightSpecularIntensity[0];
m_data->m_lightSpecularIntensity[1] = lightSpecularIntensity[1];
m_data->m_lightSpecularIntensity[2] = lightSpecularIntensity[2];
}
void GLInstancingRenderer::setLightPosition(const float lightPos[3])
{
m_data->m_lightPos[0] = lightPos[0];
@@ -1302,6 +1329,21 @@ void GLInstancingRenderer::updateCamera(int upAxis)
m_data->m_defaultCamera1.update();
m_data->m_activeCamera->getCameraProjectionMatrix(m_data->m_projectionMatrix);
m_data->m_activeCamera->getCameraViewMatrix(m_data->m_viewMatrix);
b3Scalar viewMat[16];
b3Scalar viewMatInverse[16];
for (int i=0;i<16;i++)
{
viewMat[i] = m_data->m_viewMatrix[i];
}
b3Transform tr;
tr.setFromOpenGLMatrix(viewMat);
tr = tr.inverse();
tr.getOpenGLMatrix(viewMatInverse);
for (int i=0;i<16;i++)
{
m_data->m_viewMatrixInverse[i]=viewMatInverse[i];
}
}
@@ -2131,12 +2173,24 @@ b3Assert(glGetError() ==GL_NO_ERROR);
glUseProgram(useShadowMapInstancingShader);
glUniformMatrix4fv(useShadow_ProjectionMatrix, 1, false, &m_data->m_projectionMatrix[0]);
glUniformMatrix4fv(useShadow_ModelViewMatrix, 1, false, &m_data->m_viewMatrix[0]);
glUniformMatrix4fv(useShadow_ViewMatrixInverse, 1, false, &m_data->m_viewMatrixInverse[0]);
glUniformMatrix4fv(useShadow_ModelViewMatrix, 1, false, &m_data->m_viewMatrix[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];
b3Matrix4x4Mul16(m_data->m_projectionMatrix,m_data->m_viewMatrix,MVP);
glUniformMatrix4fv(useShadow_MVP, 1, false, &MVP[0]);
b3Vector3 gLightDir = m_data->m_lightPos;
gLightDir.normalize();
glUniform3f(useShadow_lightDirIn,gLightDir[0],gLightDir[1],gLightDir[2]);
//gLightDir.normalize();
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, &depthBiasMVP[0][0]);
glActiveTexture(GL_TEXTURE1);
glBindTexture(GL_TEXTURE_2D, m_data->m_shadowTexture);

View File

@@ -124,6 +124,7 @@ public:
virtual void setLightPosition(const float lightPos[3]);
virtual void setLightPosition(const double lightPos[3]);
void setLightSpecularIntensity(const float lightSpecularIntensity[3]);
virtual void resize(int width, int height);
virtual int getScreenWidth()

View File

@@ -13,9 +13,14 @@ in Vert
uniform sampler2D Diffuse;
uniform sampler2DShadow shadowMap;
uniform mat4 ViewMatrixInverse;
in vec3 lightDir,normal,ambient;
in vec3 lightPos,cameraPosition, normal,ambient;
in vec4 ShadowCoord;
in vec4 vertexPos;
in float materialShininess;
in vec3 lightSpecularIntensity;
in vec3 materialSpecularColor;
out vec4 color;
@@ -28,8 +33,11 @@ void main(void)
float intensity,at,af;
if (fragment.color.w==0)
discard;
vec3 lightDir = normalize(lightPos);
intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 );
vec3 normalDir = normalize(normal);
intensity = 0.5+0.5*clamp( dot( normalDir,lightDir ), -1,1 );
af = 1.0;
@@ -38,6 +46,23 @@ void main(void)
//float bias = 0.005f;
vec3 specularReflection;
if (dot(normalDir, lightDir) < 0.0)
{
specularReflection = vec3(0.0, 0.0, 0.0);
}
else // light source on the right side
{
vec3 surfaceToLight = normalize(lightPos - vertexPos.xyz);
vec3 surfaceToCamera = normalize(cameraPosition - vertexPos.xyz);
float specularCoefficient = 0.0;
specularCoefficient = pow(max(0.0, dot(surfaceToCamera, reflect(-surfaceToLight, normalDir))), materialShininess);
specularReflection = specularCoefficient * materialSpecularColor * lightSpecularIntensity;
}
float visibility = texture(shadowMap, vec3(ShadowCoord.xy,(ShadowCoord.z)/ShadowCoord.w));
@@ -46,6 +71,6 @@ void main(void)
intensity = 0.7*intensity + 0.3*intensity*visibility;
cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient;
cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient+specularReflection*visibility;
color = vec4(ct * cf, fragment.color.w);
}

View File

@@ -12,8 +12,13 @@ static const char* useShadowMapInstancingFragmentShader= \
"} vert;\n"
"uniform sampler2D Diffuse;\n"
"uniform sampler2DShadow shadowMap;\n"
"in vec3 lightDir,normal,ambient;\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"
"in vec3 materialSpecularColor;\n"
"out vec4 color;\n"
"void main(void)\n"
"{\n"
@@ -22,7 +27,11 @@ static const char* useShadowMapInstancingFragmentShader= \
" float intensity,at,af;\n"
" if (fragment.color.w==0)\n"
" discard;\n"
" intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 );\n"
" vec3 lightDir = normalize(lightPos);\n"
" \n"
" vec3 normalDir = normalize(normal);\n"
" \n"
" intensity = 0.5+0.5*clamp( dot( normalDir,lightDir ), -1,1 );\n"
" \n"
" af = 1.0;\n"
" \n"
@@ -31,13 +40,30 @@ static const char* useShadowMapInstancingFragmentShader= \
" \n"
" //float bias = 0.005f;\n"
" \n"
" vec3 specularReflection;\n"
" \n"
" if (dot(normalDir, lightDir) < 0.0) \n"
" {\n"
" specularReflection = vec3(0.0, 0.0, 0.0);\n"
" }\n"
" else // light source on the right side\n"
" {\n"
" vec3 surfaceToLight = normalize(lightPos - vertexPos.xyz);\n"
" vec3 surfaceToCamera = normalize(cameraPosition - vertexPos.xyz);\n"
" \n"
" \n"
" float specularCoefficient = 0.0;\n"
" specularCoefficient = pow(max(0.0, dot(surfaceToCamera, reflect(-surfaceToLight, normalDir))), materialShininess);\n"
" specularReflection = specularCoefficient * materialSpecularColor * lightSpecularIntensity;\n"
" \n"
" }\n"
" \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;\n"
" cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient+specularReflection*visibility;\n"
" color = vec4(ct * cf, fragment.color.w);\n"
"}\n"
;

View File

@@ -15,7 +15,12 @@ uniform mat4 ModelViewMatrix;
uniform mat4 ProjectionMatrix;
uniform mat4 DepthBiasModelViewProjectionMatrix;
uniform mat4 MVP;
uniform vec3 lightDirIn;
uniform vec3 lightPosIn;
uniform vec3 cameraPositionIn;
uniform mat4 ViewMatrixInverse;
uniform float materialShininessIn;
uniform vec3 lightSpecularIntensityIn;
uniform vec3 materialSpecularColorIn;
out vec4 ShadowCoord;
@@ -60,7 +65,13 @@ vec4 quatRotate ( in vec4 p, in vec4 q )
return quatMul ( temp, vec4 ( -q.x, -q.y, -q.z, q.w ) );
}
out vec3 lightDir,normal,ambient;
out vec3 lightPos,normal,ambient;
out vec4 vertexPos;
out vec3 cameraPosition;
out float materialShininess;
out vec3 lightSpecularIntensity;
out vec3 materialSpecularColor;
void main(void)
{
@@ -69,15 +80,19 @@ void main(void)
vec4 worldNormal = (quatRotate3( vertexnormal,q));
normal = normalize(worldNormal).xyz;
lightDir = lightDirIn;
normal = worldNormal.xyz;
lightPos = lightPosIn;
cameraPosition = cameraPositionIn;
materialShininess = materialShininessIn;
lightSpecularIntensity = lightSpecularIntensityIn;
materialSpecularColor = materialSpecularColorIn;
vec4 localcoord = quatRotate3( position.xyz*instance_scale,q);
vec4 vertexPos = MVP* vec4((instance_position+localcoord).xyz,1);
vertexPos = vec4((instance_position+localcoord).xyz,1);
gl_Position = vertexPos;
vec4 vertexLoc = MVP* vec4((instance_position+localcoord).xyz,1);
gl_Position = vertexLoc;
ShadowCoord = DepthBiasModelViewProjectionMatrix * vec4((instance_position+localcoord).xyz,1);
fragment.color = instance_color;

View File

@@ -13,7 +13,12 @@ static const char* useShadowMapInstancingVertexShader= \
"uniform mat4 ProjectionMatrix;\n"
"uniform mat4 DepthBiasModelViewProjectionMatrix;\n"
"uniform mat4 MVP;\n"
"uniform vec3 lightDirIn;\n"
"uniform vec3 lightPosIn;\n"
"uniform vec3 cameraPositionIn;\n"
"uniform mat4 ViewMatrixInverse;\n"
"uniform float materialShininessIn;\n"
"uniform vec3 lightSpecularIntensityIn;\n"
"uniform vec3 materialSpecularColorIn;\n"
"out vec4 ShadowCoord;\n"
"out Fragment\n"
"{\n"
@@ -51,7 +56,12 @@ static const char* useShadowMapInstancingVertexShader= \
" vec4 temp = quatMul ( q, p );\n"
" return quatMul ( temp, vec4 ( -q.x, -q.y, -q.z, q.w ) );\n"
"}\n"
"out vec3 lightDir,normal,ambient;\n"
"out vec3 lightPos,normal,ambient;\n"
"out vec4 vertexPos;\n"
"out vec3 cameraPosition;\n"
"out float materialShininess;\n"
"out vec3 lightSpecularIntensity;\n"
"out vec3 materialSpecularColor;\n"
"void main(void)\n"
"{\n"
" vec4 q = instance_quaternion;\n"
@@ -59,13 +69,18 @@ static const char* useShadowMapInstancingVertexShader= \
" \n"
" vec4 worldNormal = (quatRotate3( vertexnormal,q));\n"
" \n"
" normal = normalize(worldNormal).xyz;\n"
" lightDir = lightDirIn;\n"
" \n"
" normal = worldNormal.xyz;\n"
" lightPos = lightPosIn;\n"
" cameraPosition = cameraPositionIn;\n"
" materialShininess = materialShininessIn;\n"
" lightSpecularIntensity = lightSpecularIntensityIn;\n"
" materialSpecularColor = materialSpecularColorIn;\n"
" \n"
" vec4 localcoord = quatRotate3( position.xyz*instance_scale,q);\n"
" vec4 vertexPos = MVP* vec4((instance_position+localcoord).xyz,1);\n"
" gl_Position = vertexPos;\n"
" vertexPos = vec4((instance_position+localcoord).xyz,1);\n"
" \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"
" vert.texcoord = uvcoords;\n"