Skip to content

Commit e744890

Browse files
authored
Merge pull request #835 from erwincoumans/master
don't use GL_LINEAR_MIPMAP_LINEAR for shadow maps, compile issue, VR tiny UI work-in-progress
2 parents 4ebc327 + da40981 commit e744890

23 files changed

+616
-83
lines changed

examples/BasicDemo/BasicExample.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,6 @@ subject to the following restrictions:
1414
*/
1515

1616

17-
1817
#include "BasicExample.h"
1918

2019
#include "btBulletDynamicsCommon.h"

examples/CommonInterfaces/CommonRigidBodyBase.h

+8-2
Original file line numberDiff line numberDiff line change
@@ -446,9 +446,15 @@ struct CommonRigidBodyBase : public CommonExampleInterface
446446

447447
virtual void renderScene()
448448
{
449-
m_guiHelper->syncPhysicsToGraphics(m_dynamicsWorld);
449+
{
450+
451+
m_guiHelper->syncPhysicsToGraphics(m_dynamicsWorld);
452+
}
450453

451-
m_guiHelper->render(m_dynamicsWorld);
454+
{
455+
456+
m_guiHelper->render(m_dynamicsWorld);
457+
}
452458
}
453459
};
454460

examples/ExampleBrowser/CMakeLists.txt

