Merge remote-tracking branch 'upstream/master'

This commit is contained in:
yunfeibai
2017-06-02 18:26:04 -07:00
126 changed files with 111577 additions and 2758 deletions

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(41),
m_materialSpecularColor(b3MakeVector3(.5,.5,.5))
{
}
@@ -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;
@@ -225,13 +231,15 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData
m_shadowTexture(0),
m_renderFrameBuffer(0)
{
m_lightPos=b3MakeVector3(-50,50,50);
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;
@@ -296,7 +309,7 @@ static GLint ProjectionMatrix=0;
static GLint regularLightDirIn=0;
static GLint uniform_texture_diffuse = 0;
static GLint uniform_texture_diffuse = 0;
static GLint screenWidthPointSprite=0;
static GLint ModelViewMatrixPointSprite=0;
@@ -400,11 +413,15 @@ bool GLInstancingRenderer::readSingleInstanceTransformToCPU(float* position, flo
return false;
}
void GLInstancingRenderer::writeSingleInstanceTransformToCPU(const float* position, const float* orientation, int bodyUniqueId)
void GLInstancingRenderer::writeSingleInstanceTransformToCPU(const float* position, const float* orientation, int srcIndex2)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
b3Assert(pg);
if (pg==0)
return;
int srcIndex = pg->m_internalInstanceIndex;
b3Assert(srcIndex<m_data->m_totalNumInstances);
@@ -422,9 +439,9 @@ void GLInstancingRenderer::writeSingleInstanceTransformToCPU(const float* positi
}
void GLInstancingRenderer::readSingleInstanceTransformFromCPU(int bodyUniqueId, float* position, float* orientation)
void GLInstancingRenderer::readSingleInstanceTransformFromCPU(int srcIndex2, float* position, float* orientation)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
b3Assert(pg);
int srcIndex = pg->m_internalInstanceIndex;
@@ -440,9 +457,9 @@ void GLInstancingRenderer::readSingleInstanceTransformFromCPU(int bodyUniqueId,
orientation[2] = m_data->m_instance_quaternion_ptr[srcIndex*4+2];
orientation[3] = m_data->m_instance_quaternion_ptr[srcIndex*4+3];
}
void GLInstancingRenderer::writeSingleInstanceColorToCPU(const double* color, int bodyUniqueId)
void GLInstancingRenderer::writeSingleInstanceColorToCPU(const double* color, int srcIndex2)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
b3Assert(pg);
int srcIndex = pg->m_internalInstanceIndex;
@@ -452,9 +469,9 @@ void GLInstancingRenderer::writeSingleInstanceColorToCPU(const double* color, in
m_data->m_instance_colors_ptr[srcIndex*4+3]=float(color[3]);
}
void GLInstancingRenderer::writeSingleInstanceColorToCPU(const float* color, int bodyUniqueId)
void GLInstancingRenderer::writeSingleInstanceColorToCPU(const float* color, int srcIndex2)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
b3Assert(pg);
int srcIndex = pg->m_internalInstanceIndex;
@@ -464,9 +481,9 @@ void GLInstancingRenderer::writeSingleInstanceColorToCPU(const float* color, int
m_data->m_instance_colors_ptr[srcIndex*4+3]=color[3];
}
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const float* scale, int bodyUniqueId)
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const float* scale, int srcIndex2)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
b3Assert(pg);
int srcIndex = pg->m_internalInstanceIndex;
@@ -475,9 +492,63 @@ void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const float* scale, int
m_data->m_instance_scale_ptr[srcIndex*3+2]=scale[2];
}
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const double* scale, int bodyUniqueId)
void GLInstancingRenderer::writeSingleInstanceSpecularColorToCPU(const double* specular, int srcIndex2)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
b3Assert(pg);
int graphicsIndex = pg->m_internalInstanceIndex;
int totalNumInstances = 0;
int gfxObjIndex = -1;
for (int i=0;i<m_graphicsInstances.size();i++)
{
totalNumInstances+=m_graphicsInstances[i]->m_numGraphicsInstances;
if (srcIndex2<totalNumInstances)
{
gfxObjIndex = i;
break;
}
}
if (gfxObjIndex>0)
{
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[0] = specular[0];
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[1] = specular[1];
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[2] = specular[2];
}
}
void GLInstancingRenderer::writeSingleInstanceSpecularColorToCPU(const float* specular, int srcIndex2)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
b3Assert(pg);
int srcIndex = pg->m_internalInstanceIndex;
int totalNumInstances = 0;
int gfxObjIndex = -1;
for (int i=0;i<m_graphicsInstances.size();i++)
{
totalNumInstances+=m_graphicsInstances[i]->m_numGraphicsInstances;
if (srcIndex2<totalNumInstances)
{
gfxObjIndex = i;
break;
}
}
if (gfxObjIndex>0)
{
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[0] = specular[0];
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[1] = specular[1];
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[2] = specular[2];
}
}
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const double* scale, int srcIndex2)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
b3Assert(pg);
int srcIndex = pg->m_internalInstanceIndex;
@@ -694,8 +765,8 @@ void GLInstancingRenderer::rebuildGraphicsInstances()
for (int i=0;i<usedObjects.size();i++)
{
int bodyUniqueId = usedObjects[i];
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
int srcIndex2 = usedObjects[i];
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
b3Assert(pg);
int srcIndex = pg->m_internalInstanceIndex;
@@ -722,9 +793,9 @@ void GLInstancingRenderer::rebuildGraphicsInstances()
}
for (int i=0;i<usedObjects.size();i++)
{
int bodyUniqueId = usedObjects[i];
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
m_graphicsInstances[pg->m_shapeIndex]->m_tempObjectUids.push_back(bodyUniqueId);
int srcIndex2 = usedObjects[i];
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(srcIndex2);
m_graphicsInstances[pg->m_shapeIndex]->m_tempObjectUids.push_back(srcIndex2);
}
int curOffset = 0;
@@ -1099,13 +1170,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);
@@ -1272,6 +1348,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];
@@ -1298,6 +1383,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];
}
}
@@ -2127,12 +2227,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

