more work on PyBullet implementation of DeepMimic humanoid mimic of motion capture.
b3Quaternion, deal with zero-length axis (in axis,angle constructor)
This commit is contained in:
@@ -3,9 +3,9 @@ currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentfram
|
||||
parentdir = os.path.dirname(os.path.dirname(currentdir))
|
||||
os.sys.path.insert(0,parentdir)
|
||||
|
||||
from pybullet_envs.deep_mimic.humanoid import Humanoid
|
||||
from pybullet_envs.mimic.humanoid import Humanoid
|
||||
from pybullet_utils.bullet_client import BulletClient
|
||||
from pybullet_envs.deep_mimic.motion_capture_data import MotionCaptureData
|
||||
from pybullet_envs.mimic.motion_capture_data import MotionCaptureData
|
||||
import pybullet_data
|
||||
import pybullet
|
||||
import time
|
||||
@@ -17,17 +17,19 @@ bc.configureDebugVisualizer(bc.COV_ENABLE_Y_AXIS_UP,1)
|
||||
bc.setGravity(0,-9.8,0)
|
||||
motion=MotionCaptureData()
|
||||
|
||||
motionPath = pybullet_data.getDataPath()+"/motions/humanoid3d_backflip.txt"#humanoid3d_spinkick.txt"#humanoid3d_backflip.txt"
|
||||
motionPath = pybullet_data.getDataPath()+"/motions/humanoid3d_walk.txt"#humanoid3d_spinkick.txt"#/motions/humanoid3d_backflip.txt"
|
||||
motion.Load(motionPath)
|
||||
print("numFrames = ", motion.NumFrames())
|
||||
frameTimeId= bc.addUserDebugParameter("frameTime",0,motion.NumFrames()-1.1,0)
|
||||
simTimeId= bc.addUserDebugParameter("simTime",0,motion.NumFrames()-1.1,0)
|
||||
|
||||
y2zOrn = bc.getQuaternionFromEuler([-1.57,0,0])
|
||||
bc.loadURDF("plane.urdf",[0,-0.08,0], y2zOrn)
|
||||
bc.loadURDF("plane.urdf",[0,-0.04,0], y2zOrn)
|
||||
|
||||
humanoid = Humanoid(bc, motion,[0,0,0])
|
||||
|
||||
frameTime = 0
|
||||
simTime = 0
|
||||
|
||||
|
||||
keyFrameDuration = motion.KeyFrameDuraction()
|
||||
print("keyFrameDuration=",keyFrameDuration)
|
||||
#for i in range (50):
|
||||
@@ -40,37 +42,41 @@ stage = 0
|
||||
|
||||
|
||||
def Reset(humanoid):
|
||||
global frameTime
|
||||
global simTime
|
||||
humanoid.Reset()
|
||||
frameTime = 0#random.randint(0,motion.NumFrames()-2)
|
||||
print("RESET frametime=",frameTime)
|
||||
humanoid.SetFrameTime(frameTime)
|
||||
simTime = random.randint(0,motion.NumFrames()-2)
|
||||
humanoid.SetSimTime(simTime)
|
||||
pose = humanoid.InitializePoseFromMotionData()
|
||||
humanoid.ApplyPose(pose, True)
|
||||
humanoid.ApplyPose(pose, True, True)
|
||||
|
||||
|
||||
Reset(humanoid)
|
||||
bc.stepSimulation()
|
||||
|
||||
|
||||
while (1):
|
||||
#frameTime = bc.readUserDebugParameter(frameTimeId)
|
||||
#simTime = bc.readUserDebugParameter(frameTimeId)
|
||||
#print("keyFrameDuration=",keyFrameDuration)
|
||||
dt = (1./240.)/keyFrameDuration
|
||||
#print("dt=",dt)
|
||||
frameTime += dt
|
||||
if (frameTime >= (motion.NumFrames())-1.1):
|
||||
frameTime = motion.NumFrames()-1.1
|
||||
#print("frameTime=", frameTime)
|
||||
humanoid.SetFrameTime(frameTime)
|
||||
dt = (1./240.)
|
||||
print("------------------------------------------")
|
||||
print("dt=",dt)
|
||||
|
||||
print("simTime=",simTime)
|
||||
print("humanoid.SetSimTime(simTime)")
|
||||
humanoid.SetSimTime(simTime)
|
||||
|
||||
pose = humanoid.InitializePoseFromMotionData()
|
||||
#pose = humanoid.InitializePoseFromMotionData()
|
||||
|
||||
#humanoid.ApplyPose(pose, False)#False, False)
|
||||
#humanoid.ApplyPose(pose, True)#False)#False, False)
|
||||
if (humanoid.Terminates()):
|
||||
Reset(humanoid)
|
||||
|
||||
bc.stepSimulation()
|
||||
|
||||
|
||||
time.sleep(1./240.)
|
||||
state = humanoid.GetState()
|
||||
action = [0]*36
|
||||
humanoid.ApplyAction(action)
|
||||
for s in range (8):
|
||||
print("step:",s)
|
||||
bc.stepSimulation()
|
||||
simTime += dt
|
||||
time.sleep(1./240.)
|
||||
|
||||
|
||||
Reference in New Issue
Block a user