Update humanoid_running.py
disable sleep and use GUI mode by default
This commit is contained in:
@@ -4,7 +4,7 @@ import numpy as np
|
|||||||
|
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
import time
|
import time
|
||||||
p.connect(p.SHARED_MEMORY) #GUI is slower, but shows the running gait
|
p.connect(p.GUI) #GUI is slower, but shows the running gait
|
||||||
p.setGravity(0,0,-9.8)
|
p.setGravity(0,0,-9.8)
|
||||||
p.setPhysicsEngineParameter(fixedTimeStep=1.0/60., numSolverIterations=5, numSubSteps=2)
|
p.setPhysicsEngineParameter(fixedTimeStep=1.0/60., numSolverIterations=5, numSubSteps=2)
|
||||||
#this mp4 recording requires ffmpeg installed
|
#this mp4 recording requires ffmpeg installed
|
||||||
@@ -186,7 +186,7 @@ def demo_run():
|
|||||||
p.setJointMotorControlArray(human2, motors,controlMode=p.TORQUE_CONTROL, forces=forces)
|
p.setJointMotorControlArray(human2, motors,controlMode=p.TORQUE_CONTROL, forces=forces)
|
||||||
|
|
||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
time.sleep(0.01)
|
#time.sleep(0.01)
|
||||||
distance=5
|
distance=5
|
||||||
yaw = 0
|
yaw = 0
|
||||||
humanPos, humanOrn = p.getBasePositionAndOrientation(human)
|
humanPos, humanOrn = p.getBasePositionAndOrientation(human)
|
||||||
|
|||||||
Reference in New Issue
Block a user