Upstream retargeting pipeline available for more example Humanoid AMP motions? #2220
-
I'm interested in trying out new motions with the Humanoid AMP implementation in IsaacLab. Is there an existing library or pipeline that was used to create the .npz example files in the format described in the README.md? If such a pipeline already exists from a well-known mocap database of motions into this humanoid_28.usd format that could save lots of effort. Any direction is appreciated. Thanks! |
Beta Was this translation helpful? Give feedback.
Replies: 2 comments 1 reply
-
Thanks for posting this. The following script was used, I've included the code below, and it requires IsaacGymEnvs. You can call it as follows, for example:
where import argparse
parser = argparse.ArgumentParser()
parser.add_argument("--file", type=str, required=True, help="Motion file (IsaacGymEnvs/assets/amp/motions)")
parser.add_argument("--threshold", type=float, default=1.0e-3, help="Threshold for data checking")
args, _ = parser.parse_known_args()
motion_file = args.file
# avoid: ImportError: PyTorch was imported before isaacgym modules
import isaacgym
import os
import numpy as np
from isaacgymenvs.utils.torch_jit_utils import to_torch
from isaacgymenvs.tasks.amp.utils_amp.motion_lib import MotionLib as _MotionLib
class MotionLib(_MotionLib):
def _calc_frame_blend(self, time, len, num_frames, dt):
phase = time / len
phase = np.clip(phase, 0.0, 1.0)
frame_idx0 = (phase * (num_frames - 1)).round(decimals=0).astype(int)
frame_idx1 = np.minimum(frame_idx0 + 1, num_frames - 1)
blend = ((time - frame_idx0 * dt) / dt).round(decimals=4)
assert (frame_idx0 == np.arange(num_frames[0])).all(), frame_idx0.tolist()
assert not blend.any(), blend.tolist()
return frame_idx0, frame_idx1, blend
def get_full_motion_states(self, motion_ids, motion_times):
n = len(motion_ids)
num_bodies = self._get_num_bodies()
positions = np.empty([n, num_bodies, 3])
rotations = np.empty([n, num_bodies, 4])
local_rotations = np.empty([n, num_bodies, 4])
linear_velocities = np.empty([n, num_bodies, 3])
angular_velocities = np.empty([n, num_bodies, 3])
dof_velocities = np.empty([n, self._num_dof])
motion_len = self._motion_lengths[motion_ids]
num_frames = self._motion_num_frames[motion_ids]
dt = self._motion_dt[motion_ids]
frame_idx0, frame_idx1, blend = self._calc_frame_blend(motion_times, motion_len, num_frames, dt)
unique_ids = np.unique(motion_ids)
for uid in unique_ids:
ids = np.where(motion_ids == uid)
curr_motion = self._motions[uid]
positions[ids, :, :] = curr_motion.global_translation[frame_idx0[ids][:, np.newaxis], self._key_body_ids[np.newaxis, :]].numpy()
rotations[ids, :, :] = curr_motion.global_rotation[frame_idx0[ids][:, np.newaxis], self._key_body_ids[np.newaxis, :]].numpy()
local_rotations[ids, :, :] = curr_motion.local_rotation[frame_idx0[ids][:, np.newaxis], self._key_body_ids[np.newaxis, :]].numpy()
linear_velocities[ids, :, :] = curr_motion.global_velocity[frame_idx0[ids][:, np.newaxis], self._key_body_ids[np.newaxis, :]].numpy()
angular_velocities[ids, :, :] = curr_motion.global_angular_velocity[frame_idx0[ids][:, np.newaxis], self._key_body_ids[np.newaxis, :]].numpy()
dof_velocities[ids, :] = curr_motion.dof_vels[frame_idx0[ids]]
positions = to_torch(positions, device=self._device)
rotations = to_torch(rotations, device=self._device)
local_rotations = to_torch(local_rotations, device=self._device)
linear_velocities = to_torch(linear_velocities, device=self._device)
angular_velocities = to_torch(angular_velocities, device=self._device)
dof_velocities = to_torch(dof_velocities, device=self._device)
dof_positions = self._local_rotation_to_dof(local_rotations)
return dof_positions, dof_velocities, positions, rotations, linear_velocities, angular_velocities
IG_BODY_NAMES = [
"pelvis",
"torso",
"head",
"right_upper_arm",
"right_lower_arm",
"right_hand",
"left_upper_arm",
"left_lower_arm",
"left_hand",
"right_thigh",
"right_shin",
"right_foot",
"left_thigh",
"left_shin",
"left_foot"
]
IG_DOF_NAMES = [
"abdomen_x",
"abdomen_y",
"abdomen_z",
"neck_x",
"neck_y",
"neck_z",
"right_shoulder_x",
"right_shoulder_y",
"right_shoulder_z",
"right_elbow",
"left_shoulder_x",
"left_shoulder_y",
"left_shoulder_z",
"left_elbow",
"right_hip_x",
"right_hip_y",
"right_hip_z",
"right_knee",
"right_ankle_x",
"right_ankle_y",
"right_ankle_z",
"left_hip_x",
"left_hip_y",
"left_hip_z",
"left_knee",
"left_ankle_x",
"left_ankle_y",
"left_ankle_z"
]
def isaacgym_reorder_quat(tensor): # xyzw -> wxyz
if tensor.ndim == 2:
return tensor[:, [3, 0, 1, 2]]
elif tensor.ndim == 3:
return tensor[:, :, [3, 0, 1, 2]]
def isaacgym_reorder_joints(tensor, names, isaacgym=True):
if isaacgym:
return tensor[:, [names.index(name) for name in IG_DOF_NAMES]]
return tensor[:, [IG_DOF_NAMES.index(name) for name in names]]
def isaacgym_get_body_indexes(names):
return [IG_BODY_NAMES.index(name) for name in names]
# load motions
motion_lib = MotionLib(
motion_file=motion_file,
num_dofs=len(IG_DOF_NAMES),
key_body_ids=np.array(isaacgym_get_body_indexes(IG_BODY_NAMES)),
device="cuda:0",
)
num_motions = motion_lib.num_motions()
assert num_motions == 1, num_motions
motions = [motion_lib.get_motion(index) for index in range(num_motions)]
motion_frames = [len(motion) for motion in motions]
motion_durations = [motion_lib.get_motion_length(index) for index in range(num_motions)]
motion_fps = [np.array(motion.fps) for motion in motions]
motion_ids = [np.array([index] * len(motion_lib.get_motion(index))) for index in range(num_motions)]
motion_times = [motion_lib.get_motion_length(index) * np.linspace(0, 1, len(motion_lib.get_motion(index))) for index in range(num_motions)]
print()
print("number of motions:", num_motions)
print("motion (fps):", motion_fps)
print("motion length (frames):", motion_frames)
print("motion length (time):", motion_durations)
dof_positions, dof_velocities, positions, rotations, linear_velocities, angular_velocities = motion_lib.get_full_motion_states(motion_ids[0], motion_times[0])
root_pos, root_rot, dof_pos, root_vel, root_ang_vel, dof_vel, key_pos = motion_lib.get_motion_state(motion_ids[0], motion_times[0])
assert (dof_positions - dof_pos).sum().item() < args.threshold, (dof_positions - dof_pos).sum().item()
assert (dof_velocities - dof_vel).sum().item() < args.threshold, (dof_velocities - dof_vel).sum().item()
assert (positions[:,0] - root_pos).sum().item() < args.threshold, (positions[:,0] - root_pos).sum().item()
assert (rotations[:,0] - root_rot).sum().item() < args.threshold, (rotations[:,0] - root_rot).sum().item()
assert (linear_velocities[:,0] - root_vel).sum().item() < args.threshold, (linear_velocities[:,0] - root_vel).sum().item()
assert (angular_velocities[:,0] - root_ang_vel).sum().item() < args.threshold, (angular_velocities[:,0] - root_ang_vel).sum().item()
assert (positions - key_pos).sum().item() < args.threshold, (positions - key_pos).sum().item()
filename = os.path.basename(motion_file).replace(".npy", ".npz")
np.savez(
f"exported-{filename}",
fps=motion_fps[0].item(),
dof_names=IG_DOF_NAMES,
body_names=IG_BODY_NAMES,
dof_positions=dof_positions.cpu().numpy(),
dof_velocities=dof_velocities.cpu().numpy(),
body_positions=positions.cpu().numpy(),
body_rotations=isaacgym_reorder_quat(rotations).cpu().numpy(),
body_linear_velocities=linear_velocities.cpu().numpy(),
body_angular_velocities=angular_velocities.cpu().numpy(),
) |
Beta Was this translation helpful? Give feedback.
-
Two ways to get files for future googlers: Either isaac gui # ./isaaclab.sh -p scripts/tutorials/00_sim/create_empty.py # open isaac sim editor
# menu bar -> windows -> browsers -> [X] isaac sim assets
# bottom pane, third tab ("Isaac Sim Assets [Beta]") search humanoid and download
cp -v ~/Downloads/humanoid_28.usd /wherever/Isaac/IsaacLab/Robots/Classic/Humanoid28/humanoid_28.usd or s3 bucket # https://omniverse-content-production.s3-us-west-2.amazonaws.com/
# save list of files
rclone ls ":s3,env_auth=false,provider=AWS,region=us-west-2:omniverse-content-production/Assets/Isaac/4.5/" | tee files.txt
# get size of download
rclone size --progress ":s3,env_auth=false,provider=AWS,region=us-west-2:omniverse-content-production/Assets/Isaac/4.5/Isaac"
# Total objects: 47.207k (47207)
# Total size: 47.633 GiB (51145982874 Byte)
# download it
rclone copy --transfers 16 --progress :s3,env_auth=false,provider=AWS,region=us-west-2:omniverse-content-production/Assets/Isaac/4.5/Isaac ~/Downloads/isaac-4-5-assets/ |
Beta Was this translation helpful? Give feedback.
Thanks for posting this. The following script was used, I've included the code below, and it requires IsaacGymEnvs. You can call it as follows, for example:
where
export_motions.py
is: