diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 51c3c1d93..634004d84 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -51,6 +51,10 @@ public: { + } + + virtual ~MyDebugDrawer() + { } virtual DefaultColors getDefaultColors() const { diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index 7d628b11d..8974cf24a 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -1621,6 +1621,11 @@ static void b3CreateLookAt(const b3Vector3& eye, const b3Vector3& center,cons void GLInstancingRenderer::renderSceneInternal(int renderMode) { + if (!useShadowMap) + { + renderMode = B3_DEFAULT_RENDERMODE; + } + // glEnable(GL_DEPTH_TEST); GLint dims[4]; diff --git a/examples/RoboticsLearning/R2D2GraspExample.cpp b/examples/RoboticsLearning/R2D2GraspExample.cpp index 7cae8046d..ad14ceec5 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.cpp +++ b/examples/RoboticsLearning/R2D2GraspExample.cpp @@ -92,7 +92,7 @@ public: m_robotSim.loadSDF("kiva_shelf/model.sdf",results); } { - m_robotSim.loadURDF("results"); + m_robotSim.loadURDF("plane.urdf"); } m_robotSim.setGravity(b3MakeVector3(0,0,-10)); diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index 7fe0109d8..0a3bc706c 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -122,7 +122,8 @@ protected: { if (m_options == eCLIENTEXAMPLE_SERVER) { - m_physicsServer.renderScene(); + int renderFlags = 0; + m_physicsServer.renderScene(renderFlags); } b3DebugLines debugLines; diff --git a/examples/SharedMemory/PhysicsClientTCP.cpp b/examples/SharedMemory/PhysicsClientTCP.cpp index 4215769e1..f959325c0 100644 --- a/examples/SharedMemory/PhysicsClientTCP.cpp +++ b/examples/SharedMemory/PhysicsClientTCP.cpp @@ -226,7 +226,7 @@ bool TcpNetworkedPhysicsProcessor::receiveStatus(struct SharedMemoryStatus& serv } -void TcpNetworkedPhysicsProcessor::renderScene() +void TcpNetworkedPhysicsProcessor::renderScene(int renderFlags) { } diff --git a/examples/SharedMemory/PhysicsClientTCP.h b/examples/SharedMemory/PhysicsClientTCP.h index 12644eb68..0304e0a65 100644 --- a/examples/SharedMemory/PhysicsClientTCP.h +++ b/examples/SharedMemory/PhysicsClientTCP.h @@ -24,7 +24,7 @@ public: virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); - virtual void renderScene(); + virtual void renderScene(int renderFlags); virtual void physicsDebugDraw(int debugDrawFlags); diff --git a/examples/SharedMemory/PhysicsClientUDP.cpp b/examples/SharedMemory/PhysicsClientUDP.cpp index 7bc1a6286..f3b316723 100644 --- a/examples/SharedMemory/PhysicsClientUDP.cpp +++ b/examples/SharedMemory/PhysicsClientUDP.cpp @@ -540,7 +540,7 @@ bool UdpNetworkedPhysicsProcessor::receiveStatus(struct SharedMemoryStatus& serv } -void UdpNetworkedPhysicsProcessor::renderScene() +void UdpNetworkedPhysicsProcessor::renderScene(int renderFlags) { } diff --git a/examples/SharedMemory/PhysicsClientUDP.h b/examples/SharedMemory/PhysicsClientUDP.h index bcb4e3268..8d8d08fd1 100644 --- a/examples/SharedMemory/PhysicsClientUDP.h +++ b/examples/SharedMemory/PhysicsClientUDP.h @@ -24,7 +24,7 @@ public: virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); - virtual void renderScene(); + virtual void renderScene(int renderFlags); virtual void physicsDebugDraw(int debugDrawFlags); diff --git a/examples/SharedMemory/PhysicsCommandProcessorInterface.h b/examples/SharedMemory/PhysicsCommandProcessorInterface.h index e883b86f4..70ed2d044 100644 --- a/examples/SharedMemory/PhysicsCommandProcessorInterface.h +++ b/examples/SharedMemory/PhysicsCommandProcessorInterface.h @@ -1,6 +1,11 @@ #ifndef PHYSICS_COMMAND_PROCESSOR_INTERFACE_H #define PHYSICS_COMMAND_PROCESSOR_INTERFACE_H +enum PhysicsCOmmandRenderFlags +{ + COV_DISABLE_SYNC_RENDERING=1 +}; + class PhysicsCommandProcessorInterface { @@ -17,7 +22,7 @@ public: virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes) = 0; - virtual void renderScene() = 0; + virtual void renderScene(int renderFlags) = 0; virtual void physicsDebugDraw(int debugDrawFlags) = 0; virtual void setGuiHelper(struct GUIHelperInterface* guiHelper) = 0; virtual void setTimeOut(double timeOutInSeconds) = 0; diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index 8a5ec6c8d..e03e2d7f0 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -171,7 +171,8 @@ bool PhysicsDirect::connect(struct GUIHelperInterface* guiHelper) void PhysicsDirect::renderScene() { - m_data->m_commandProcessor->renderScene(); + int renderFlags = 0; + m_data->m_commandProcessor->renderScene(renderFlags); } void PhysicsDirect::debugDraw(int debugDrawMode) diff --git a/examples/SharedMemory/PhysicsServer.h b/examples/SharedMemory/PhysicsServer.h index e80af8193..7b75a36cf 100644 --- a/examples/SharedMemory/PhysicsServer.h +++ b/examples/SharedMemory/PhysicsServer.h @@ -33,7 +33,7 @@ public: //and for physics visualization. The idea is that physicsDebugDraw can also send wireframe //to a physics client, over shared memory virtual void physicsDebugDraw(int debugDrawFlags)=0; - virtual void renderScene()=0; + virtual void renderScene(int renderFlags)=0; virtual void enableCommandLogging(bool enable, const char* fileName)=0; virtual void replayFromLogFile(const char* fileName)=0; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 9b3c724c2..8e0945b0c 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -4216,10 +4216,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm case CMD_RESET_SIMULATION: { + BT_PROFILE("CMD_RESET_SIMULATION"); - + m_data->m_guiHelper->setVisualizerFlag(COV_ENABLE_SYNC_RENDERING_INTERNAL,0); resetSimulation(); - + m_data->m_guiHelper->setVisualizerFlag(COV_ENABLE_SYNC_RENDERING_INTERNAL,1); + SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED; hasStatus = true; @@ -5062,6 +5064,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm serverCmd.m_removeObjectArgs.m_numBodies = 0; serverCmd.m_removeObjectArgs.m_numUserConstraints = 0; + m_data->m_guiHelper->setVisualizerFlag(COV_ENABLE_SYNC_RENDERING_INTERNAL,0); + for (int i=0;im_bodyHandles.freeHandle(bodyUniqueId); } - + m_data->m_guiHelper->setVisualizerFlag(COV_ENABLE_SYNC_RENDERING_INTERNAL,1); + hasStatus = true; break; @@ -5929,11 +5934,14 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm //static int skip=1; -void PhysicsServerCommandProcessor::renderScene() +void PhysicsServerCommandProcessor::renderScene(int renderFlags) { if (m_data->m_guiHelper) { - m_data->m_guiHelper->syncPhysicsToGraphics(m_data->m_dynamicsWorld); + if (0==(renderFlags&COV_DISABLE_SYNC_RENDERING)) + { + m_data->m_guiHelper->syncPhysicsToGraphics(m_data->m_dynamicsWorld); + } m_data->m_guiHelper->render(m_data->m_dynamicsWorld); } #ifdef USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.h b/examples/SharedMemory/PhysicsServerCommandProcessor.h index 5dc0d0e64..f30d35f2c 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.h +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.h @@ -78,7 +78,7 @@ public: return false; }; - virtual void renderScene(); + virtual void renderScene(int renderFlags); virtual void physicsDebugDraw(int debugDrawFlags); virtual void setGuiHelper(struct GUIHelperInterface* guiHelper); diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 52c8e6097..f68036439 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -27,6 +27,9 @@ extern btVector3 gLastPickPos; bool gEnablePicking=true; bool gEnableTeleporting=true; +bool gEnableRendering= true; +bool gEnableSyncPhysicsRendering= true; +bool gEnableUpdateDebugDrawLines = true; btVector3 gVRTeleportPosLocal(0,0,0); btQuaternion gVRTeleportOrnLocal(0,0,0,1); @@ -183,6 +186,7 @@ enum MultiThreadedGUIHelperCommunicationEnums eGUIDumpFramesToVideo, eGUIHelperRemoveGraphicsInstance, eGUIHelperChangeGraphicsInstanceRGBAColor, + eGUIHelperSetVisualizerFlag, }; @@ -234,7 +238,8 @@ struct MyMouseCommand struct MotionArgs { MotionArgs() - :m_physicsServerPtr(0) + :m_physicsServerPtr(0), + m_debugDrawFlags(0) { for (int i=0;i m_mouseCommands; @@ -454,6 +460,15 @@ void MotionThreadFunc(void* userPtr,void* lsMemory) { args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds, args->m_sendVrControllerEvents,numSendVrControllers, keyEvents, args->m_sendKeyEvents.size()); } + { + if (gEnableUpdateDebugDrawLines) + { + args->m_csGUI->lock(); + args->m_physicsServerPtr->physicsDebugDraw(args->m_debugDrawFlags); + gEnableUpdateDebugDrawLines=false; + args->m_csGUI->unlock(); + } + } deltaTimeInSeconds = 0; } @@ -548,6 +563,138 @@ struct UserDebugText }; + struct LineSegment +{ + btVector3 m_from; + btVector3 m_to; +}; + +struct ColorWidth +{ + btVector3FloatData m_color; + int width; + int getHash() const + { + unsigned char r = (unsigned char) m_color.m_floats[0]*255; + unsigned char g = (unsigned char) m_color.m_floats[1]*255; + unsigned char b = (unsigned char) m_color.m_floats[2]*255; + unsigned char w = width; + return r+(256*g)+(256*256*b)+(256*256*256*w); + } + bool equals(const ColorWidth& other) const + { + bool same = ((width == other.width) && (m_color.m_floats[0] == other.m_color.m_floats[0]) && + (m_color.m_floats[1] == other.m_color.m_floats[1]) && + (m_color.m_floats[2] == other.m_color.m_floats[2])); + return same; + } +}; + + + +ATTRIBUTE_ALIGNED16( class )MultithreadedDebugDrawer : public btIDebugDraw +{ + class GUIHelperInterface* m_guiHelper; + int m_debugMode; + + btAlignedObjectArray< btAlignedObjectArray > m_sortedIndices; + btAlignedObjectArray< btAlignedObjectArray > m_sortedLines; + btHashMap m_hashedLines; + + + public: + void drawDebugDrawerLines() + { + if (m_hashedLines.size()) + { + for (int i=0;igetRenderInterface()->drawLines(positions,cw.m_color.m_floats,numPoints, stride, indices,numIndices,cw.width); + } + } + } + MultithreadedDebugDrawer(GUIHelperInterface* guiHelper) + :m_guiHelper(guiHelper), + m_debugMode(0) + { + } + virtual ~MultithreadedDebugDrawer() + { + } + virtual void drawLine(const btVector3& from,const btVector3& to,const btVector3& color) + { + { + ColorWidth cw; + color.serializeFloat(cw.m_color); + cw.width = 1; + int index = -1; + + int* indexPtr = m_hashedLines.find(cw); + if (indexPtr) + { + index = *indexPtr; + } else + { + index = m_sortedLines.size(); + m_sortedLines.expand(); + m_sortedIndices.expand(); + m_hashedLines.insert(cw,index); + } + btAssert(index>=0); + if (index>=0) + { + btVector3FloatData from1,toX1; + m_sortedIndices[index].push_back(m_sortedLines[index].size()); + from.serializeFloat(from1); + m_sortedLines[index].push_back(from1); + m_sortedIndices[index].push_back(m_sortedLines[index].size()); + to.serializeFloat(toX1); + m_sortedLines[index].push_back(toX1); + } + } + } + + virtual void drawContactPoint(const btVector3& PointOnB,const btVector3& normalOnB,btScalar distance,int lifeTime,const btVector3& color) + { + drawLine(PointOnB,PointOnB+normalOnB*distance,color); + btVector3 ncolor(0, 0, 0); + drawLine(PointOnB, PointOnB + normalOnB*0.01, ncolor); + } + + virtual void reportErrorWarning(const char* warningString) + { + } + virtual void draw3dText(const btVector3& location,const char* textString) + { + } + virtual void setDebugMode(int debugMode) + { + m_debugMode = debugMode; + } + + virtual int getDebugMode() const + { + return m_debugMode; + } + + virtual void clearLines() + { + m_hashedLines.clear(); + m_sortedIndices.clear(); + m_sortedLines.clear(); + } + virtual void flushLines() + { + + } +}; class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface { @@ -557,21 +704,19 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface b3CriticalSection* m_cs2; b3CriticalSection* m_cs3; b3CriticalSection* m_csGUI; - + public: - void setVisualizerFlag(int flag, int enable) - { - m_childGuiHelper->setVisualizerFlag(flag,enable); - } - - void setVisualizerFlagCallback(VisualizerFlagCallback callback) - { - m_childGuiHelper->setVisualizerFlagCallback(callback); - } - + MultithreadedDebugDrawer* m_debugDraw; + void drawDebugDrawerLines() + { + if (m_debugDraw) + { + m_debugDraw->drawDebugDrawerLines(); + } + } GUIHelperInterface* m_childGuiHelper; int m_uidGenerator; @@ -632,6 +777,7 @@ public: m_cs2(0), m_cs3(0), m_csGUI(0), + m_debugDraw(0), m_uidGenerator(0), m_texels(0), m_textureId(-1) @@ -733,7 +879,18 @@ public: virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld) { - m_childGuiHelper->createPhysicsDebugDrawer(rbWorld); + btAssert(rbWorld); + if (m_debugDraw) + { + delete m_debugDraw; + m_debugDraw = 0; + } + + m_debugDraw = new MultithreadedDebugDrawer(this); + + rbWorld->setDebugDrawer(m_debugDraw ); + + //m_childGuiHelper->createPhysicsDebugDrawer(rbWorld); } virtual int registerTexture(const unsigned char* texels, int width, int height) @@ -765,6 +922,25 @@ public: return m_shapeIndex; } + + int m_visualizerFlag; + int m_visualizerEnable; + void setVisualizerFlag(int flag, int enable) + { + m_visualizerFlag = flag; + m_visualizerEnable = enable; + + m_cs->lock(); + m_cs->setSharedParam(1,eGUIHelperSetVisualizerFlag); + workerThreadWait(); + } + + void setVisualizerFlagCallback(VisualizerFlagCallback callback) + { + m_childGuiHelper->setVisualizerFlagCallback(callback); + } + + virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) { m_shapeIndex = shapeIndex; @@ -1568,6 +1744,38 @@ void PhysicsServerExample::updateGraphics() m_multiThreadedHelper->mainThreadRelease(); break; } + + case eGUIHelperSetVisualizerFlag: + { + int flag = m_multiThreadedHelper->m_visualizerFlag; + int enable = m_multiThreadedHelper->m_visualizerEnable; + + if (flag==COV_ENABLE_VR_TELEPORTING) + { + gEnableTeleporting = enable; + } + + if (flag == COV_ENABLE_VR_PICKING) + { + gEnablePicking = enable; + } + + if (flag ==COV_ENABLE_SYNC_RENDERING_INTERNAL) + { + gEnableSyncPhysicsRendering = enable; + } + + if (flag == COV_ENABLE_RENDERING) + { + gEnableRendering = enable; + } + + m_multiThreadedHelper->m_childGuiHelper->setVisualizerFlag(m_multiThreadedHelper->m_visualizerFlag,m_multiThreadedHelper->m_visualizerEnable); + m_multiThreadedHelper->mainThreadRelease(); + break; + } + + case eGUIHelperRegisterGraphicsInstance: { m_multiThreadedHelper->m_instanceId = m_multiThreadedHelper->m_childGuiHelper->registerGraphicsInstance( @@ -1771,32 +1979,6 @@ extern double gSubStep; extern int gVRTrackingObjectUniqueId; extern btTransform gVRTrackingObjectTr; - struct LineSegment - { - btVector3 m_from; - btVector3 m_to; - }; - - struct ColorWidth - { - btVector3FloatData m_color; - int width; - int getHash() const - { - unsigned char r = (unsigned char) m_color.m_floats[0]*255; - unsigned char g = (unsigned char) m_color.m_floats[1]*255; - unsigned char b = (unsigned char) m_color.m_floats[2]*255; - unsigned char w = width; - return r+(256*g)+(256*256*b)+(256*256*256*w); - } - bool equals(const ColorWidth& other) const - { - bool same = ((width == other.width) && (m_color.m_floats[0] == other.m_color.m_floats[0]) && - (m_color.m_floats[1] == other.m_color.m_floats[1]) && - (m_color.m_floats[2] == other.m_color.m_floats[2])); - return same; - } - }; void PhysicsServerExample::drawUserDebugLines() { @@ -2023,7 +2205,15 @@ void PhysicsServerExample::renderScene() m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()-> getActiveCamera()->setVRCameraOffsetTransform(vrOffset); } - m_physicsServer.renderScene(); + if (gEnableRendering) + { + int renderFlags = 0; + if (!gEnableSyncPhysicsRendering) + { + renderFlags|=1;//COV_DISABLE_SYNC_RENDERING; + } + m_physicsServer.renderScene(renderFlags); + } if (gEnablePicking) { @@ -2071,9 +2261,18 @@ void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags) { drawUserDebugLines(); - ///debug rendering - m_physicsServer.physicsDebugDraw(debugDrawFlags); + if (gEnableRendering) + { + ///debug rendering + //m_physicsServer.physicsDebugDraw(debugDrawFlags); + m_args[0].m_csGUI->lock(); + //draw stuff and flush? + this->m_multiThreadedHelper->m_debugDraw->drawDebugDrawerLines(); + m_args[0].m_debugDrawFlags = debugDrawFlags; + gEnableUpdateDebugDrawLines = true; + m_args[0].m_csGUI->unlock(); + } } diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.cpp b/examples/SharedMemory/PhysicsServerSharedMemory.cpp index 0a9c75f3c..b145db6c6 100644 --- a/examples/SharedMemory/PhysicsServerSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsServerSharedMemory.cpp @@ -274,9 +274,9 @@ void PhysicsServerSharedMemory::processClientCommands() } } -void PhysicsServerSharedMemory::renderScene() +void PhysicsServerSharedMemory::renderScene(int renderFlags) { - m_data->m_commandProcessor->renderScene(); + m_data->m_commandProcessor->renderScene(renderFlags); diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.h b/examples/SharedMemory/PhysicsServerSharedMemory.h index c85daabe7..3e1270c51 100644 --- a/examples/SharedMemory/PhysicsServerSharedMemory.h +++ b/examples/SharedMemory/PhysicsServerSharedMemory.h @@ -42,7 +42,7 @@ public: //and for physics visualization. The idea is that physicsDebugDraw can also send wireframe //to a physics client, over shared memory void physicsDebugDraw(int debugDrawFlags); - void renderScene(); + void renderScene(int renderFlags); void enableCommandLogging(bool enable, const char* fileName); void replayFromLogFile(const char* fileName); diff --git a/examples/SharedMemory/SharedMemoryCommandProcessor.cpp b/examples/SharedMemory/SharedMemoryCommandProcessor.cpp index 90980794e..abd4879a2 100644 --- a/examples/SharedMemory/SharedMemoryCommandProcessor.cpp +++ b/examples/SharedMemory/SharedMemoryCommandProcessor.cpp @@ -183,7 +183,7 @@ bool SharedMemoryCommandProcessor::receiveStatus(struct SharedMemoryStatus& serv return false; } -void SharedMemoryCommandProcessor::renderScene() +void SharedMemoryCommandProcessor::renderScene(int renderFlags) { } diff --git a/examples/SharedMemory/SharedMemoryCommandProcessor.h b/examples/SharedMemory/SharedMemoryCommandProcessor.h index b552b7ad3..6d75b87d9 100644 --- a/examples/SharedMemory/SharedMemoryCommandProcessor.h +++ b/examples/SharedMemory/SharedMemoryCommandProcessor.h @@ -23,7 +23,7 @@ public: virtual bool receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes); - virtual void renderScene(); + virtual void renderScene(int renderFlags); virtual void physicsDebugDraw(int debugDrawFlags); virtual void setGuiHelper(struct GUIHelperInterface* guiHelper); diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index ef0590e02..25a8afc40 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -497,6 +497,9 @@ enum b3ConfigureDebugVisualizerEnum COV_ENABLE_WIREFRAME, COV_ENABLE_VR_TELEPORTING, COV_ENABLE_VR_PICKING, + COV_ENABLE_VR_RENDER_CONTROLLERS, + COV_ENABLE_RENDERING, + COV_ENABLE_SYNC_RENDERING_INTERNAL, }; enum eCONNECT_METHOD { diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index c5636f570..a430ea615 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -373,10 +373,9 @@ void MyKeyboardCallback(int key, int state) #include "../SharedMemory/SharedMemoryPublic.h" extern bool useShadowMap; -extern int gDebugDrawFlags; +bool gEnableVRRenderControllers=true; + -extern bool gEnablePicking; -extern bool gEnableTeleporting; void VRPhysicsServerVisualizerFlagCallback(int flag, bool enable) { @@ -388,24 +387,27 @@ void VRPhysicsServerVisualizerFlagCallback(int flag, bool enable) { //there is no regular GUI here, but disable the } - - if (flag==COV_ENABLE_VR_TELEPORTING) + if (flag == COV_ENABLE_VR_RENDER_CONTROLLERS) { - gEnableTeleporting = enable; + gEnableVRRenderControllers = enable; } + + - if (flag == COV_ENABLE_VR_PICKING) - { - gEnablePicking = enable; - } - if (flag == COV_ENABLE_WIREFRAME) { - gDebugDrawFlags |= btIDebugDraw::DBG_DrawWireframe; - } else - { - gDebugDrawFlags &= ~btIDebugDraw::DBG_DrawWireframe; + if (enable) + { + glPolygonMode( GL_FRONT_AND_BACK, GL_LINE ); + //gDebugDrawFlags |= btIDebugDraw::DBG_DrawWireframe; + } else + { + glPolygonMode( GL_FRONT_AND_BACK, GL_FILL); + //gDebugDrawFlags &= ~btIDebugDraw::DBG_DrawWireframe; + } } + + } //----------------------------------------------------------------------------- @@ -815,6 +817,7 @@ bool CMainApplication::HandleInput() if (button==2) { //glPolygonMode( GL_FRONT_AND_BACK, GL_LINE ); + ///todo(erwincoumans) can't use reguar debug drawer, because physics/graphics are not in sync ///so it can (and likely will) cause crashes ///add a special debug drawer that deals with this @@ -852,7 +855,6 @@ bool CMainApplication::HandleInput() if (button==2) { gDebugDrawFlags = 0; - glPolygonMode( GL_FRONT_AND_BACK, GL_FILL); } sExample->vrControllerButtonCallback(unDevice, button, 0, pos, orn); @@ -1421,6 +1423,8 @@ extern int gGraspingController; void CMainApplication::DrawControllers() { + + // don't draw controllers if somebody else has input focus if( m_pHMD->IsInputFocusCapturedByAnotherProcess() ) return; @@ -1908,39 +1912,42 @@ void CMainApplication::RenderScene( vr::Hmd_Eye nEye ) bool bIsInputCapturedByAnotherProcess = m_pHMD->IsInputFocusCapturedByAnotherProcess(); - if( !bIsInputCapturedByAnotherProcess ) + if (gEnableVRRenderControllers) { - // draw the controller axis lines - glUseProgram( m_unControllerTransformProgramID ); - glUniformMatrix4fv( m_nControllerMatrixLocation, 1, GL_FALSE, GetCurrentViewProjectionMatrix( nEye ).get() ); - glBindVertexArray( m_unControllerVAO ); - glDrawArrays( GL_LINES, 0, m_uiControllerVertcount ); - glBindVertexArray( 0 ); + if( !bIsInputCapturedByAnotherProcess ) + { + // draw the controller axis lines + glUseProgram( m_unControllerTransformProgramID ); + glUniformMatrix4fv( m_nControllerMatrixLocation, 1, GL_FALSE, GetCurrentViewProjectionMatrix( nEye ).get() ); + glBindVertexArray( m_unControllerVAO ); + glDrawArrays( GL_LINES, 0, m_uiControllerVertcount ); + glBindVertexArray( 0 ); + } + + // ----- Render Model rendering ----- + glUseProgram( m_unRenderModelProgramID ); + + for( uint32_t unTrackedDevice = 0; unTrackedDevice < vr::k_unMaxTrackedDeviceCount; unTrackedDevice++ ) + { + if( !m_rTrackedDeviceToRenderModel[ unTrackedDevice ] || !m_rbShowTrackedDevice[ unTrackedDevice ] ) + continue; + + const vr::TrackedDevicePose_t & pose = m_rTrackedDevicePose[ unTrackedDevice ]; + if( !pose.bPoseIsValid ) + continue; + + if( bIsInputCapturedByAnotherProcess && m_pHMD->GetTrackedDeviceClass( unTrackedDevice ) == vr::TrackedDeviceClass_Controller ) + continue; + + const Matrix4 & matDeviceToTracking = m_rmat4DevicePose[ unTrackedDevice ]; + Matrix4 matMVP = GetCurrentViewProjectionMatrix( nEye ) * matDeviceToTracking; + glUniformMatrix4fv( m_nRenderModelMatrixLocation, 1, GL_FALSE, matMVP.get() ); + + m_rTrackedDeviceToRenderModel[ unTrackedDevice ]->Draw(); + } } - - // ----- Render Model rendering ----- - glUseProgram( m_unRenderModelProgramID ); - - for( uint32_t unTrackedDevice = 0; unTrackedDevice < vr::k_unMaxTrackedDeviceCount; unTrackedDevice++ ) - { - if( !m_rTrackedDeviceToRenderModel[ unTrackedDevice ] || !m_rbShowTrackedDevice[ unTrackedDevice ] ) - continue; - - const vr::TrackedDevicePose_t & pose = m_rTrackedDevicePose[ unTrackedDevice ]; - if( !pose.bPoseIsValid ) - continue; - - if( bIsInputCapturedByAnotherProcess && m_pHMD->GetTrackedDeviceClass( unTrackedDevice ) == vr::TrackedDeviceClass_Controller ) - continue; - - const Matrix4 & matDeviceToTracking = m_rmat4DevicePose[ unTrackedDevice ]; - Matrix4 matMVP = GetCurrentViewProjectionMatrix( nEye ) * matDeviceToTracking; - glUniformMatrix4fv( m_nRenderModelMatrixLocation, 1, GL_FALSE, matMVP.get() ); - - m_rTrackedDeviceToRenderModel[ unTrackedDevice ]->Draw(); - } - - glUseProgram( 0 ); + glUseProgram( 0 ); + } diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 7732a1559..49b7d6df3 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -6348,6 +6348,9 @@ initpybullet(void) PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME); PyModule_AddIntConstant(m, "COV_ENABLE_VR_PICKING", COV_ENABLE_VR_PICKING); PyModule_AddIntConstant(m, "COV_ENABLE_VR_TELEPORTING", COV_ENABLE_VR_TELEPORTING); + PyModule_AddIntConstant(m, "COV_ENABLE_RENDERING", COV_ENABLE_RENDERING); + PyModule_AddIntConstant(m, "COV_ENABLE_VR_RENDER_CONTROLLERS", COV_ENABLE_VR_RENDER_CONTROLLERS); + PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER); PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL); diff --git a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp index 4c5a67689..2940f7550 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp @@ -1514,6 +1514,8 @@ void btCollisionWorld::debugDrawWorld() { if (getDebugDrawer()) { + getDebugDrawer()->clearLines(); + btIDebugDraw::DefaultColors defaultColors = getDebugDrawer()->getDefaultColors(); if ( getDebugDrawer()->getDebugMode() & btIDebugDraw::DBG_DrawContactPoints) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index 2bed4a3a7..9eacc2264 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -798,6 +798,8 @@ void btMultiBodyDynamicsWorld::debugDrawWorld() { BT_PROFILE("btMultiBodyDynamicsWorld debugDrawWorld"); + btDiscreteDynamicsWorld::debugDrawWorld(); + bool drawConstraints = false; if (getDebugDrawer()) { @@ -867,7 +869,7 @@ void btMultiBodyDynamicsWorld::debugDrawWorld() } } - btDiscreteDynamicsWorld::debugDrawWorld(); + } diff --git a/src/LinearMath/btIDebugDraw.h b/src/LinearMath/btIDebugDraw.h index a020c3f4e..936aaa896 100644 --- a/src/LinearMath/btIDebugDraw.h +++ b/src/LinearMath/btIDebugDraw.h @@ -469,6 +469,10 @@ class btIDebugDraw drawLine(transform*pt2,transform*pt3,color); } + virtual void clearLines() + { + } + virtual void flushLines() { }