From 68b53feb9c91d5b311027277e2dd7e6c09df99b6 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Thu, 16 Jul 2015 23:58:36 -0700 Subject: [PATCH] add Inverted Pendulum example with PD control --- .../CommonGraphicsAppInterface.h | 3 + examples/ExampleBrowser/CMakeLists.txt | 2 + examples/ExampleBrowser/ExampleEntries.cpp | 8 +- examples/ExampleBrowser/premake4.lua | 1 + .../MultiBody/InvertedPendulumPDControl.cpp | 473 ++++++++++++++++++ .../MultiBody/InvertedPendulumPDControl.h | 7 + examples/OpenGLWindow/SimpleOpenGL3App.cpp | 13 +- 7 files changed, 499 insertions(+), 8 deletions(-) create mode 100644 examples/MultiBody/InvertedPendulumPDControl.cpp create mode 100644 examples/MultiBody/InvertedPendulumPDControl.h diff --git a/examples/CommonInterfaces/CommonGraphicsAppInterface.h b/examples/CommonInterfaces/CommonGraphicsAppInterface.h index f26a5f7ea..45e8ae30f 100644 --- a/examples/CommonInterfaces/CommonGraphicsAppInterface.h +++ b/examples/CommonInterfaces/CommonGraphicsAppInterface.h @@ -62,6 +62,9 @@ struct CommonGraphicsApp { } + virtual void dumpNextFrameToPng(const char* pngFilename){} + virtual void dumpFramesToVideo(const char* mp4Filename){} + virtual void drawGrid(DrawGridData data=DrawGridData()) = 0; virtual void setUpAxis(int axis) = 0; virtual int getUpAxis() const = 0; diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index 8b3ae8d10..153789cf7 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -102,6 +102,8 @@ SET(App_ExampleBrowser_SRCS ../Vehicles/Hinge2Vehicle.h ../MultiBody/TestJointTorqueSetup.cpp ../MultiBody/TestJointTorqueSetup.h + ../MultiBody/InvertedPendulumPDControl.cpp + ../MultiBody/InvertedPendulumPDControl.h ../MultiBody/MultiBodyConstraintFeedback.cpp ../MultiBody/MultiDofDemo.cpp ../MultiBody/MultiDofDemo.h diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index e191b479c..5d35aef57 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -16,12 +16,14 @@ #include "../Importers/ImportColladaDemo/ImportColladaSetup.h" #include "../Importers/ImportSTLDemo/ImportSTLSetup.h" #include "../Importers/ImportURDFDemo/ImportURDFSetup.h" + #include "../GyroscopicDemo/GyroscopicSetup.h" #include "../Constraints/Dof6Spring2Setup.h" #include "../Constraints/ConstraintPhysicsSetup.h" #include "../MultiBody/TestJointTorqueSetup.h" #include "../MultiBody/MultiBodyConstraintFeedback.h" #include "../MultiBody/MultiDofDemo.h" +#include "../MultiBody/InvertedPendulumPDControl.h" #include "../VoronoiFracture/VoronoiFractureDemo.h" #include "../SoftDemo/SoftDemo.h" #include "../Constraints/ConstraintDemo.h" @@ -96,14 +98,14 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(1,"Gyroscopic", "Show the Dzhanibekov effect using various settings of the gyroscopic term. You can select the gyroscopic term computation using btRigidBody::setFlags, with arguments BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT (using explicit integration, which adds energy and can lead to explosions), BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD, BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY. If you don't set any of these flags, there is no gyroscopic term used.", GyroscopicCreateFunc), - + ExampleEntry(0,"MultiBody"), ExampleEntry(1,"MultiDofCreateFunc","Create a basic btMultiBody with 3-DOF spherical joints (mobilizers). The demo uses a fixed base or a floating base at restart.", MultiDofCreateFunc), ExampleEntry(1,"TestJointTorque","Apply a torque to a btMultiBody with 1-DOF joints (mobilizers). This setup is similar to API/TestHingeTorque.", TestJointTorqueCreateFunc), ExampleEntry(1,"Constraint Feedback", "The example shows how to receive joint reaction forces in a btMultiBody. Also the applied impulse is available for a btMultiBodyJointMotor", MultiBodyConstraintFeedbackCreateFunc), - - + ExampleEntry(1,"Inverted Pendulum PD","Keep an inverted pendulum up using open loop PD control", InvertedPendulumPDControlCreateFunc), + #ifdef INCLUDE_CLOTH_DEMOS ExampleEntry(0,"Soft Body"), ExampleEntry(1,"Cloth","Simulate a patch of cloth.", SoftDemoCreateFunc,0), diff --git a/examples/ExampleBrowser/premake4.lua b/examples/ExampleBrowser/premake4.lua index e0843482e..34c5fcc01 100644 --- a/examples/ExampleBrowser/premake4.lua +++ b/examples/ExampleBrowser/premake4.lua @@ -77,6 +77,7 @@ "../MultiBody/MultiDofDemo.cpp", "../MultiBody/TestJointTorqueSetup.cpp", "../MultiBody/MultiBodyConstraintFeedback.cpp", + "../MultiBody/InvertedPendulumPDControl.cpp", "../ThirdPartyLibs/stb_image/*", "../ThirdPartyLibs/Wavefront/tiny_obj_loader.*", "../ThirdPartyLibs/tinyxml/*", diff --git a/examples/MultiBody/InvertedPendulumPDControl.cpp b/examples/MultiBody/InvertedPendulumPDControl.cpp new file mode 100644 index 000000000..bd8115cad --- /dev/null +++ b/examples/MultiBody/InvertedPendulumPDControl.cpp @@ -0,0 +1,473 @@ + +#include "InvertedPendulumPDControl.h" + +#include "BulletDynamics/Featherstone/btMultiBodyLinkCollider.h" +#include "BulletDynamics/Featherstone/btMultiBodyJointFeedback.h" + +#include "../CommonInterfaces/CommonMultiBodyBase.h" +#include "../Utils/b3ResourcePath.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +static btScalar radius(0.2); +static btScalar kp = 100; +static btScalar kd = 20; +static btScalar maxForce = 100; + +struct InvertedPendulumPDControl : public CommonMultiBodyBase +{ + btMultiBody* m_multiBody; + btAlignedObjectArray m_jointFeedbacks; + bool m_once; + int m_frameCount; +public: + + InvertedPendulumPDControl(struct GUIHelperInterface* helper); + virtual ~InvertedPendulumPDControl(); + + virtual void initPhysics(); + + virtual void stepSimulation(float deltaTime); + + virtual void resetCamera() + { + float dist = 5; + float pitch = 270; + float yaw = 21; + float targetPos[3]={-1.34,3.4,-0.44}; + m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); + } + + +}; + +InvertedPendulumPDControl::InvertedPendulumPDControl(struct GUIHelperInterface* helper) +:CommonMultiBodyBase(helper), +m_once(true), +m_frameCount(0) +{ +} + +InvertedPendulumPDControl::~InvertedPendulumPDControl() +{ + +} + +///this is a temporary global, until we determine if we need the option or not +extern bool gJointFeedbackInWorldSpace; +extern bool gJointFeedbackInJointFrame; + + + +void InvertedPendulumPDControl::initPhysics() +{ + { + SliderParams slider("Kp",&kp); + slider.m_minVal=-200; + slider.m_maxVal=200; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + { + SliderParams slider("Kd",&kd); + slider.m_minVal=-50; + slider.m_maxVal=50; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + { + SliderParams slider("max force",&maxForce); + slider.m_minVal=0; + slider.m_maxVal=100; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + + + + + int upAxis = 1; + gJointFeedbackInWorldSpace = true; + gJointFeedbackInJointFrame = true; + + m_guiHelper->setUpAxis(upAxis); + + btVector4 colors[4] = + { + btVector4(1,0,0,1), + btVector4(0,1,0,1), + btVector4(0,1,1,1), + btVector4(1,1,0,1), + }; + int curColor = 0; + + + + + + this->createEmptyDynamicsWorld(); + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + m_dynamicsWorld->getDebugDrawer()->setDebugMode( + //btIDebugDraw::DBG_DrawConstraints + +btIDebugDraw::DBG_DrawWireframe + +btIDebugDraw::DBG_DrawContactPoints + +btIDebugDraw::DBG_DrawAabb + );//+btIDebugDraw::DBG_DrawConstraintLimits); + + m_dynamicsWorld->setGravity(btVector3(0,-10,0)); + + { + bool floating = false; + bool damping = false; + bool gyro = false; + int numLinks = 2; + bool spherical = false; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals + bool canSleep = false; + bool selfCollide = false; + btVector3 linkHalfExtents(0.05, 0.37, 0.1); + btVector3 baseHalfExtents(0.04, 0.35, 0.08); + + btVector3 basePosition = btVector3(-0.4f, 3.f, 0.f); + //mbC->forceMultiDof(); //if !spherical, you can comment this line to check the 1DoF algorithm + //init the base + btVector3 baseInertiaDiag(0.f, 0.f, 0.f); + float baseMass = 1.f; + + if(baseMass) + { + //btCollisionShape *shape = new btSphereShape(baseHalfExtents[0]);// btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2])); + btCollisionShape *shape = new btBoxShape(btVector3(baseHalfExtents[0], baseHalfExtents[1], baseHalfExtents[2])); + shape->calculateLocalInertia(baseMass, baseInertiaDiag); + delete shape; + } + + bool isMultiDof = true; + btMultiBody *pMultiBody = new btMultiBody(numLinks, baseMass, baseInertiaDiag, !floating, canSleep, isMultiDof); + + m_multiBody = pMultiBody; + btQuaternion baseOriQuat(0.f, 0.f, 0.f, 1.f); + // baseOriQuat.setEulerZYX(-.25*SIMD_PI,0,-1.75*SIMD_PI); + pMultiBody->setBasePos(basePosition); + pMultiBody->setWorldToBaseRot(baseOriQuat); + btVector3 vel(0, 0, 0); + // pMultiBody->setBaseVel(vel); + + //init the links + btVector3 hingeJointAxis(1, 0, 0); + + //y-axis assumed up + btVector3 parentComToCurrentCom(0, -linkHalfExtents[1] * 2.f, 0); //par body's COM to cur body's COM offset + btVector3 currentPivotToCurrentCom(0, -linkHalfExtents[1], 0); //cur body's COM to cur body's PIV offset + btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset + + ////// + btScalar q0 = 1.f * SIMD_PI/ 180.f; + btQuaternion quat0(btVector3(1, 0, 0).normalized(), q0); + quat0.normalize(); + ///// + + for(int i = 0; i < numLinks; ++i) + { + float linkMass = 1.f; + //if (i==3 || i==2) + // linkMass= 1000; + btVector3 linkInertiaDiag(0.f, 0.f, 0.f); + + btCollisionShape* shape = 0; + if (i==0) + { + shape = new btBoxShape(btVector3(linkHalfExtents[0], linkHalfExtents[1], linkHalfExtents[2]));// + } else + { + shape = new btSphereShape(radius); + } + shape->calculateLocalInertia(linkMass, linkInertiaDiag); + delete shape; + + + if(!spherical) + { + //pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), hingeJointAxis, parentComToCurrentPivot, currentPivotToCurrentCom, false); + + if (i==0) + { + pMultiBody->setupRevolute(i, linkMass, linkInertiaDiag, i - 1, + btQuaternion(0.f, 0.f, 0.f, 1.f), + hingeJointAxis, + parentComToCurrentPivot, + currentPivotToCurrentCom, false); + } else + { + btVector3 parentComToCurrentCom(0, -radius * 2.f, 0); //par body's COM to cur body's COM offset + btVector3 currentPivotToCurrentCom(0, -radius, 0); //cur body's COM to cur body's PIV offset + btVector3 parentComToCurrentPivot = parentComToCurrentCom - currentPivotToCurrentCom; //par body's COM to cur body's PIV offset + + + pMultiBody->setupFixed(i, linkMass, linkInertiaDiag, i - 1, + btQuaternion(0.f, 0.f, 0.f, 1.f), + parentComToCurrentPivot, + currentPivotToCurrentCom, false); + } + + //pMultiBody->setupFixed(i,linkMass,linkInertiaDiag,i-1,btQuaternion(0,0,0,1),parentComToCurrentPivot,currentPivotToCurrentCom,false); + + } + else + { + //pMultiBody->setupPlanar(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f)/*quat0*/, btVector3(1, 0, 0), parentComToCurrentPivot*2, false); + pMultiBody->setupSpherical(i, linkMass, linkInertiaDiag, i - 1, btQuaternion(0.f, 0.f, 0.f, 1.f), parentComToCurrentPivot, currentPivotToCurrentCom, false); + } + } + + pMultiBody->finalizeMultiDof(); + + //for (int i=pMultiBody->getNumLinks()-1;i>=0;i--)// + for (int i=0;igetNumLinks();i++) + { + btMultiBodyJointFeedback* fb = new btMultiBodyJointFeedback(); + pMultiBody->getLink(i).m_jointFeedback = fb; + m_jointFeedbacks.push_back(fb); + //break; + } + btMultiBodyDynamicsWorld* world = m_dynamicsWorld; + + /// + world->addMultiBody(pMultiBody); + btMultiBody* mbC = pMultiBody; + mbC->setCanSleep(canSleep); + mbC->setHasSelfCollision(selfCollide); + mbC->setUseGyroTerm(gyro); + // + if(!damping) + { + mbC->setLinearDamping(0.f); + mbC->setAngularDamping(0.f); + }else + { mbC->setLinearDamping(0.1f); + mbC->setAngularDamping(0.9f); + } + // + + + ////////////////////////////////////////////// + if(numLinks > 0) + { + btScalar q0 = 180.f * SIMD_PI/ 180.f; + if(!spherical) + if(mbC->isMultiDof()) + mbC->setJointPosMultiDof(0, &q0); + else + mbC->setJointPos(0, q0); + else + { + btQuaternion quat0(btVector3(1, 1, 0).normalized(), q0); + quat0.normalize(); + mbC->setJointPosMultiDof(0, quat0); + } + } + /// + + btAlignedObjectArray world_to_local; + world_to_local.resize(pMultiBody->getNumLinks() + 1); + + btAlignedObjectArray local_origin; + local_origin.resize(pMultiBody->getNumLinks() + 1); + world_to_local[0] = pMultiBody->getWorldToBaseRot(); + local_origin[0] = pMultiBody->getBasePos(); + double friction = 1; + { + + // float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1}; + float quat[4]={-world_to_local[0].x(),-world_to_local[0].y(),-world_to_local[0].z(),world_to_local[0].w()}; + + + if (1) + { + btCollisionShape* shape = new btBoxShape(btVector3(baseHalfExtents[0],baseHalfExtents[1],baseHalfExtents[2]));//new btSphereShape(baseHalfExtents[0]); + m_guiHelper->createCollisionShapeGraphicsObject(shape); + + btMultiBodyLinkCollider* col= new btMultiBodyLinkCollider(pMultiBody, -1); + col->setCollisionShape(shape); + + btTransform tr; + tr.setIdentity(); +//if we don't set the initial pose of the btCollisionObject, the simulator will do this + //when syncing the btMultiBody link transforms to the btMultiBodyLinkCollider + + tr.setOrigin(local_origin[0]); + btQuaternion orn(btVector3(0,0,1),0.25*3.1415926538); + + tr.setRotation(orn); + col->setWorldTransform(tr); + + bool isDynamic = (baseMass > 0 && floating); + short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter); + short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter); + + + world->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);//, 2,1+2); + + btVector3 color(0.0,0.0,0.5); + m_guiHelper->createCollisionObjectGraphicsObject(col,color); + +// col->setFriction(friction); + pMultiBody->setBaseCollider(col); + + } + } + + + for (int i=0; i < pMultiBody->getNumLinks(); ++i) + { + const int parent = pMultiBody->getParent(i); + world_to_local[i+1] = pMultiBody->getParentToLocalRot(i) * world_to_local[parent+1]; + local_origin[i+1] = local_origin[parent+1] + (quatRotate(world_to_local[i+1].inverse() , pMultiBody->getRVector(i))); + } + + + for (int i=0; i < pMultiBody->getNumLinks(); ++i) + { + + btVector3 posr = local_origin[i+1]; + // float pos[4]={posr.x(),posr.y(),posr.z(),1}; + + float quat[4]={-world_to_local[i+1].x(),-world_to_local[i+1].y(),-world_to_local[i+1].z(),world_to_local[i+1].w()}; + btCollisionShape* shape =0; + + if (i==0) + { + shape = new btBoxShape(btVector3(linkHalfExtents[0],linkHalfExtents[1],linkHalfExtents[2]));//btSphereShape(linkHalfExtents[0]); + } else + { + + shape = new btSphereShape(radius); + } + + m_guiHelper->createCollisionShapeGraphicsObject(shape); + btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i); + + col->setCollisionShape(shape); + btTransform tr; + tr.setIdentity(); + tr.setOrigin(posr); + tr.setRotation(btQuaternion(quat[0],quat[1],quat[2],quat[3])); + col->setWorldTransform(tr); + // col->setFriction(friction); + bool isDynamic = 1;//(linkMass > 0); + short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter); + short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter); + + //if (i==0||i>numLinks-2) + { + world->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);//,2,1+2); + btVector4 color = colors[curColor]; + curColor++; + curColor&=3; + m_guiHelper->createCollisionObjectGraphicsObject(col,color); + + + pMultiBody->getLink(i).m_collider=col; + } + + } + } + + +} +char fileName[1024]; + +static btAlignedObjectArray qDesiredArray; +void InvertedPendulumPDControl::stepSimulation(float deltaTime) +{ + + static btScalar offset = -0.1*SIMD_PI; + + m_frameCount++; + if ((m_frameCount&0xff)==0 ) + { + offset = -offset; + } + btScalar target= SIMD_PI+offset; + qDesiredArray.resize(0); + qDesiredArray.resize(m_multiBody->getNumLinks(),target); + + for (int joint = 0; jointgetNumLinks();joint++) + { + int dof1 = 0; + btScalar qActual = m_multiBody->getJointPosMultiDof(joint)[dof1]; + btScalar qdActual = m_multiBody->getJointVelMultiDof(joint)[dof1]; + // b3Printf("Joint Pos[%d]=%f, Vel = %f\n", joint, qActual, qdActual); + + btScalar positionError = (qDesiredArray[joint]-qActual); + + btScalar force = kp * positionError - kd*qdActual; + btClamp(force,-maxForce,maxForce); + + // b3Printf("force = %f positionError = %f, qDesired = %f\n", force,positionError, target); + m_multiBody->addJointTorque(joint, force); + + //btScalar torque = m_multiBody->getJointTorque(0); + // b3Printf("t = %f,%f,%f\n",torque,torque,torque);//[0],torque[1],torque[2]); + + } + + + + + if (m_frameCount==100) + { + const char* gPngFileName = "pendulum"; + + + if (gPngFileName) + { + + + //printf("gPngFileName=%s\n",gPngFileName); + + sprintf(fileName,"%s%d.png",gPngFileName,m_frameCount); + b3Printf("Made screenshot %s",fileName); + this->m_guiHelper->getAppInterface()->dumpNextFrameToPng(fileName); + } + } + m_dynamicsWorld->stepSimulation(1./240,0); + + static int count = 0; + if ((count& 0x0f)==0) + { +#if 0 + for (int i=0;im_reactionForces.m_topVec[0], + m_jointFeedbacks[i]->m_reactionForces.m_topVec[1], + m_jointFeedbacks[i]->m_reactionForces.m_topVec[2], + + m_jointFeedbacks[i]->m_reactionForces.m_bottomVec[0], + m_jointFeedbacks[i]->m_reactionForces.m_bottomVec[1], + m_jointFeedbacks[i]->m_reactionForces.m_bottomVec[2] + + ); + + } +#endif + } + count++; + + + /* + b3Printf("base angvel = %f,%f,%f",m_multiBody->getBaseOmega()[0], + m_multiBody->getBaseOmega()[1], + m_multiBody->getBaseOmega()[2] + ); + */ + btScalar jointVel =m_multiBody->getJointVel(0); + +// b3Printf("child angvel = %f",jointVel); + + + +} + + +class CommonExampleInterface* InvertedPendulumPDControlCreateFunc(struct CommonExampleOptions& options) +{ + return new InvertedPendulumPDControl(options.m_guiHelper); +} diff --git a/examples/MultiBody/InvertedPendulumPDControl.h b/examples/MultiBody/InvertedPendulumPDControl.h new file mode 100644 index 000000000..ae28abafa --- /dev/null +++ b/examples/MultiBody/InvertedPendulumPDControl.h @@ -0,0 +1,7 @@ +#ifndef INVERTED_PENDULUM_PD_CONTROL_H +#define INVERTED_PENDULUM_PD_CONTROL_H + +class CommonExampleInterface* InvertedPendulumPDControlCreateFunc(struct CommonExampleOptions& options); + +#endif //INVERTED_PENDULUM_PD_CONTROL_H + diff --git a/examples/OpenGLWindow/SimpleOpenGL3App.cpp b/examples/OpenGLWindow/SimpleOpenGL3App.cpp index 81466bec4..498bb6c99 100644 --- a/examples/OpenGLWindow/SimpleOpenGL3App.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL3App.cpp @@ -695,7 +695,7 @@ void SimpleOpenGL3App::swapBuffer() //m_data->m_renderTexture->disable(); //if (m_data->m_ffmpegFile==0) //{ - // m_data->m_frameDumpPngFileName = 0; + m_data->m_frameDumpPngFileName = 0; //} } m_window->startRendering(); @@ -727,9 +727,12 @@ void SimpleOpenGL3App::dumpFramesToVideo(const char* mp4FileName) { pclose(m_data->m_ffmpegFile); } - m_data->m_ffmpegFile = popen(cmd, "w"); + if (mp4FileName) + { + m_data->m_ffmpegFile = popen(cmd, "w"); - m_data->m_frameDumpPngFileName = mp4FileName; + m_data->m_frameDumpPngFileName = mp4FileName; + } } void SimpleOpenGL3App::dumpNextFrameToPng(const char* filename) { @@ -739,7 +742,7 @@ void SimpleOpenGL3App::dumpNextFrameToPng(const char* filename) m_data->m_frameDumpPngFileName = filename; //you could use m_renderTexture to allow to render at higher resolutions, such as 4k or so - /*if (!m_data->m_renderTexture) + if (!m_data->m_renderTexture) { m_data->m_renderTexture = new GLRenderToTexture(); GLuint renderTextureId; @@ -764,7 +767,7 @@ void SimpleOpenGL3App::dumpNextFrameToPng(const char* filename) } bool result = m_data->m_renderTexture->enable(); -*/ + } void SimpleOpenGL3App::setUpAxis(int axis)