add --mp4fps=30 command line parameter for ExampleBrowser (and using pybullet.connect(p.GUI, options="--mp4fps=30 --mp4=\"testvideo.mp4\"")

This commit is contained in:
Erwin Coumans
2020-01-11 12:19:42 -08:00
parent 8ebdf7862c
commit 83bdef8254
4 changed files with 22 additions and 5 deletions

View File

@@ -14,6 +14,7 @@ struct SimpleOpenGL3App : public CommonGraphicsApp
class GLPrimitiveRenderer* m_primRenderer;
class GLInstancingRenderer* m_instancingRenderer;
virtual void setBackgroundColor(float red, float green, float blue);
virtual void setMp4Fps(int fps);
SimpleOpenGL3App(const char* title, int width, int height, bool allowRetina = true, int windowType = 0, int renderDevice = -1, int maxNumObjectCapacity = 128 * 1024, int maxShapeCapacityInBytes = 128 * 1024 * 1024);