Expose PyBullet.calculateVelocityQuaternion, getAxisAngleFromQuaternion, getQuaternionFromAxisAngle, getDifferenceQuaternion
Add preparation for DeepMimic humanoid environment, replicating parts of https://github.com/xbpeng/DeepMimic Loading humanoid.urdf and applying motion action: examples/pybullet/gym/pybullet_envs/mimic/humanoid.py Loading MotionCapture data: examples/pybullet/gym/pybullet_envs/mimic/motion_capture_data.py Little test: examples/pybullet/gym/pybullet_envs/mimic/humanoid_test.py
This commit is contained in:
@@ -16,7 +16,7 @@ p.setPhysicsEngineParameter(numSolverIterations=200)
|
||||
#path = pybullet_data.getDataPath()+"/motions/humanoid3d_backflip.txt"
|
||||
path = pybullet_data.getDataPath()+"/motions/humanoid3d_cartwheel.txt"
|
||||
|
||||
p.loadURDF("plane.urdf",[0,0,-1])
|
||||
p.loadURDF("plane.urdf",[0,0,-0.03])
|
||||
print("path = ", path)
|
||||
with open(path, 'r') as f:
|
||||
motion_dict = json.load(f)
|
||||
|
||||
Reference in New Issue
Block a user