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:
erwincoumans
2018-11-16 17:29:03 -08:00
parent b13e84e43c
commit 9e99f5cdbc
9 changed files with 640 additions and 6 deletions

View File

@@ -1,8 +1,8 @@
<robot name="dumpUrdf">
<link name="base" >
<link name="root" >
<inertial>
<origin rpy = "0 0 0" xyz = "0 0 0" />
<mass value = "0.000000" />
<mass value = "0.00100" />
<inertia ixx = "0.1" ixy = "0" ixz = "0" iyy = "0.1" iyz = "0" izz = "0.1" />
</inertial>
</link>
@@ -20,7 +20,7 @@
</collision>
</link>
<joint name="joint0" type="fixed" >
<parent link = "base" />
<parent link = "root" />
<child link="link0" />
<origin rpy = "0 0 0" xyz = "0.000000 0.000000 0.000000" />
</joint>