fix loadpanda video generation
remove duplicate code (formerly Windows ffpmeg needed different settings?)
This commit is contained in:
@@ -1106,27 +1106,11 @@ void SimpleOpenGL3App::dumpFramesToVideo(const char* mp4FileName)
|
|||||||
int height = (int)m_window->getRetinaScale() * m_instancingRenderer->getScreenHeight();
|
int height = (int)m_window->getRetinaScale() * m_instancingRenderer->getScreenHeight();
|
||||||
char cmd[8192];
|
char cmd[8192];
|
||||||
|
|
||||||
#ifdef _WIN32
|
|
||||||
sprintf(cmd,
|
sprintf(cmd,
|
||||||
"ffmpeg -r %d -f rawvideo -pix_fmt rgba -s %dx%d -i - "
|
"ffmpeg -r %d -f rawvideo -pix_fmt rgba -s %dx%d -i - "
|
||||||
"-threads 0 -y -b:v 50000k -c:v libx264 -preset slow -crf 22 -an -pix_fmt yuv420p -vf vflip %s",
|
"-threads 0 -y -b:v 50000k -c:v libx264 -preset slow -crf 22 -an -pix_fmt yuv420p -vf vflip %s",
|
||||||
m_data->m_mp4Fps, width, height, mp4FileName);
|
m_data->m_mp4Fps, width, height, mp4FileName);
|
||||||
|
|
||||||
//sprintf(cmd, "ffmpeg -r %d -f rawvideo -pix_fmt rgba -s %dx%d -i - "
|
|
||||||
// "-y -crf 0 -b:v 1500000 -an -vcodec h264 -vf vflip %s", m_data->m_mp4Fps, width, height, mp4FileName);
|
|
||||||
#else
|
|
||||||
|
|
||||||
sprintf(cmd,
|
|
||||||
"ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - "
|
|
||||||
"-threads 0 -y -b 50000k -c:v libx264 -preset slow -crf 22 -an -pix_fmt yuv420p -vf vflip %s",
|
|
||||||
width, height, mp4FileName);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//sprintf(cmd,"ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - "
|
|
||||||
// "-threads 0 -y -crf 0 -b 50000k -vf vflip %s",width,height,mp4FileName);
|
|
||||||
|
|
||||||
// sprintf(cmd,"ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - "
|
|
||||||
// "-threads 0 -preset fast -y -crf 21 -vf vflip %s",width,height,mp4FileName);
|
|
||||||
|
|
||||||
if (m_data->m_ffmpegFile)
|
if (m_data->m_ffmpegFile)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -7,23 +7,26 @@ import pybullet_robots.panda.panda_sim_grasp as panda_sim
|
|||||||
|
|
||||||
#video requires ffmpeg available in path
|
#video requires ffmpeg available in path
|
||||||
createVideo=False
|
createVideo=False
|
||||||
|
fps=240.
|
||||||
|
timeStep = 1./fps
|
||||||
|
|
||||||
if createVideo:
|
if createVideo:
|
||||||
p.connect(p.GUI, options="--mp4=\"pybullet_grasp.mp4\", --mp4fps=240")
|
p.connect(p.GUI, options="--minGraphicsUpdateTimeMs=0 --mp4=\"pybullet_grasp.mp4\" --mp4fps="+str(fps) )
|
||||||
else:
|
else:
|
||||||
p.connect(p.GUI)
|
p.connect(p.GUI)
|
||||||
|
|
||||||
p.configureDebugVisualizer(p.COV_ENABLE_Y_AXIS_UP,1)
|
p.configureDebugVisualizer(p.COV_ENABLE_Y_AXIS_UP,1)
|
||||||
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
|
||||||
|
p.setPhysicsEngineParameter(maxNumCmdPer1ms=1000)
|
||||||
p.resetDebugVisualizerCamera(cameraDistance=1.3, cameraYaw=38, cameraPitch=-22, cameraTargetPosition=[0.35,-0.13,0])
|
p.resetDebugVisualizerCamera(cameraDistance=1.3, cameraYaw=38, cameraPitch=-22, cameraTargetPosition=[0.35,-0.13,0])
|
||||||
p.setAdditionalSearchPath(pd.getDataPath())
|
p.setAdditionalSearchPath(pd.getDataPath())
|
||||||
|
|
||||||
timeStep=1./120.#240.
|
|
||||||
p.setTimeStep(timeStep)
|
p.setTimeStep(timeStep)
|
||||||
p.setGravity(0,-9.8,0)
|
p.setGravity(0,-9.8,0)
|
||||||
|
|
||||||
panda = panda_sim.PandaSimAuto(p,[0,0,0])
|
panda = panda_sim.PandaSimAuto(p,[0,0,0])
|
||||||
|
panda.control_dt = timeStep
|
||||||
|
|
||||||
logId = panda.bullet_client.startStateLogging(panda.bullet_client.STATE_LOGGING_PROFILE_TIMINGS, "log.json")
|
logId = panda.bullet_client.startStateLogging(panda.bullet_client.STATE_LOGGING_PROFILE_TIMINGS, "log.json")
|
||||||
panda.bullet_client.submitProfileTiming("start")
|
panda.bullet_client.submitProfileTiming("start")
|
||||||
for i in range (100000):
|
for i in range (100000):
|
||||||
@@ -32,6 +35,7 @@ for i in range (100000):
|
|||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
if createVideo:
|
if createVideo:
|
||||||
p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1)
|
p.configureDebugVisualizer(p.COV_ENABLE_SINGLE_STEP_RENDERING,1)
|
||||||
|
if not createVideo:
|
||||||
time.sleep(timeStep)
|
time.sleep(timeStep)
|
||||||
panda.bullet_client.submitProfileTiming()
|
panda.bullet_client.submitProfileTiming()
|
||||||
panda.bullet_client.submitProfileTiming()
|
panda.bullet_client.submitProfileTiming()
|
||||||
|
|||||||
@@ -39,7 +39,7 @@ class PandaSim(object):
|
|||||||
self.panda = self.bullet_client.loadURDF("franka_panda/panda.urdf", np.array([0,0,0])+self.offset, orn, useFixedBase=True, flags=flags)
|
self.panda = self.bullet_client.loadURDF("franka_panda/panda.urdf", np.array([0,0,0])+self.offset, orn, useFixedBase=True, flags=flags)
|
||||||
index = 0
|
index = 0
|
||||||
self.state = 0
|
self.state = 0
|
||||||
self.control_dt = 1./120.
|
self.control_dt = 1./240.
|
||||||
self.finger_target = 0
|
self.finger_target = 0
|
||||||
self.gripper_height = 0.2
|
self.gripper_height = 0.2
|
||||||
#create a constraint to keep the fingers centered
|
#create a constraint to keep the fingers centered
|
||||||
|
|||||||
Reference in New Issue
Block a user