@@ -95,6 +95,7 @@ public:
}
virtual void readSingleInstanceTransformFromCPU(int srcIndex, float* position, float* orientation);
virtual void writeSingleInstanceTransformToGPU(float* position, float* orientation, int srcIndex);
@@ -102,6 +103,9 @@ public:
virtual void writeSingleInstanceColorToCPU(const float* color, int srcIndex);
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
virtual void writeSingleInstanceSpecularColorToCPU(const double* specular, int srcIndex2);
virtual void writeSingleInstanceSpecularColorToCPU(const float* specular, int srcIndex2);
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
@@ -124,6 +128,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

@@ -1,10 +1,10 @@
#ifndef NO_OPENGL3
#include "GLPrimitiveRenderer.h"
#include "GLPrimInternalData.h"
//#include "Bullet3Common/b3Logging.h"
#include "Bullet3Common/b3Scalar.h"
#include "LoadShader.h"
#include <assert.h>
static const char* vertexShader3D= \
"#version 150 \n"
@@ -75,27 +75,27 @@ m_screenHeight(screenHeight)
m_data->m_viewmatUniform = glGetUniformLocation(m_data->m_shaderProg,"viewMatrix");
if (m_data->m_viewmatUniform < 0) {
assert(0);
b3Assert(0);
}
m_data->m_projMatUniform = glGetUniformLocation(m_data->m_shaderProg,"projMatrix");
if (m_data->m_projMatUniform < 0) {
assert(0);
b3Assert(0);
}
m_data->m_positionUniform = glGetUniformLocation(m_data->m_shaderProg, "p");
if (m_data->m_positionUniform < 0) {
assert(0);
b3Assert(0);
}
m_data->m_colourAttribute = glGetAttribLocation(m_data->m_shaderProg, "colour");
if (m_data->m_colourAttribute < 0) {
assert(0);
b3Assert(0);
}
m_data->m_positionAttribute = glGetAttribLocation(m_data->m_shaderProg, "position");
if (m_data->m_positionAttribute < 0) {
assert(0);
b3Assert(0);
}
m_data->m_textureAttribute = glGetAttribLocation(m_data->m_shaderProg,"texuv");
if (m_data->m_textureAttribute < 0) {
assert(0);
b3Assert(0);
}
loadBufferData();
@@ -127,7 +127,7 @@ void GLPrimitiveRenderer::loadBufferData()
glBufferData(GL_ARRAY_BUFFER, MAX_VERTICES2 * sizeof(PrimVertex), 0, GL_DYNAMIC_DRAW);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
@@ -153,14 +153,14 @@ void GLPrimitiveRenderer::loadBufferData()
glEnableVertexAttribArray(m_data->m_positionAttribute);
glEnableVertexAttribArray(m_data->m_colourAttribute);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glEnableVertexAttribArray(m_data->m_textureAttribute);
glVertexAttribPointer(m_data->m_positionAttribute, 4, GL_FLOAT, GL_FALSE, sizeof(PrimVertex), (const GLvoid *)0);
glVertexAttribPointer(m_data->m_colourAttribute , 4, GL_FLOAT, GL_FALSE, sizeof(PrimVertex), (const GLvoid *)sizeof(PrimVec4));
glVertexAttribPointer(m_data->m_textureAttribute , 2, GL_FLOAT, GL_FALSE, sizeof(PrimVertex), (const GLvoid *)(sizeof(PrimVec4)+sizeof(PrimVec4)));
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
@@ -200,7 +200,7 @@ void GLPrimitiveRenderer::loadBufferData()
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, 256,256,0,GL_RGB,GL_UNSIGNED_BYTE,image);
glGenerateMipmap(GL_TEXTURE_2D);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
delete[] image;
@@ -226,14 +226,14 @@ void GLPrimitiveRenderer::drawLine()
void GLPrimitiveRenderer::drawRect(float x0, float y0, float x1, float y1, float color[4])
{
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glActiveTexture(GL_TEXTURE0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindTexture(GL_TEXTURE_2D,m_data->m_texturehandle);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
drawTexturedRect(x0,y0,x1,y1,color,0,0,1,1);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
}
@@ -242,7 +242,7 @@ void GLPrimitiveRenderer::drawTexturedRect3D(const PrimVertex& v0,const PrimVert
{
//B3_PROFILE("GLPrimitiveRenderer::drawTexturedRect3D");
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glUseProgram(m_data->m_shaderProg);
@@ -250,7 +250,7 @@ void GLPrimitiveRenderer::drawTexturedRect3D(const PrimVertex& v0,const PrimVert
glUniformMatrix4fv(m_data->m_viewmatUniform, 1, false, viewMat);
glUniformMatrix4fv(m_data->m_projMatUniform, 1, false, projMat);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vertexBuffer);
glBindVertexArray(m_data->m_vertexArrayObject);
@@ -277,7 +277,7 @@ void GLPrimitiveRenderer::drawTexturedRect3D(const PrimVertex& v0,const PrimVert
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
PrimVec2 p( 0.f,0.f);//?b?0.5f * sinf(timeValue), 0.5f * cosf(timeValue) );
if (useRGBA)
@@ -290,47 +290,47 @@ void GLPrimitiveRenderer::drawTexturedRect3D(const PrimVertex& v0,const PrimVert
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glEnableVertexAttribArray(m_data->m_positionAttribute);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glEnableVertexAttribArray(m_data->m_colourAttribute);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glEnableVertexAttribArray(m_data->m_textureAttribute);
glVertexAttribPointer(m_data->m_positionAttribute, 4, GL_FLOAT, GL_FALSE, sizeof(PrimVertex), (const GLvoid *)0);
glVertexAttribPointer(m_data->m_colourAttribute , 4, GL_FLOAT, GL_FALSE, sizeof(PrimVertex), (const GLvoid *)sizeof(PrimVec4));
glVertexAttribPointer(m_data->m_textureAttribute , 2, GL_FLOAT, GL_FALSE, sizeof(PrimVertex), (const GLvoid *)(sizeof(PrimVec4)+sizeof(PrimVec4)));
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, m_data->m_indexBuffer);
//glDrawArrays(GL_TRIANGLE_FAN, 0, 4);
int indexCount = 6;
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glDrawElements(GL_TRIANGLES, indexCount, GL_UNSIGNED_INT, 0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindVertexArray(0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindBuffer(GL_ARRAY_BUFFER, 0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
//glDisableVertexAttribArray(m_data->m_textureAttribute);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glUseProgram(0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
}
@@ -349,7 +349,7 @@ void GLPrimitiveRenderer::drawTexturedRect3D2( PrimVertex* vertices, int numVert
}
//B3_PROFILE("GLPrimitiveRenderer::drawTexturedRect3D");
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
float identity[16]={1,0,0,0,
0,1,0,0,
0,0,1,0,
@@ -360,7 +360,7 @@ void GLPrimitiveRenderer::drawTexturedRect3D2( PrimVertex* vertices, int numVert
glUniformMatrix4fv(m_data->m_viewmatUniform, 1, false, identity);
glUniformMatrix4fv(m_data->m_projMatUniform, 1, false, identity);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vertexBuffer2);
glBindVertexArray(m_data->m_vertexArrayObject2);
@@ -388,7 +388,7 @@ void GLPrimitiveRenderer::drawTexturedRect3D2( PrimVertex* vertices, int numVert
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
PrimVec2 p( 0.f,0.f);//?b?0.5f * sinf(timeValue), 0.5f * cosf(timeValue) );
if (useRGBA)
@@ -401,47 +401,47 @@ void GLPrimitiveRenderer::drawTexturedRect3D2( PrimVertex* vertices, int numVert
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glEnableVertexAttribArray(m_data->m_positionAttribute);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glEnableVertexAttribArray(m_data->m_colourAttribute);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glEnableVertexAttribArray(m_data->m_textureAttribute);
glVertexAttribPointer(m_data->m_positionAttribute, 4, GL_FLOAT, GL_FALSE, sizeof(PrimVertex), (const GLvoid *)0);
glVertexAttribPointer(m_data->m_colourAttribute , 4, GL_FLOAT, GL_FALSE, sizeof(PrimVertex), (const GLvoid *)sizeof(PrimVec4));
glVertexAttribPointer(m_data->m_textureAttribute , 2, GL_FLOAT, GL_FALSE, sizeof(PrimVertex), (const GLvoid *)(sizeof(PrimVec4)+sizeof(PrimVec4)));
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, m_data->m_indexBuffer2);
//glDrawArrays(GL_TRIANGLE_FAN, 0, 4);
int indexCount = (numVertices/4)*6;
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glDrawElements(GL_TRIANGLES, indexCount, GL_UNSIGNED_INT, 0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindVertexArray(0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindBuffer(GL_ARRAY_BUFFER, 0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
//glDisableVertexAttribArray(m_data->m_textureAttribute);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glUseProgram(0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
}
@@ -477,7 +477,7 @@ void GLPrimitiveRenderer::flushBatchedRects()
return;
glActiveTexture(GL_TEXTURE0);
assert(glGetError()==GL_NO_ERROR);
b3Assert(glGetError()==GL_NO_ERROR);
glBindTexture(GL_TEXTURE_2D,m_data->m_texturehandle);
drawTexturedRect3D2(m_data2->m_verticesRect, m_data2->m_numVerticesRect,0);
m_data2->m_numVerticesRect=0;

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;
intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 );
vec3 lightDir = normalize(lightPos);
vec3 normalDir = normalize(normal);
intensity = 0.5+0.5*clamp( dot( normalDir,lightDir ), -1,1 );
af = 1.0;
@@ -38,7 +46,24 @@ 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));
if (intensity<0.5)
@@ -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;
normal = worldNormal.xyz;
lightDir = lightDirIn;
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);
gl_Position = vertexPos;
vertexPos = vec4((instance_position+localcoord).xyz,1);
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"

View File

@@ -415,3 +415,13 @@ float SimpleCamera::getCameraFrustumNear() const
{
return m_data->m_frustumZNear;
}
void SimpleCamera::setCameraFrustumFar(float far)
{
m_data->m_frustumZFar = far;
}
void SimpleCamera::setCameraFrustumNear(float near)
{
m_data->m_frustumZNear = near;
}

View File

@@ -54,6 +54,9 @@ struct SimpleCamera : public CommonCameraInterface
virtual float getCameraFrustumFar() const;
virtual float getCameraFrustumNear() const;
virtual void setCameraFrustumFar(float far);
virtual void setCameraFrustumNear(float near);
};
#endif //SIMPLE_CAMERA_H

View File

@@ -39,6 +39,9 @@ public:
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
virtual void writeSingleInstanceSpecularColorToCPU(const double* specular, int srcIndex){}
virtual void writeSingleInstanceSpecularColorToCPU(const float* specular, int srcIndex){}
virtual void getCameraViewMatrix(float viewMat[16]) const;
virtual void getCameraProjectionMatrix(float projMat[16]) const;
virtual void drawTexturedTriangleMesh(float worldPosition[3], float worldOrientation[4], const float* vertices, int numvertices, const unsigned int* indices, int numIndices, float color[4], int textureIndex=-1, int vertexLayout=0)