mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 13:20:07 +00:00
example how to create a video using PyBullet using GUI mode with ffmpeg, synchronizing video with stepSimulation at specific frame rate (240 Hz for example)
This commit is contained in:
parent
2336dfcb9e
commit
8f8bbbee3b
24
examples/pybullet/examples/video_sync_mp4.py
Normal file
24
examples/pybullet/examples/video_sync_mp4.py
Normal file
@ -0,0 +1,24 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
#by default, PyBullet runs at 240Hz
|
||||
p.connect(p.GUI, options="--mp4=\"test.mp4\" --mp4fps=240")
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1)
|
||||
p.loadURDF("plane.urdf")
|
||||
|
||||
#in 3 seconds, the object travels about 0.5*g*t^2 meter ~ 45 meter.
|
||||
r2d2 = p.loadURDF("r2d2.urdf",[0,0,45])
|
||||
#disable linear damping
|
||||
p.changeDynamics(r2d2,-1, linearDamping=0)
|
||||
p.setGravity(0,0,-10)
|
||||
|
||||
for i in range (3*240):
|
||||
txt = "frame "+str(i)
|
||||
item = p.addUserDebugText(txt, [0,1,0])
|
||||
p.stepSimulation()
|
||||
#synchronize the visualizer (rendering frames for the video mp4) with stepSimulation
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1)
|
||||
#print("r2d2 vel=", p.getBaseVelocity(r2d2)[0][2])
|
||||
p.removeUserDebugItem(item)
|
||||
|
||||
p.disconnect()
|
Loading…
Reference in New Issue
Block a user