Skip to content

Commit

Permalink
Merge pull request #835 from erwincoumans/master
Browse files Browse the repository at this point in the history
don't use GL_LINEAR_MIPMAP_LINEAR for shadow maps, compile issue, VR tiny UI work-in-progress
  • Loading branch information
erwincoumans authored Oct 15, 2016
2 parents 4ebc327 + da40981 commit e744890
Show file tree
Hide file tree
Showing 23 changed files with 616 additions and 83 deletions.
1 change: 0 additions & 1 deletion examples/BasicDemo/BasicExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@ subject to the following restrictions:
*/



#include "BasicExample.h"

#include "btBulletDynamicsCommon.h"
Expand Down
10 changes: 8 additions & 2 deletions examples/CommonInterfaces/CommonRigidBodyBase.h
Original file line number Diff line number Diff line change
Expand Up @@ -446,9 +446,15 @@ struct CommonRigidBodyBase : public CommonExampleInterface

virtual void renderScene()
{
m_guiHelper->syncPhysicsToGraphics(m_dynamicsWorld);
{

m_guiHelper->syncPhysicsToGraphics(m_dynamicsWorld);
}

m_guiHelper->render(m_dynamicsWorld);
{

m_guiHelper->render(m_dynamicsWorld);
}
}
};

Expand Down
8 changes: 7 additions & 1 deletion examples/ExampleBrowser/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ SET(BulletExampleBrowser_SRCS
../SharedMemory/TinyRendererVisualShapeConverter.h
../SharedMemory/IKTrajectoryHelper.cpp
../SharedMemory/IKTrajectoryHelper.h
../RenderingExamples/TinyRendererSetup.cpp

../SharedMemory/PhysicsServer.cpp
../SharedMemory/PhysicsClientSharedMemory.cpp
../SharedMemory/PhysicsClient.cpp
Expand Down Expand Up @@ -208,10 +208,16 @@ SET(BulletExampleBrowser_SRCS
../MultiThreading/b3PosixThreadSupport.cpp
../MultiThreading/b3Win32ThreadSupport.cpp
../MultiThreading/b3ThreadSupportInterface.cpp
../RenderingExamples/TinyRendererSetup.cpp
../RenderingExamples/TimeSeriesCanvas.cpp
../RenderingExamples/TimeSeriesCanvas.h
../RenderingExamples/TimeSeriesFontData.cpp
../RenderingExamples/TimeSeriesFontData.h
../RenderingExamples/DynamicTexturedCubeDemo.cpp
../RenderingExamples/DynamicTexturedCubeDemo.h
../RenderingExamples/TinyVRGui.cpp
../RenderingExamples/TinyVRGui.h

../RoboticsLearning/GripperGraspExample.cpp
../RoboticsLearning/GripperGraspExample.h
../RoboticsLearning/b3RobotSimAPI.cpp
Expand Down
5 changes: 4 additions & 1 deletion examples/ExampleBrowser/ExampleEntries.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#include "../RenderingExamples/CoordinateSystemDemo.h"
#include "../RenderingExamples/RaytracerSetup.h"
#include "../RenderingExamples/TinyRendererSetup.h"

#include "../RenderingExamples/DynamicTexturedCubeDemo.h"
#include "../ForkLift/ForkLiftDemo.h"
#include "../BasicDemo/BasicExample.h"
#include "../Planar2D/Planar2D.h"
Expand Down Expand Up @@ -290,6 +290,9 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"CoordinateSystemDemo","Show the axis and positive rotation direction around the axis.", CoordinateSystemCreateFunc),
ExampleEntry(1,"Time Series", "Render some value(s) in a 2D graph window, shifting to the left", TimeSeriesCreateFunc),
ExampleEntry(1,"TinyRenderer", "Very small software renderer.", TinyRendererCreateFunc),
ExampleEntry(1,"Dynamic Texture", "Dynamic updated textured applied to a cube.", DynamicTexturedCubeDemoCreateFunc),



//Extended Tutorials Added by Mobeen
ExampleEntry(0,"Extended Tutorials"),
Expand Down
13 changes: 9 additions & 4 deletions examples/ExampleBrowser/OpenGLExampleBrowser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1087,7 +1087,7 @@ bool OpenGLExampleBrowser::requestedExit()

void OpenGLExampleBrowser::update(float deltaTime)
{

B3_PROFILE("OpenGLExampleBrowser::update");
assert(glGetError()==GL_NO_ERROR);
s_instancingRenderer->init();
DrawGridData dg;
Expand Down Expand Up @@ -1139,9 +1139,11 @@ void OpenGLExampleBrowser::update(float deltaTime)
singleStepSimulation = false;
//printf("---------------------------------------------------\n");
//printf("Framecount = %d\n",frameCount);

B3_PROFILE("sCurrentDemo->stepSimulation");

if (gFixedTimeStep>0)
{

sCurrentDemo->stepSimulation(gFixedTimeStep);
} else
{
Expand All @@ -1167,7 +1169,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
sCurrentDemo->renderScene();
}
{

B3_PROFILE("physicsDebugDraw");
glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
sCurrentDemo->physicsDebugDraw(gDebugDrawFlags);
}
Expand All @@ -1179,6 +1181,7 @@ void OpenGLExampleBrowser::update(float deltaTime)

if (gui2 && s_guiHelper && s_guiHelper->getRenderInterface() && s_guiHelper->getRenderInterface()->getActiveCamera())
{
B3_PROFILE("setStatusBarMessage");
char msg[1024];
float camDist = s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraDistance();
float pitch = s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraPitch();
Expand All @@ -1194,6 +1197,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
static int toggle = 1;
if (renderGui)
{
B3_PROFILE("renderGui");
// if (!pauseSimulation)
// processProfileData(s_profWindow,false);

Expand All @@ -1202,7 +1206,7 @@ void OpenGLExampleBrowser::update(float deltaTime)

saveOpenGLState(s_instancingRenderer->getScreenWidth(), s_instancingRenderer->getScreenHeight());
}
BT_PROFILE("Draw Gwen GUI");

if (m_internalData->m_gui)
{
m_internalData->m_gui->draw(s_instancingRenderer->getScreenWidth(), s_instancingRenderer->getScreenHeight());
Expand Down Expand Up @@ -1237,6 +1241,7 @@ void OpenGLExampleBrowser::update(float deltaTime)

if (gui2)
{
B3_PROFILE("forceUpdateScrollBars");
gui2->forceUpdateScrollBars();
}

Expand Down
23 changes: 15 additions & 8 deletions examples/ExampleBrowser/OpenGLGuiHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -289,18 +289,25 @@ void OpenGLGuiHelper::syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWor
return;

int numCollisionObjects = rbWorld->getNumCollisionObjects();
for (int i = 0; i<numCollisionObjects; i++)
{
btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i];
btVector3 pos = colObj->getWorldTransform().getOrigin();
btQuaternion orn = colObj->getWorldTransform().getRotation();
int index = colObj->getUserIndex();
if (index >= 0)
B3_PROFILE("write all InstanceTransformToCPU");
for (int i = 0; i<numCollisionObjects; i++)
{
m_data->m_glApp->m_renderer->writeSingleInstanceTransformToCPU(pos, orn, index);
B3_PROFILE("writeSingleInstanceTransformToCPU");
btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i];
btVector3 pos = colObj->getWorldTransform().getOrigin();
btQuaternion orn = colObj->getWorldTransform().getRotation();
int index = colObj->getUserIndex();
if (index >= 0)
{
m_data->m_glApp->m_renderer->writeSingleInstanceTransformToCPU(pos, orn, index);
}
}
}
m_data->m_glApp->m_renderer->writeTransforms();
{
B3_PROFILE("writeTransforms");
m_data->m_glApp->m_renderer->writeTransforms();
}
}


Expand Down
1 change: 0 additions & 1 deletion examples/ExampleBrowser/premake4.lua
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,6 @@ project "App_BulletExampleBrowser"
"../TinyRenderer/tgaimage.cpp",
"../TinyRenderer/our_gl.cpp",
"../TinyRenderer/TinyRenderer.cpp",
"../RenderingExamples/TinyRendererSetup.cpp",
"../SharedMemory/IKTrajectoryHelper.cpp",
"../SharedMemory/IKTrajectoryHelper.h",
"../SharedMemory/PhysicsClientC_API.cpp",
Expand Down
62 changes: 53 additions & 9 deletions examples/OpenGLWindow/GLInstancingRenderer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -413,17 +413,32 @@ void GLInstancingRenderer::writeSingleInstanceTransformToGPU(float* position, fl
void GLInstancingRenderer::writeTransforms()
{

b3Assert(glGetError() ==GL_NO_ERROR);

{
B3_PROFILE("b3Assert(glGetError() 1");
b3Assert(glGetError() ==GL_NO_ERROR);
}
{
B3_PROFILE("glBindBuffer");
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
}

glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
//glFlush();
{
B3_PROFILE("glFlush()");
//without the flush, the glBufferSubData can spike to really slow (seconds slow)
glFlush();
}

b3Assert(glGetError() ==GL_NO_ERROR);
{
B3_PROFILE("b3Assert(glGetError() 2");
b3Assert(glGetError() ==GL_NO_ERROR);
}


#ifdef B3_DEBUG
{

//B3_PROFILE("m_data->m_totalNumInstances == totalNumInstances");

int totalNumInstances= 0;
for (int k=0;k<m_graphicsInstances.size();k++)
{
Expand All @@ -440,14 +455,29 @@ void GLInstancingRenderer::writeTransforms()
// int SCALE_BUFFER_SIZE = (totalNumInstances*sizeof(float)*3);

#if 1
{
// printf("m_data->m_totalNumInstances = %d\n", m_data->m_totalNumInstances);
{
B3_PROFILE("glBufferSubData pos");
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes,m_data->m_totalNumInstances*sizeof(float)*4,
&m_data->m_instance_positions_ptr[0]);
}
{
B3_PROFILE("glBufferSubData orn");
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*4,
&m_data->m_instance_quaternion_ptr[0]);
}
{
B3_PROFILE("glBufferSubData color");
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+ POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE, m_data->m_totalNumInstances*sizeof(float)*4,
&m_data->m_instance_colors_ptr[0]);
}
{
B3_PROFILE("glBufferSubData scale");
glBufferSubData( GL_ARRAY_BUFFER, m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*3,
&m_data->m_instance_scale_ptr[0]);
}
}
#else
char* orgBase = (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_READ_WRITE);
Expand Down Expand Up @@ -517,9 +547,15 @@ void GLInstancingRenderer::writeTransforms()
#endif

glBindBuffer(GL_ARRAY_BUFFER, 0);//m_data->m_vbo);
{
B3_PROFILE("glBindBuffer 2");
glBindBuffer(GL_ARRAY_BUFFER, 0);//m_data->m_vbo);
}

b3Assert(glGetError() ==GL_NO_ERROR);
{
B3_PROFILE("b3Assert(glGetError() 4");
b3Assert(glGetError() ==GL_NO_ERROR);
}

}

Expand Down Expand Up @@ -686,16 +722,24 @@ int GLInstancingRenderer::registerShape(const float* vertices, int numvertices,


glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
char* dest= (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_WRITE_ONLY);//GL_WRITE_ONLY
int vertexStrideInBytes = 9*sizeof(float);
int sz = numvertices*vertexStrideInBytes;
#if 0

char* dest= (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_WRITE_ONLY);//GL_WRITE_ONLY


#ifdef B3_DEBUG
int totalUsed = vertexStrideInBytes*gfxObj->m_vertexArrayOffset+sz;
b3Assert(totalUsed<m_data->m_maxShapeCapacityInBytes);
#endif//B3_DEBUG

memcpy(dest+vertexStrideInBytes*gfxObj->m_vertexArrayOffset,vertices,sz);
glUnmapBuffer( GL_ARRAY_BUFFER);
#else
glBufferSubData( GL_ARRAY_BUFFER,vertexStrideInBytes*gfxObj->m_vertexArrayOffset,sz,
vertices);
#endif

glGenBuffers(1, &gfxObj->m_index_vbo);

Expand Down Expand Up @@ -1465,7 +1509,7 @@ void GLInstancingRenderer::renderSceneInternal(int renderMode)
#endif//OLD_SHADOWMAP_INIT

glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR);
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);