+7-1
Original file line numberDiff line numberDiff line change
@@ -131,7 +131,7 @@ SET(BulletExampleBrowser_SRCS
131131
../SharedMemory/TinyRendererVisualShapeConverter.h
132132
../SharedMemory/IKTrajectoryHelper.cpp
133133
../SharedMemory/IKTrajectoryHelper.h
134-
../RenderingExamples/TinyRendererSetup.cpp
134+
135135
../SharedMemory/PhysicsServer.cpp
136136
../SharedMemory/PhysicsClientSharedMemory.cpp
137137
../SharedMemory/PhysicsClient.cpp
@@ -208,10 +208,16 @@ SET(BulletExampleBrowser_SRCS
208208
../MultiThreading/b3PosixThreadSupport.cpp
209209
../MultiThreading/b3Win32ThreadSupport.cpp
210210
../MultiThreading/b3ThreadSupportInterface.cpp
211+
../RenderingExamples/TinyRendererSetup.cpp
211212
../RenderingExamples/TimeSeriesCanvas.cpp
212213
../RenderingExamples/TimeSeriesCanvas.h
213214
../RenderingExamples/TimeSeriesFontData.cpp
214215
../RenderingExamples/TimeSeriesFontData.h
216+
../RenderingExamples/DynamicTexturedCubeDemo.cpp
217+
../RenderingExamples/DynamicTexturedCubeDemo.h
218+
../RenderingExamples/TinyVRGui.cpp
219+
../RenderingExamples/TinyVRGui.h
220+
215221
../RoboticsLearning/GripperGraspExample.cpp
216222
../RoboticsLearning/GripperGraspExample.h
217223
../RoboticsLearning/b3RobotSimAPI.cpp

examples/ExampleBrowser/ExampleEntries.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
#include "../RenderingExamples/CoordinateSystemDemo.h"
77
#include "../RenderingExamples/RaytracerSetup.h"
88
#include "../RenderingExamples/TinyRendererSetup.h"
9-
9+
#include "../RenderingExamples/DynamicTexturedCubeDemo.h"
1010
#include "../ForkLift/ForkLiftDemo.h"
1111
#include "../BasicDemo/BasicExample.h"
1212
#include "../Planar2D/Planar2D.h"
@@ -290,6 +290,9 @@ static ExampleEntry gDefaultExamples[]=
290290
ExampleEntry(1,"CoordinateSystemDemo","Show the axis and positive rotation direction around the axis.", CoordinateSystemCreateFunc),
291291
ExampleEntry(1,"Time Series", "Render some value(s) in a 2D graph window, shifting to the left", TimeSeriesCreateFunc),
292292
ExampleEntry(1,"TinyRenderer", "Very small software renderer.", TinyRendererCreateFunc),
293+
ExampleEntry(1,"Dynamic Texture", "Dynamic updated textured applied to a cube.", DynamicTexturedCubeDemoCreateFunc),
294+
295+
293296

294297
//Extended Tutorials Added by Mobeen
295298
ExampleEntry(0,"Extended Tutorials"),

examples/ExampleBrowser/OpenGLExampleBrowser.cpp

+9-4
Original file line numberDiff line numberDiff line change
@@ -1087,7 +1087,7 @@ bool OpenGLExampleBrowser::requestedExit()
10871087

10881088
void OpenGLExampleBrowser::update(float deltaTime)
10891089
{
1090-
1090+
B3_PROFILE("OpenGLExampleBrowser::update");
10911091
assert(glGetError()==GL_NO_ERROR);
10921092
s_instancingRenderer->init();
10931093
DrawGridData dg;
@@ -1139,9 +1139,11 @@ void OpenGLExampleBrowser::update(float deltaTime)
11391139
singleStepSimulation = false;
11401140
//printf("---------------------------------------------------\n");
11411141
//printf("Framecount = %d\n",frameCount);
1142-
1142+
B3_PROFILE("sCurrentDemo->stepSimulation");
1143+
11431144
if (gFixedTimeStep>0)
11441145
{
1146+
11451147
sCurrentDemo->stepSimulation(gFixedTimeStep);
11461148
} else
11471149
{
@@ -1167,7 +1169,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
11671169
sCurrentDemo->renderScene();
11681170
}
11691171
{
1170-
1172+
B3_PROFILE("physicsDebugDraw");
11711173
glPolygonMode( GL_FRONT_AND_BACK, GL_FILL );
11721174
sCurrentDemo->physicsDebugDraw(gDebugDrawFlags);
11731175
}
@@ -1179,6 +1181,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
11791181

11801182
if (gui2 && s_guiHelper && s_guiHelper->getRenderInterface() && s_guiHelper->getRenderInterface()->getActiveCamera())
11811183
{
1184+
B3_PROFILE("setStatusBarMessage");
11821185
char msg[1024];
11831186
float camDist = s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraDistance();
11841187
float pitch = s_guiHelper->getRenderInterface()->getActiveCamera()->getCameraPitch();
@@ -1194,6 +1197,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
11941197
static int toggle = 1;
11951198
if (renderGui)
11961199
{
1200+
B3_PROFILE("renderGui");
11971201
// if (!pauseSimulation)
11981202
// processProfileData(s_profWindow,false);
11991203

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

12031207
saveOpenGLState(s_instancingRenderer->getScreenWidth(), s_instancingRenderer->getScreenHeight());
12041208
}
1205-
BT_PROFILE("Draw Gwen GUI");
1209+
12061210
if (m_internalData->m_gui)
12071211
{
12081212
m_internalData->m_gui->draw(s_instancingRenderer->getScreenWidth(), s_instancingRenderer->getScreenHeight());
@@ -1237,6 +1241,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
12371241

12381242
if (gui2)
12391243
{
1244+
B3_PROFILE("forceUpdateScrollBars");
12401245
gui2->forceUpdateScrollBars();
12411246
}
12421247

examples/ExampleBrowser/OpenGLGuiHelper.cpp

+15-8
Original file line numberDiff line numberDiff line change
@@ -289,18 +289,25 @@ void OpenGLGuiHelper::syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWor
289289
return;
290290

291291
int numCollisionObjects = rbWorld->getNumCollisionObjects();
292-
for (int i = 0; i<numCollisionObjects; i++)
293292
{
294-
btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i];
295-
btVector3 pos = colObj->getWorldTransform().getOrigin();
296-
btQuaternion orn = colObj->getWorldTransform().getRotation();
297-
int index = colObj->getUserIndex();
298-
if (index >= 0)
293+
B3_PROFILE("write all InstanceTransformToCPU");
294+
for (int i = 0; i<numCollisionObjects; i++)
299295
{
300-
m_data->m_glApp->m_renderer->writeSingleInstanceTransformToCPU(pos, orn, index);
296+
B3_PROFILE("writeSingleInstanceTransformToCPU");
297+
btCollisionObject* colObj = rbWorld->getCollisionObjectArray()[i];
298+
btVector3 pos = colObj->getWorldTransform().getOrigin();
299+
btQuaternion orn = colObj->getWorldTransform().getRotation();
300+
int index = colObj->getUserIndex();
301+
if (index >= 0)
302+
{
303+
m_data->m_glApp->m_renderer->writeSingleInstanceTransformToCPU(pos, orn, index);
304+
}
301305
}
302306
}
303-
m_data->m_glApp->m_renderer->writeTransforms();
307+
{
308+
B3_PROFILE("writeTransforms");
309+
m_data->m_glApp->m_renderer->writeTransforms();
310+
}
304311
}
305312

306313

examples/ExampleBrowser/premake4.lua

-1
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,6 @@ project "App_BulletExampleBrowser"
5454
"../TinyRenderer/tgaimage.cpp",
5555
"../TinyRenderer/our_gl.cpp",
5656
"../TinyRenderer/TinyRenderer.cpp",
57-
"../RenderingExamples/TinyRendererSetup.cpp",
5857
"../SharedMemory/IKTrajectoryHelper.cpp",
5958
"../SharedMemory/IKTrajectoryHelper.h",
6059
"../SharedMemory/PhysicsClientC_API.cpp",

examples/OpenGLWindow/GLInstancingRenderer.cpp

+53-9
Original file line numberDiff line numberDiff line change
@@ -413,17 +413,32 @@ void GLInstancingRenderer::writeSingleInstanceTransformToGPU(float* position, fl
413413
void GLInstancingRenderer::writeTransforms()
414414
{
415415

416-
b3Assert(glGetError() ==GL_NO_ERROR);
417-
416+
{
417+
B3_PROFILE("b3Assert(glGetError() 1");
418+
b3Assert(glGetError() ==GL_NO_ERROR);
419+
}
420+
{
421+
B3_PROFILE("glBindBuffer");
422+
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
423+
}
418424

419-
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
420-
//glFlush();
425+
{
426+
B3_PROFILE("glFlush()");
427+
//without the flush, the glBufferSubData can spike to really slow (seconds slow)
428+
glFlush();
429+
}
421430

422-
b3Assert(glGetError() ==GL_NO_ERROR);
431+
{
432+
B3_PROFILE("b3Assert(glGetError() 2");
433+
b3Assert(glGetError() ==GL_NO_ERROR);
434+
}
423435

424436

425437
#ifdef B3_DEBUG
426438
{
439+
440+
//B3_PROFILE("m_data->m_totalNumInstances == totalNumInstances");
441+
427442
int totalNumInstances= 0;
428443
for (int k=0;k<m_graphicsInstances.size();k++)
429444
{
@@ -440,14 +455,29 @@ void GLInstancingRenderer::writeTransforms()
440455
// int SCALE_BUFFER_SIZE = (totalNumInstances*sizeof(float)*3);
441456

442457
#if 1
458+
{
459+
// printf("m_data->m_totalNumInstances = %d\n", m_data->m_totalNumInstances);
460+
{
461+
B3_PROFILE("glBufferSubData pos");
443462
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes,m_data->m_totalNumInstances*sizeof(float)*4,
444463
&m_data->m_instance_positions_ptr[0]);
464+
}
465+
{
466+
B3_PROFILE("glBufferSubData orn");
445467
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*4,
446468
&m_data->m_instance_quaternion_ptr[0]);
469+
}
470+
{
471+
B3_PROFILE("glBufferSubData color");
447472
glBufferSubData( GL_ARRAY_BUFFER,m_data->m_maxShapeCapacityInBytes+ POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE, m_data->m_totalNumInstances*sizeof(float)*4,
448473
&m_data->m_instance_colors_ptr[0]);
474+
}
475+
{
476+
B3_PROFILE("glBufferSubData scale");
449477
glBufferSubData( GL_ARRAY_BUFFER, m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE,m_data->m_totalNumInstances*sizeof(float)*3,
450478
&m_data->m_instance_scale_ptr[0]);
479+
}
480+
}
451481
#else
452482
453483
char* orgBase = (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_READ_WRITE);
@@ -517,9 +547,15 @@ void GLInstancingRenderer::writeTransforms()
517547
518548
#endif
519549

520-
glBindBuffer(GL_ARRAY_BUFFER, 0);//m_data->m_vbo);
550+
{
551+
B3_PROFILE("glBindBuffer 2");
552+
glBindBuffer(GL_ARRAY_BUFFER, 0);//m_data->m_vbo);
553+
}
521554

522-
b3Assert(glGetError() ==GL_NO_ERROR);
555+
{
556+
B3_PROFILE("b3Assert(glGetError() 4");
557+
b3Assert(glGetError() ==GL_NO_ERROR);
558+
}
523559

524560
}
525561

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

687723

688724
glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo);
689-
char* dest= (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_WRITE_ONLY);//GL_WRITE_ONLY
690725
int vertexStrideInBytes = 9*sizeof(float);
691726
int sz = numvertices*vertexStrideInBytes;
727+
#if 0
728+
729+
char* dest= (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_WRITE_ONLY);//GL_WRITE_ONLY
730+
731+
692732
#ifdef B3_DEBUG
693733
int totalUsed = vertexStrideInBytes*gfxObj->m_vertexArrayOffset+sz;
694734
b3Assert(totalUsed<m_data->m_maxShapeCapacityInBytes);
695735
#endif//B3_DEBUG
696736

697737
memcpy(dest+vertexStrideInBytes*gfxObj->m_vertexArrayOffset,vertices,sz);
698738
glUnmapBuffer( GL_ARRAY_BUFFER);
739+
#else
740+
glBufferSubData( GL_ARRAY_BUFFER,vertexStrideInBytes*gfxObj->m_vertexArrayOffset,sz,
741+
vertices);
742+
#endif
699743

700744
glGenBuffers(1, &gfxObj->m_index_vbo);
701745

@@ -1465,7 +1509,7 @@ void GLInstancingRenderer::renderSceneInternal(int renderMode)
14651509
#endif//OLD_SHADOWMAP_INIT
14661510

14671511
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
1468-
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR);
1512+
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
14691513

14701514

14711515

examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl

+2-4
Original file line numberDiff line numberDiff line change
@@ -36,11 +36,9 @@ void main(void)
3636

3737
//float bias = 0.005f;
3838

39-
float bias = 0.0001*tan(acos(intensity));
40-
bias = clamp(bias, 0,0.01);
41-
39+
4240

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

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

examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h

+2-3
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,8 @@ static const char* useShadowMapInstancingFragmentShader= \
3030
" \n"
3131
" //float bias = 0.005f;\n"
3232
" \n"
33-
" float bias = 0.0001*tan(acos(intensity));\n"
34-
" bias = clamp(bias, 0,0.01);\n"
35-
" float visibility = texture(shadowMap, vec3(ShadowCoord.xy,(ShadowCoord.z-bias)/ShadowCoord.w));\n"
33+
" \n"
34+
" float visibility = texture(shadowMap, vec3(ShadowCoord.xy,(ShadowCoord.z)/ShadowCoord.w));\n"
3635
" \n"
3736
" intensity = 0.7*intensity + 0.3*intensity*visibility;\n"
3837
" \n"

examples/OpenGLWindow/SimpleOpenGL3App.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -173,6 +173,7 @@ SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, boo
173173
b3Assert(glGetError() ==GL_NO_ERROR);
174174

175175
m_instancingRenderer = new GLInstancingRenderer(128*1024,128*1024*1024);
176+
176177
m_primRenderer = new GLPrimitiveRenderer(width,height);
177178

178179
m_renderer = m_instancingRenderer ;

0 commit comments

Comments
 (0)