Expand Down
6 changes: 2 additions & 4 deletions examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,9 @@ void main(void)

//float bias = 0.005f;

float bias = 0.0001*tan(acos(intensity));
bias = clamp(bias, 0,0.01);



float visibility = texture(shadowMap, vec3(ShadowCoord.xy,(ShadowCoord.z-bias)/ShadowCoord.w));
float visibility = texture(shadowMap, vec3(ShadowCoord.xy,(ShadowCoord.z)/ShadowCoord.w));

intensity = 0.7*intensity + 0.3*intensity*visibility;

Expand Down
5 changes: 2 additions & 3 deletions examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,8 @@ static const char* useShadowMapInstancingFragmentShader= \
" \n"
" //float bias = 0.005f;\n"
" \n"
" float bias = 0.0001*tan(acos(intensity));\n"
" bias = clamp(bias, 0,0.01);\n"
" float visibility = texture(shadowMap, vec3(ShadowCoord.xy,(ShadowCoord.z-bias)/ShadowCoord.w));\n"
" \n"
" float visibility = texture(shadowMap, vec3(ShadowCoord.xy,(ShadowCoord.z)/ShadowCoord.w));\n"
" \n"
" intensity = 0.7*intensity + 0.3*intensity*visibility;\n"
" \n"
Expand Down
1 change: 1 addition & 0 deletions examples/OpenGLWindow/SimpleOpenGL3App.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,6 +173,7 @@ SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, boo
b3Assert(glGetError() ==GL_NO_ERROR);

m_instancingRenderer = new GLInstancingRenderer(128*1024,128*1024*1024);

m_primRenderer = new GLPrimitiveRenderer(width,height);

m_renderer = m_instancingRenderer ;
Expand Down
Loading

0 comments on commit e744890

Please sign in to comment.