Commit e5acb85e authored by peterd-NV's avatar peterd-NV Committed by Kelly Guo

Adds two new GR1 environments for IsaacLab Mimic (#392)

<!--
Thank you for your interest in sending a pull request. Please make sure
to check the contribution guidelines.

Link:
https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html
-->

Changes:

1. Adds two new GR1 humanoid environments to isaaclab_tasks extension. A
beaker pouring task (nut pouring) and an exhaust pipe pick/place task
(exhaust pipe)
2. Adds the corresponding Mimic envs for the two new GR1 tasks to
isaaclab_mimic extension.
3. Adds a processed action recorder term to record post step processed
actions.
4. Update recorder script to remove cameras from envs if using XR
handtracking device.

<!-- As you go through the list, delete the ones that are not
applicable. -->

- New feature (non-breaking change which adds functionality)

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [ ] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [ ] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [ ] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there

<!--
As you go through the checklist above, you can mark something as done by
putting an x character in it

For example,
- [x] I have done this task
- [ ] I have not done this task
-->

---------
Co-authored-by: 's avatarKelly Guo <kellyguo123@hotmail.com>
Co-authored-by: 's avatarKelly Guo <kellyg@nvidia.com>
parent 01732521
...@@ -61,6 +61,8 @@ simulation_app = app_launcher.app ...@@ -61,6 +61,8 @@ simulation_app = app_launcher.app
import copy import copy
import gymnasium as gym import gymnasium as gym
import numpy as np
import random
import torch import torch
import robomimic.utils.file_utils as FileUtils import robomimic.utils.file_utils as FileUtils
...@@ -160,18 +162,18 @@ def main(): ...@@ -160,18 +162,18 @@ def main():
# Set seed # Set seed
torch.manual_seed(args_cli.seed) torch.manual_seed(args_cli.seed)
np.random.seed(args_cli.seed)
random.seed(args_cli.seed)
env.seed(args_cli.seed) env.seed(args_cli.seed)
# Acquire device # Acquire device
device = TorchUtils.get_torch_device(try_to_use_cuda=True) device = TorchUtils.get_torch_device(try_to_use_cuda=True)
# Load policy
policy, _ = FileUtils.policy_from_checkpoint(ckpt_path=args_cli.checkpoint, device=device, verbose=True)
# Run policy # Run policy
results = [] results = []
for trial in range(args_cli.num_rollouts): for trial in range(args_cli.num_rollouts):
print(f"[INFO] Starting trial {trial}") print(f"[INFO] Starting trial {trial}")
policy, _ = FileUtils.policy_from_checkpoint(ckpt_path=args_cli.checkpoint, device=device)
terminated, traj = rollout(policy, env, success_term, args_cli.horizon, device) terminated, traj = rollout(policy, env, success_term, args_cli.horizon, device)
results.append(terminated) results.append(terminated)
print(f"[INFO] Trial {trial}: {terminated}\n") print(f"[INFO] Trial {trial}: {terminated}\n")
......
...@@ -27,13 +27,6 @@ optional arguments: ...@@ -27,13 +27,6 @@ optional arguments:
import argparse import argparse
import contextlib import contextlib
# Third-party imports
import gymnasium as gym
import numpy as np
import os
import time
import torch
# Isaac Lab AppLauncher # Isaac Lab AppLauncher
from isaaclab.app import AppLauncher from isaaclab.app import AppLauncher
...@@ -79,6 +72,16 @@ if "handtracking" in args_cli.teleop_device.lower(): ...@@ -79,6 +72,16 @@ if "handtracking" in args_cli.teleop_device.lower():
app_launcher = AppLauncher(args_cli) app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app simulation_app = app_launcher.app
"""Rest everything follows."""
# Third-party imports
import gymnasium as gym
import numpy as np
import os
import time
import torch
# Omniverse logger # Omniverse logger
import omni.log import omni.log
import omni.ui as ui import omni.ui as ui
...@@ -94,9 +97,11 @@ if args_cli.enable_pinocchio: ...@@ -94,9 +97,11 @@ if args_cli.enable_pinocchio:
import isaaclab_tasks.manager_based.manipulation.pick_place # noqa: F401 import isaaclab_tasks.manager_based.manipulation.pick_place # noqa: F401
from isaaclab.devices.openxr.retargeters.manipulator import GripperRetargeter, Se3AbsRetargeter, Se3RelRetargeter from isaaclab.devices.openxr.retargeters.manipulator import GripperRetargeter, Se3AbsRetargeter, Se3RelRetargeter
from isaaclab.envs import ManagerBasedEnvCfg
from isaaclab.envs.mdp.recorders.recorders_cfg import ActionStateRecorderManagerCfg from isaaclab.envs.mdp.recorders.recorders_cfg import ActionStateRecorderManagerCfg
from isaaclab.envs.ui import EmptyWindow from isaaclab.envs.ui import EmptyWindow
from isaaclab.managers import DatasetExportMode from isaaclab.managers import DatasetExportMode, SceneEntityCfg
from isaaclab.sensors import CameraCfg
import isaaclab_tasks # noqa: F401 import isaaclab_tasks # noqa: F401
from isaaclab_tasks.utils.parse_cfg import parse_env_cfg from isaaclab_tasks.utils.parse_cfg import parse_env_cfg
...@@ -156,7 +161,7 @@ def pre_process_actions( ...@@ -156,7 +161,7 @@ def pre_process_actions(
# note: reach is the only one that uses a different action space # note: reach is the only one that uses a different action space
# compute actions # compute actions
return delta_pose return delta_pose
elif "PickPlace-GR1T2" in args_cli.task: elif "GR1T2" in args_cli.task:
(left_wrist_pose, right_wrist_pose, hand_joints) = teleop_data[0] (left_wrist_pose, right_wrist_pose, hand_joints) = teleop_data[0]
# Reconstruct actions_arms tensor with converted positions and rotations # Reconstruct actions_arms tensor with converted positions and rotations
actions = torch.tensor( actions = torch.tensor(
...@@ -181,6 +186,25 @@ def pre_process_actions( ...@@ -181,6 +186,25 @@ def pre_process_actions(
return torch.concat([delta_pose, gripper_vel], dim=1) return torch.concat([delta_pose, gripper_vel], dim=1)
def remove_camera_configs(env_cfg: ManagerBasedEnvCfg):
for attr_name in dir(env_cfg.scene):
attr = getattr(env_cfg.scene, attr_name)
if isinstance(attr, CameraCfg):
delattr(env_cfg.scene, attr_name)
omni.log.info(f"Removed camera config: {attr_name}")
# Remove any ObsTerms for the camera
for obs_name in dir(env_cfg.observations.policy):
obsterm = getattr(env_cfg.observations.policy, obs_name)
if hasattr(obsterm, "params") and obsterm.params:
for param_value in obsterm.params.values():
if isinstance(param_value, SceneEntityCfg) and param_value.name == attr_name:
delattr(env_cfg.observations.policy, attr_name)
omni.log.info(f"Removed camera observation term: {attr_name}")
break
return env_cfg
def main(): def main():
"""Collect demonstrations from the environment using teleop interfaces.""" """Collect demonstrations from the environment using teleop interfaces."""
...@@ -213,6 +237,12 @@ def main(): ...@@ -213,6 +237,12 @@ def main():
" Will not be able to mark recorded demos as successful." " Will not be able to mark recorded demos as successful."
) )
if "handtracking" in args_cli.teleop_device.lower():
# External cameras are not supported with XR teleop
# Check for any camera configs and disable them
env_cfg = remove_camera_configs(env_cfg)
env_cfg.sim.render.antialiasing_mode = "DLSS"
# modify configuration such that the environment runs indefinitely until # modify configuration such that the environment runs indefinitely until
# the goal is reached or other termination conditions are met # the goal is reached or other termination conditions are met
env_cfg.terminations.time_out = None env_cfg.terminations.time_out = None
...@@ -357,7 +387,7 @@ def main(): ...@@ -357,7 +387,7 @@ def main():
label_text = f"Recorded {current_recorded_demo_count} successful demonstrations." label_text = f"Recorded {current_recorded_demo_count} successful demonstrations."
instruction_display = InstructionDisplay(args_cli.teleop_device) instruction_display = InstructionDisplay(args_cli.teleop_device)
if args_cli.teleop_device.lower() != "handtracking": if "handtracking" not in args_cli.teleop_device.lower():
window = EmptyWindow(env, "Instruction") window = EmptyWindow(env, "Instruction")
with window.ui_window_elements["main_vstack"]: with window.ui_window_elements["main_vstack"]:
demo_label = ui.Label(label_text) demo_label = ui.Label(label_text)
......
...@@ -391,6 +391,16 @@ Added ...@@ -391,6 +391,16 @@ Added
* Added :meth:`~isaaclab.envs.mdp.observations.body_projected_gravity_b` * Added :meth:`~isaaclab.envs.mdp.observations.body_projected_gravity_b`
0.37.3 (2025-05-08)
~~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Updated PINK task space action to record processed actions.
* Added new recorder term for recording post step processed actions.
0.37.2 (2025-05-06) 0.37.2 (2025-05-06)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
......
...@@ -197,10 +197,12 @@ class PinkInverseKinematicsAction(ActionTerm): ...@@ -197,10 +197,12 @@ class PinkInverseKinematicsAction(ActionTerm):
joint_pos_des = ik_controller.compute(curr_joint_pos, self._sim_dt) joint_pos_des = ik_controller.compute(curr_joint_pos, self._sim_dt)
all_envs_joint_pos_des.append(joint_pos_des) all_envs_joint_pos_des.append(joint_pos_des)
all_envs_joint_pos_des = torch.stack(all_envs_joint_pos_des) all_envs_joint_pos_des = torch.stack(all_envs_joint_pos_des)
# Combine IK joint positions with hand joint positions # Combine IK joint positions with hand joint positions
all_envs_joint_pos_des = torch.cat((all_envs_joint_pos_des, self._target_hand_joint_positions), dim=1) all_envs_joint_pos_des = torch.cat((all_envs_joint_pos_des, self._target_hand_joint_positions), dim=1)
self._processed_actions = all_envs_joint_pos_des
self._asset.set_joint_position_target(all_envs_joint_pos_des, self._joint_ids) self._asset.set_joint_position_target(self._processed_actions, self._joint_ids)
def reset(self, env_ids: Sequence[int] | None = None) -> None: def reset(self, env_ids: Sequence[int] | None = None) -> None:
"""Reset the action term for specified environments. """Reset the action term for specified environments.
......
...@@ -4,6 +4,7 @@ ...@@ -4,6 +4,7 @@
# SPDX-License-Identifier: BSD-3-Clause # SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations from __future__ import annotations
import torch
from collections.abc import Sequence from collections.abc import Sequence
from isaaclab.managers.recorder_manager import RecorderTerm from isaaclab.managers.recorder_manager import RecorderTerm
...@@ -41,3 +42,20 @@ class PreStepFlatPolicyObservationsRecorder(RecorderTerm): ...@@ -41,3 +42,20 @@ class PreStepFlatPolicyObservationsRecorder(RecorderTerm):
def record_pre_step(self): def record_pre_step(self):
return "obs", self._env.obs_buf["policy"] return "obs", self._env.obs_buf["policy"]
class PostStepProcessedActionsRecorder(RecorderTerm):
"""Recorder term that records processed actions at the end of each step."""
def record_post_step(self):
processed_actions = None
# Loop through active terms and concatenate their processed actions
for term_name in self._env.action_manager.active_terms:
term_actions = self._env.action_manager.get_term(term_name).processed_actions.clone()
if processed_actions is None:
processed_actions = term_actions
else:
processed_actions = torch.cat([processed_actions, term_actions], dim=-1)
return "processed_actions", processed_actions
...@@ -40,6 +40,13 @@ class PreStepFlatPolicyObservationsRecorderCfg(RecorderTermCfg): ...@@ -40,6 +40,13 @@ class PreStepFlatPolicyObservationsRecorderCfg(RecorderTermCfg):
class_type: type[RecorderTerm] = recorders.PreStepFlatPolicyObservationsRecorder class_type: type[RecorderTerm] = recorders.PreStepFlatPolicyObservationsRecorder
@configclass
class PostStepProcessedActionsRecorderCfg(RecorderTermCfg):
"""Configuration for the post step processed actions recorder term."""
class_type: type[RecorderTerm] = recorders.PostStepProcessedActionsRecorder
## ##
# Recorder manager configurations. # Recorder manager configurations.
## ##
...@@ -53,3 +60,4 @@ class ActionStateRecorderManagerCfg(RecorderManagerBaseCfg): ...@@ -53,3 +60,4 @@ class ActionStateRecorderManagerCfg(RecorderManagerBaseCfg):
record_post_step_states = PostStepStatesRecorderCfg() record_post_step_states = PostStepStatesRecorderCfg()
record_pre_step_actions = PreStepActionsRecorderCfg() record_pre_step_actions = PreStepActionsRecorderCfg()
record_pre_step_flat_policy_observations = PreStepFlatPolicyObservationsRecorderCfg() record_pre_step_flat_policy_observations = PreStepFlatPolicyObservationsRecorderCfg()
record_post_step_processed_actions = PostStepProcessedActionsRecorderCfg()
[package] [package]
# Semantic Versioning is used: https://semver.org/ # Semantic Versioning is used: https://semver.org/
version = "1.0.7" version = "1.0.8"
# Description # Description
category = "isaaclab" category = "isaaclab"
......
Changelog Changelog
--------- ---------
1.0.8 (2025-05-01)
~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added :class:`NutPourGR1T2MimicEnv` and :class:`ExhaustPipeGR1T2MimicEnv` for the GR1T2 nut pouring and exhaust pipe tasks.
* Updated instruction display to support all XR handtracking devices.
1.0.7 (2025-03-19) 1.0.7 (2025-03-19)
~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~
...@@ -14,7 +24,7 @@ Changed ...@@ -14,7 +24,7 @@ Changed
~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~
Added Added
^^^^^^^ ^^^^^
* Added :class:`FrankaCubeStackIKAbsMimicEnv` and support for the GR1T2 robot task (:class:`PickPlaceGR1T2MimicEnv`). * Added :class:`FrankaCubeStackIKAbsMimicEnv` and support for the GR1T2 robot task (:class:`PickPlaceGR1T2MimicEnv`).
......
...@@ -12,6 +12,8 @@ ...@@ -12,6 +12,8 @@
import gymnasium as gym import gymnasium as gym
from .exhaustpipe_gr1t2_mimic_env_cfg import ExhaustPipeGR1T2MimicEnvCfg
from .nutpour_gr1t2_mimic_env_cfg import NutPourGR1T2MimicEnvCfg
from .pickplace_gr1t2_mimic_env import PickPlaceGR1T2MimicEnv from .pickplace_gr1t2_mimic_env import PickPlaceGR1T2MimicEnv
from .pickplace_gr1t2_mimic_env_cfg import PickPlaceGR1T2MimicEnvCfg from .pickplace_gr1t2_mimic_env_cfg import PickPlaceGR1T2MimicEnvCfg
...@@ -23,3 +25,17 @@ gym.register( ...@@ -23,3 +25,17 @@ gym.register(
}, },
disable_env_checker=True, disable_env_checker=True,
) )
gym.register(
id="Isaac-NutPour-GR1T2-Pink-IK-Abs-Mimic-v0",
entry_point="isaaclab_mimic.envs.pinocchio_envs:PickPlaceGR1T2MimicEnv",
kwargs={"env_cfg_entry_point": nutpour_gr1t2_mimic_env_cfg.NutPourGR1T2MimicEnvCfg},
disable_env_checker=True,
)
gym.register(
id="Isaac-ExhaustPipe-GR1T2-Pink-IK-Abs-Mimic-v0",
entry_point="isaaclab_mimic.envs.pinocchio_envs:PickPlaceGR1T2MimicEnv",
kwargs={"env_cfg_entry_point": exhaustpipe_gr1t2_mimic_env_cfg.ExhaustPipeGR1T2MimicEnvCfg},
disable_env_checker=True,
)
# Copyright (c) 2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: Apache-2.0
from isaaclab.envs.mimic_env_cfg import MimicEnvCfg, SubTaskConfig
from isaaclab.utils import configclass
from isaaclab_tasks.manager_based.manipulation.pick_place.exhaustpipe_gr1t2_pink_ik_env_cfg import (
ExhaustPipeGR1T2PinkIKEnvCfg,
)
@configclass
class ExhaustPipeGR1T2MimicEnvCfg(ExhaustPipeGR1T2PinkIKEnvCfg, MimicEnvCfg):
def __post_init__(self):
# Calling post init of parents
super().__post_init__()
# Override the existing values
self.datagen_config.name = "gr1t2_exhaust_pipe_D0"
self.datagen_config.generation_guarantee = True
self.datagen_config.generation_keep_failed = False
self.datagen_config.generation_num_trials = 1000
self.datagen_config.generation_select_src_per_subtask = False
self.datagen_config.generation_select_src_per_arm = False
self.datagen_config.generation_relative = False
self.datagen_config.generation_joint_pos = False
self.datagen_config.generation_transform_first_robot_pose = False
self.datagen_config.generation_interpolate_from_last_target_pose = True
self.datagen_config.max_num_failures = 25
self.datagen_config.num_demo_to_render = 10
self.datagen_config.num_fail_demo_to_render = 25
self.datagen_config.seed = 10
# The following are the subtask configurations for the stack task.
subtask_configs = []
subtask_configs.append(
SubTaskConfig(
# Each subtask involves manipulation with respect to a single object frame.
object_ref="blue_exhaust_pipe",
# This key corresponds to the binary indicator in "datagen_info" that signals
# when this subtask is finished (e.g., on a 0 to 1 edge).
subtask_term_signal="idle_right_1",
first_subtask_start_offset_range=(0, 0),
# Randomization range for starting index of the first subtask
subtask_term_offset_range=(0, 0),
# Selection strategy for the source subtask segment during data generation
selection_strategy="nearest_neighbor_object",
# Optional parameters for the selection strategy function
selection_strategy_kwargs={"nn_k": 3},
# Amount of action noise to apply during this subtask
action_noise=0.003,
# Number of interpolation steps to bridge to this subtask segment
num_interpolation_steps=5,
# Additional fixed steps for the robot to reach the necessary pose
num_fixed_steps=0,
# If True, apply action noise during the interpolation phase and execution
apply_noise_during_interpolation=False,
)
)
subtask_configs.append(
SubTaskConfig(
# Each subtask involves manipulation with respect to a single object frame.
object_ref="blue_exhaust_pipe",
# This key corresponds to the binary indicator in "datagen_info" that signals
# when this subtask is finished (e.g., on a 0 to 1 edge).
first_subtask_start_offset_range=(0, 0),
# Randomization range for starting index of the first subtask
subtask_term_offset_range=(0, 0),
# Selection strategy for the source subtask segment during data generation
selection_strategy="nearest_neighbor_object",
# Optional parameters for the selection strategy function
selection_strategy_kwargs={"nn_k": 3},
# Amount of action noise to apply during this subtask
action_noise=0.003,
# Number of interpolation steps to bridge to this subtask segment
num_interpolation_steps=5,
# Additional fixed steps for the robot to reach the necessary pose
num_fixed_steps=0,
# If True, apply action noise during the interpolation phase and execution
apply_noise_during_interpolation=False,
)
)
self.subtask_configs["right"] = subtask_configs
subtask_configs = []
subtask_configs.append(
SubTaskConfig(
# Each subtask involves manipulation with respect to a single object frame.
object_ref="blue_exhaust_pipe",
# This key corresponds to the binary indicator in "datagen_info" that signals
# when this subtask is finished (e.g., on a 0 to 1 edge).
first_subtask_start_offset_range=(0, 0),
# Randomization range for starting index of the first subtask
subtask_term_offset_range=(0, 0),
# Selection strategy for the source subtask segment during data generation
selection_strategy="nearest_neighbor_object",
# Optional parameters for the selection strategy function
selection_strategy_kwargs={"nn_k": 3},
# Amount of action noise to apply during this subtask
action_noise=0.003,
# Number of interpolation steps to bridge to this subtask segment
num_interpolation_steps=5,
# Additional fixed steps for the robot to reach the necessary pose
num_fixed_steps=0,
# If True, apply action noise during the interpolation phase and execution
apply_noise_during_interpolation=False,
)
)
self.subtask_configs["left"] = subtask_configs
# Copyright (c) 2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: Apache-2.0
from isaaclab.envs.mimic_env_cfg import MimicEnvCfg, SubTaskConfig
from isaaclab.utils import configclass
from isaaclab_tasks.manager_based.manipulation.pick_place.nutpour_gr1t2_pink_ik_env_cfg import NutPourGR1T2PinkIKEnvCfg
@configclass
class NutPourGR1T2MimicEnvCfg(NutPourGR1T2PinkIKEnvCfg, MimicEnvCfg):
def __post_init__(self):
# Calling post init of parents
super().__post_init__()
# Override the existing values
self.datagen_config.name = "gr1t2_nut_pouring_D0"
self.datagen_config.generation_guarantee = True
self.datagen_config.generation_keep_failed = False
self.datagen_config.generation_num_trials = 1000
self.datagen_config.generation_select_src_per_subtask = False
self.datagen_config.generation_select_src_per_arm = False
self.datagen_config.generation_relative = False
self.datagen_config.generation_joint_pos = False
self.datagen_config.generation_transform_first_robot_pose = False
self.datagen_config.generation_interpolate_from_last_target_pose = True
self.datagen_config.max_num_failures = 25
self.datagen_config.num_demo_to_render = 10
self.datagen_config.num_fail_demo_to_render = 25
self.datagen_config.seed = 10
# The following are the subtask configurations for the stack task.
subtask_configs = []
subtask_configs.append(
SubTaskConfig(
# Each subtask involves manipulation with respect to a single object frame.
object_ref="sorting_bowl",
# This key corresponds to the binary indicator in "datagen_info" that signals
# when this subtask is finished (e.g., on a 0 to 1 edge).
subtask_term_signal="idle_right",
first_subtask_start_offset_range=(0, 0),
# Randomization range for starting index of the first subtask
subtask_term_offset_range=(0, 0),
# Selection strategy for the source subtask segment during data generation
selection_strategy="nearest_neighbor_object",
# Optional parameters for the selection strategy function
selection_strategy_kwargs={"nn_k": 3},
# Amount of action noise to apply during this subtask
action_noise=0.003,
# Number of interpolation steps to bridge to this subtask segment
num_interpolation_steps=5,
# Additional fixed steps for the robot to reach the necessary pose
num_fixed_steps=0,
# If True, apply action noise during the interpolation phase and execution
apply_noise_during_interpolation=False,
)
)
subtask_configs.append(
SubTaskConfig(
# Each subtask involves manipulation with respect to a single object frame.
object_ref="sorting_bowl",
# This key corresponds to the binary indicator in "datagen_info" that signals
# when this subtask is finished (e.g., on a 0 to 1 edge).
subtask_term_signal="grasp_right",
first_subtask_start_offset_range=(0, 0),
# Randomization range for starting index of the first subtask
subtask_term_offset_range=(0, 0),
# Selection strategy for the source subtask segment during data generation
selection_strategy="nearest_neighbor_object",
# Optional parameters for the selection strategy function
selection_strategy_kwargs={"nn_k": 3},
# Amount of action noise to apply during this subtask
action_noise=0.003,
# Number of interpolation steps to bridge to this subtask segment
num_interpolation_steps=3,
# Additional fixed steps for the robot to reach the necessary pose
num_fixed_steps=0,
# If True, apply action noise during the interpolation phase and execution
apply_noise_during_interpolation=False,
)
)
subtask_configs.append(
SubTaskConfig(
# Each subtask involves manipulation with respect to a single object frame.
object_ref="sorting_scale",
# Corresponding key for the binary indicator in "datagen_info" for completion
subtask_term_signal=None,
# Time offsets for data generation when splitting a trajectory
subtask_term_offset_range=(0, 0),
# Selection strategy for source subtask segment
selection_strategy="nearest_neighbor_object",
# Optional parameters for the selection strategy function
selection_strategy_kwargs={"nn_k": 3},
# Amount of action noise to apply during this subtask
action_noise=0.003,
# Number of interpolation steps to bridge to this subtask segment
num_interpolation_steps=3,
# Additional fixed steps for the robot to reach the necessary pose
num_fixed_steps=0,
# If True, apply action noise during the interpolation phase and execution
apply_noise_during_interpolation=False,
)
)
self.subtask_configs["right"] = subtask_configs
subtask_configs = []
subtask_configs.append(
SubTaskConfig(
# Each subtask involves manipulation with respect to a single object frame.
object_ref="sorting_beaker",
# This key corresponds to the binary indicator in "datagen_info" that signals
# when this subtask is finished (e.g., on a 0 to 1 edge).
subtask_term_signal="grasp_left",
first_subtask_start_offset_range=(0, 0),
# Randomization range for starting index of the first subtask
subtask_term_offset_range=(0, 0),
# Selection strategy for the source subtask segment during data generatio
selection_strategy="nearest_neighbor_object",
# Optional parameters for the selection strategy function
selection_strategy_kwargs={"nn_k": 3},
# Amount of action noise to apply during this subtask
action_noise=0.003,
# Number of interpolation steps to bridge to this subtask segment
num_interpolation_steps=5,
# Additional fixed steps for the robot to reach the necessary pose
num_fixed_steps=0,
# If True, apply action noise during the interpolation phase and execution
apply_noise_during_interpolation=False,
)
)
subtask_configs.append(
SubTaskConfig(
# Each subtask involves manipulation with respect to a single object frame.
object_ref="sorting_bowl",
# Corresponding key for the binary indicator in "datagen_info" for completion
subtask_term_signal=None,
# Time offsets for data generation when splitting a trajectory
subtask_term_offset_range=(0, 0),
# Selection strategy for source subtask segment
selection_strategy="nearest_neighbor_object",
# Optional parameters for the selection strategy function
selection_strategy_kwargs={"nn_k": 3},
# Amount of action noise to apply during this subtask
action_noise=0.003,
# Number of interpolation steps to bridge to this subtask segment
num_interpolation_steps=5,
# Additional fixed steps for the robot to reach the necessary pose
num_fixed_steps=0,
# If True, apply action noise during the interpolation phase and execution
apply_noise_during_interpolation=False,
)
)
self.subtask_configs["left"] = subtask_configs
...@@ -23,7 +23,7 @@ class InstructionDisplay: ...@@ -23,7 +23,7 @@ class InstructionDisplay:
def __init__(self, teleop_device): def __init__(self, teleop_device):
self.teleop_device = teleop_device.lower() self.teleop_device = teleop_device.lower()
if self.teleop_device == "handtracking": if "handtracking" in self.teleop_device.lower():
from isaaclab.ui.xr_widgets import show_instruction from isaaclab.ui.xr_widgets import show_instruction
self._display_subtask = lambda text: show_instruction( self._display_subtask = lambda text: show_instruction(
......
[package] [package]
# Note: Semantic Versioning is used: https://semver.org/ # Note: Semantic Versioning is used: https://semver.org/
version = "0.10.36" version = "0.10.37"
# Description # Description
title = "Isaac Lab Environments" title = "Isaac Lab Environments"
......
Changelog Changelog
--------- ---------
0.10.36 (2025-06-26) 0.10.37 (2025-06-26)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
Fixed Fixed
...@@ -10,7 +10,7 @@ Fixed ...@@ -10,7 +10,7 @@ Fixed
* Relaxed upper range pin for protobuf python dependency for more permissive installation. * Relaxed upper range pin for protobuf python dependency for more permissive installation.
0.10.35 (2025-05-22) 0.10.36 (2025-05-22)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
Fixed Fixed
...@@ -19,7 +19,7 @@ Fixed ...@@ -19,7 +19,7 @@ Fixed
* Fixed redundant body_names assignment in rough_env_cfg.py for H1 robot. * Fixed redundant body_names assignment in rough_env_cfg.py for H1 robot.
0.10.34 (2025-06-16) 0.10.35 (2025-06-16)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
Changed Changed
...@@ -28,7 +28,7 @@ Changed ...@@ -28,7 +28,7 @@ Changed
* Show available RL library configs on error message when an entry point key is not available for a given task. * Show available RL library configs on error message when an entry point key is not available for a given task.
0.10.33 (2025-05-15) 0.10.34 (2025-05-15)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
Added Added
...@@ -38,7 +38,7 @@ Added ...@@ -38,7 +38,7 @@ Added
implements assembly tasks to insert pegs into their corresponding sockets. implements assembly tasks to insert pegs into their corresponding sockets.
0.10.32 (2025-05-21) 0.10.33 (2025-05-21)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
Added Added
...@@ -48,6 +48,15 @@ Added ...@@ -48,6 +48,15 @@ Added
can be pushed to a visualization dashboard to track improvements or regressions. can be pushed to a visualization dashboard to track improvements or regressions.
0.10.32 (2025-05-21)
~~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added new GR1 tasks (``Isaac-NutPour-GR1T2-Pink-IK-Abs-v0``, and ``Isaac-ExhaustPipe-GR1T2-Pink-IK-Abs-v0``).
0.10.31 (2025-04-02) 0.10.31 (2025-04-02)
~~~~~~~~~~~~~~~~~~~~ ~~~~~~~~~~~~~~~~~~~~
......
...@@ -11,7 +11,7 @@ ...@@ -11,7 +11,7 @@
import gymnasium as gym import gymnasium as gym
import os import os
from . import agents, pickplace_gr1t2_env_cfg from . import agents, exhaustpipe_gr1t2_pink_ik_env_cfg, nutpour_gr1t2_pink_ik_env_cfg, pickplace_gr1t2_env_cfg
gym.register( gym.register(
id="Isaac-PickPlace-GR1T2-Abs-v0", id="Isaac-PickPlace-GR1T2-Abs-v0",
...@@ -22,3 +22,23 @@ gym.register( ...@@ -22,3 +22,23 @@ gym.register(
}, },
disable_env_checker=True, disable_env_checker=True,
) )
gym.register(
id="Isaac-NutPour-GR1T2-Pink-IK-Abs-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": nutpour_gr1t2_pink_ik_env_cfg.NutPourGR1T2PinkIKEnvCfg,
"robomimic_bc_cfg_entry_point": os.path.join(agents.__path__[0], "robomimic/bc_rnn_image_nut_pouring.json"),
},
disable_env_checker=True,
)
gym.register(
id="Isaac-ExhaustPipe-GR1T2-Pink-IK-Abs-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
kwargs={
"env_cfg_entry_point": exhaustpipe_gr1t2_pink_ik_env_cfg.ExhaustPipeGR1T2PinkIKEnvCfg,
"robomimic_bc_cfg_entry_point": os.path.join(agents.__path__[0], "robomimic/bc_rnn_image_exhaust_pipe.json"),
},
disable_env_checker=True,
)
{
"algo_name": "bc",
"experiment": {
"name": "bc_rnn_image_gr1_exhaust_pipe",
"validate": false,
"logging": {
"terminal_output_to_txt": true,
"log_tb": true
},
"save": {
"enabled": true,
"every_n_seconds": null,
"every_n_epochs": 20,
"epochs": [],
"on_best_validation": false,
"on_best_rollout_return": false,
"on_best_rollout_success_rate": true
},
"epoch_every_n_steps": 500,
"env": null,
"additional_envs": null,
"render": false,
"render_video": false,
"rollout": {
"enabled": false
}
},
"train": {
"data": null,
"num_data_workers": 4,
"hdf5_cache_mode": "low_dim",
"hdf5_use_swmr": true,
"hdf5_load_next_obs": false,
"hdf5_normalize_obs": false,
"hdf5_filter_key": null,
"hdf5_validation_filter_key": null,
"seq_length": 10,
"pad_seq_length": true,
"frame_stack": 1,
"pad_frame_stack": true,
"dataset_keys": [
"actions",
"rewards",
"dones"
],
"goal_mode": null,
"cuda": true,
"batch_size": 16,
"num_epochs": 600,
"seed": 101
},
"algo": {
"optim_params": {
"policy": {
"optimizer_type": "adam",
"learning_rate": {
"initial": 0.0001,
"decay_factor": 0.1,
"epoch_schedule": [],
"scheduler_type": "multistep"
},
"regularization": {
"L2": 0.0
}
}
},
"loss": {
"l2_weight": 1.0,
"l1_weight": 0.0,
"cos_weight": 0.0
},
"actor_layer_dims": [],
"gaussian": {
"enabled": false,
"fixed_std": false,
"init_std": 0.1,
"min_std": 0.01,
"std_activation": "softplus",
"low_noise_eval": true
},
"gmm": {
"enabled": true,
"num_modes": 5,
"min_std": 0.0001,
"std_activation": "softplus",
"low_noise_eval": true
},
"vae": {
"enabled": false,
"latent_dim": 14,
"latent_clip": null,
"kl_weight": 1.0,
"decoder": {
"is_conditioned": true,
"reconstruction_sum_across_elements": false
},
"prior": {
"learn": false,
"is_conditioned": false,
"use_gmm": false,
"gmm_num_modes": 10,
"gmm_learn_weights": false,
"use_categorical": false,
"categorical_dim": 10,
"categorical_gumbel_softmax_hard": false,
"categorical_init_temp": 1.0,
"categorical_temp_anneal_step": 0.001,
"categorical_min_temp": 0.3
},
"encoder_layer_dims": [
300,
400
],
"decoder_layer_dims": [
300,
400
],
"prior_layer_dims": [
300,
400
]
},
"rnn": {
"enabled": true,
"horizon": 10,
"hidden_dim": 1000,
"rnn_type": "LSTM",
"num_layers": 2,
"open_loop": false,
"kwargs": {
"bidirectional": false
}
},
"transformer": {
"enabled": false,
"context_length": 10,
"embed_dim": 512,
"num_layers": 6,
"num_heads": 8,
"emb_dropout": 0.1,
"attn_dropout": 0.1,
"block_output_dropout": 0.1,
"sinusoidal_embedding": false,
"activation": "gelu",
"supervise_all_steps": false,
"nn_parameter_for_timesteps": true
}
},
"observation": {
"modalities": {
"obs": {
"low_dim": [
"left_eef_pos",
"left_eef_quat",
"right_eef_pos",
"right_eef_quat",
"hand_joint_state"
],
"rgb": [
"robot_pov_cam"
],
"depth": [],
"scan": []
},
"goal": {
"low_dim": [],
"rgb": [],
"depth": [],
"scan": []
}
},
"encoder": {
"low_dim": {
"core_class": null,
"core_kwargs": {},
"obs_randomizer_class": null,
"obs_randomizer_kwargs": {}
},
"rgb": {
"core_class": "VisualCore",
"core_kwargs": {
"feature_dimension": 64,
"flatten": true,
"backbone_class": "ResNet18Conv",
"backbone_kwargs": {
"pretrained": false,
"input_coord_conv": false
},
"pool_class": "SpatialSoftmax",
"pool_kwargs": {
"num_kp": 32,
"learnable_temperature": false,
"temperature": 1.0,
"noise_std": 0.0,
"output_variance": false
}
},
"obs_randomizer_class": "CropRandomizer",
"obs_randomizer_kwargs": {
"crop_height": 144,
"crop_width": 236,
"num_crops": 1,
"pos_enc": false
}
},
"depth": {
"core_class": "VisualCore",
"core_kwargs": {},
"obs_randomizer_class": null,
"obs_randomizer_kwargs": {}
},
"scan": {
"core_class": "ScanCore",
"core_kwargs": {},
"obs_randomizer_class": null,
"obs_randomizer_kwargs": {}
}
}
}
}
{
"algo_name": "bc",
"experiment": {
"name": "bc_rnn_image_gr1_nut_pouring",
"validate": false,
"logging": {
"terminal_output_to_txt": true,
"log_tb": true
},
"save": {
"enabled": true,
"every_n_seconds": null,
"every_n_epochs": 20,
"epochs": [],
"on_best_validation": false,
"on_best_rollout_return": false,
"on_best_rollout_success_rate": true
},
"epoch_every_n_steps": 500,
"env": null,
"additional_envs": null,
"render": false,
"render_video": false,
"rollout": {
"enabled": false
}
},
"train": {
"data": null,
"num_data_workers": 4,
"hdf5_cache_mode": "low_dim",
"hdf5_use_swmr": true,
"hdf5_load_next_obs": false,
"hdf5_normalize_obs": false,
"hdf5_filter_key": null,
"hdf5_validation_filter_key": null,
"seq_length": 10,
"pad_seq_length": true,
"frame_stack": 1,
"pad_frame_stack": true,
"dataset_keys": [
"actions",
"rewards",
"dones"
],
"goal_mode": null,
"cuda": true,
"batch_size": 16,
"num_epochs": 600,
"seed": 101
},
"algo": {
"optim_params": {
"policy": {
"optimizer_type": "adam",
"learning_rate": {
"initial": 0.0001,
"decay_factor": 0.1,
"epoch_schedule": [],
"scheduler_type": "multistep"
},
"regularization": {
"L2": 0.0
}
}
},
"loss": {
"l2_weight": 1.0,
"l1_weight": 0.0,
"cos_weight": 0.0
},
"actor_layer_dims": [],
"gaussian": {
"enabled": false,
"fixed_std": false,
"init_std": 0.1,
"min_std": 0.01,
"std_activation": "softplus",
"low_noise_eval": true
},
"gmm": {
"enabled": true,
"num_modes": 5,
"min_std": 0.0001,
"std_activation": "softplus",
"low_noise_eval": true
},
"vae": {
"enabled": false,
"latent_dim": 14,
"latent_clip": null,
"kl_weight": 1.0,
"decoder": {
"is_conditioned": true,
"reconstruction_sum_across_elements": false
},
"prior": {
"learn": false,
"is_conditioned": false,
"use_gmm": false,
"gmm_num_modes": 10,
"gmm_learn_weights": false,
"use_categorical": false,
"categorical_dim": 10,
"categorical_gumbel_softmax_hard": false,
"categorical_init_temp": 1.0,
"categorical_temp_anneal_step": 0.001,
"categorical_min_temp": 0.3
},
"encoder_layer_dims": [
300,
400
],
"decoder_layer_dims": [
300,
400
],
"prior_layer_dims": [
300,
400
]
},
"rnn": {
"enabled": true,
"horizon": 10,
"hidden_dim": 1000,
"rnn_type": "LSTM",
"num_layers": 2,
"open_loop": false,
"kwargs": {
"bidirectional": false
}
},
"transformer": {
"enabled": false,
"context_length": 10,
"embed_dim": 512,
"num_layers": 6,
"num_heads": 8,
"emb_dropout": 0.1,
"attn_dropout": 0.1,
"block_output_dropout": 0.1,
"sinusoidal_embedding": false,
"activation": "gelu",
"supervise_all_steps": false,
"nn_parameter_for_timesteps": true
}
},
"observation": {
"modalities": {
"obs": {
"low_dim": [
"left_eef_pos",
"left_eef_quat",
"right_eef_pos",
"right_eef_quat",
"hand_joint_state"
],
"rgb": [
"robot_pov_cam"
],
"depth": [],
"scan": []
},
"goal": {
"low_dim": [],
"rgb": [],
"depth": [],
"scan": []
}
},
"encoder": {
"low_dim": {
"core_class": null,
"core_kwargs": {},
"obs_randomizer_class": null,
"obs_randomizer_kwargs": {}
},
"rgb": {
"core_class": "VisualCore",
"core_kwargs": {
"feature_dimension": 64,
"flatten": true,
"backbone_class": "ResNet18Conv",
"backbone_kwargs": {
"pretrained": false,
"input_coord_conv": false
},
"pool_class": "SpatialSoftmax",
"pool_kwargs": {
"num_kp": 32,
"learnable_temperature": false,
"temperature": 1.0,
"noise_std": 0.0,
"output_variance": false
}
},
"obs_randomizer_class": "CropRandomizer",
"obs_randomizer_kwargs": {
"crop_height": 144,
"crop_width": 236,
"num_crops": 1,
"pos_enc": false
}
},
"depth": {
"core_class": "VisualCore",
"core_kwargs": {},
"obs_randomizer_class": null,
"obs_randomizer_kwargs": {}
},
"scan": {
"core_class": "ScanCore",
"core_kwargs": {},
"obs_randomizer_class": null,
"obs_randomizer_kwargs": {}
}
}
}
}
# Copyright (c) 2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from pink.tasks import FrameTask
import isaaclab.controllers.utils as ControllerUtils
from isaaclab.controllers.pink_ik_cfg import PinkIKControllerCfg
from isaaclab.envs.mdp.actions.pink_actions_cfg import PinkInverseKinematicsActionCfg
from isaaclab.utils import configclass
from isaaclab_tasks.manager_based.manipulation.pick_place.exhaustpipe_gr1t2_base_env_cfg import (
ExhaustPipeGR1T2BaseEnvCfg,
)
@configclass
class ExhaustPipeGR1T2PinkIKEnvCfg(ExhaustPipeGR1T2BaseEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
self.actions.gr1_action = PinkInverseKinematicsActionCfg(
pink_controlled_joint_names=[
"left_shoulder_pitch_joint",
"left_shoulder_roll_joint",
"left_shoulder_yaw_joint",
"left_elbow_pitch_joint",
"left_wrist_yaw_joint",
"left_wrist_roll_joint",
"left_wrist_pitch_joint",
"right_shoulder_pitch_joint",
"right_shoulder_roll_joint",
"right_shoulder_yaw_joint",
"right_elbow_pitch_joint",
"right_wrist_yaw_joint",
"right_wrist_roll_joint",
"right_wrist_pitch_joint",
],
# Joints to be locked in URDF
ik_urdf_fixed_joint_names=[
"left_hip_roll_joint",
"right_hip_roll_joint",
"left_hip_yaw_joint",
"right_hip_yaw_joint",
"left_hip_pitch_joint",
"right_hip_pitch_joint",
"left_knee_pitch_joint",
"right_knee_pitch_joint",
"left_ankle_pitch_joint",
"right_ankle_pitch_joint",
"left_ankle_roll_joint",
"right_ankle_roll_joint",
"L_index_proximal_joint",
"L_middle_proximal_joint",
"L_pinky_proximal_joint",
"L_ring_proximal_joint",
"L_thumb_proximal_yaw_joint",
"R_index_proximal_joint",
"R_middle_proximal_joint",
"R_pinky_proximal_joint",
"R_ring_proximal_joint",
"R_thumb_proximal_yaw_joint",
"L_index_intermediate_joint",
"L_middle_intermediate_joint",
"L_pinky_intermediate_joint",
"L_ring_intermediate_joint",
"L_thumb_proximal_pitch_joint",
"R_index_intermediate_joint",
"R_middle_intermediate_joint",
"R_pinky_intermediate_joint",
"R_ring_intermediate_joint",
"R_thumb_proximal_pitch_joint",
"L_thumb_distal_joint",
"R_thumb_distal_joint",
"head_roll_joint",
"head_pitch_joint",
"head_yaw_joint",
"waist_yaw_joint",
"waist_pitch_joint",
"waist_roll_joint",
],
hand_joint_names=[
"L_index_proximal_joint",
"L_middle_proximal_joint",
"L_pinky_proximal_joint",
"L_ring_proximal_joint",
"L_thumb_proximal_yaw_joint",
"R_index_proximal_joint",
"R_middle_proximal_joint",
"R_pinky_proximal_joint",
"R_ring_proximal_joint",
"R_thumb_proximal_yaw_joint",
"L_index_intermediate_joint",
"L_middle_intermediate_joint",
"L_pinky_intermediate_joint",
"L_ring_intermediate_joint",
"L_thumb_proximal_pitch_joint",
"R_index_intermediate_joint",
"R_middle_intermediate_joint",
"R_pinky_intermediate_joint",
"R_ring_intermediate_joint",
"R_thumb_proximal_pitch_joint",
"L_thumb_distal_joint",
"R_thumb_distal_joint",
],
# the robot in the sim scene we are controlling
asset_name="robot",
# Configuration for the IK controller
# The frames names are the ones present in the URDF file
# The urdf has to be generated from the USD that is being used in the scene
controller=PinkIKControllerCfg(
articulation_name="robot",
base_link_name="base_link",
num_hand_joints=22,
show_ik_warnings=False,
variable_input_tasks=[
FrameTask(
"GR1T2_fourier_hand_6dof_left_hand_pitch_link",
position_cost=1.0, # [cost] / [m]
orientation_cost=1.0, # [cost] / [rad]
lm_damping=10, # dampening for solver for step jumps
gain=0.1,
),
FrameTask(
"GR1T2_fourier_hand_6dof_right_hand_pitch_link",
position_cost=1.0, # [cost] / [m]
orientation_cost=1.0, # [cost] / [rad]
lm_damping=10, # dampening for solver for step jumps
gain=0.1,
),
],
fixed_input_tasks=[
# COMMENT OUT IF LOCKING WAIST/HEAD
# FrameTask(
# "GR1T2_fourier_hand_6dof_head_yaw_link",
# position_cost=1.0, # [cost] / [m]
# orientation_cost=0.05, # [cost] / [rad]
# ),
],
),
)
# Convert USD to URDF and change revolute joints to fixed
temp_urdf_output_path, temp_urdf_meshes_output_path = ControllerUtils.convert_usd_to_urdf(
self.scene.robot.spawn.usd_path, self.temp_urdf_dir, force_conversion=True
)
ControllerUtils.change_revolute_to_fixed(
temp_urdf_output_path, self.actions.gr1_action.ik_urdf_fixed_joint_names
)
# Set the URDF and mesh paths for the IK controller
self.actions.gr1_action.controller.urdf_path = temp_urdf_output_path
self.actions.gr1_action.controller.mesh_path = temp_urdf_meshes_output_path
...@@ -13,4 +13,5 @@ ...@@ -13,4 +13,5 @@
from isaaclab.envs.mdp import * # noqa: F401, F403 from isaaclab.envs.mdp import * # noqa: F401, F403
from .observations import * # noqa: F401, F403 from .observations import * # noqa: F401, F403
from .pick_place_events import * # noqa: F401, F403
from .terminations import * # noqa: F401, F403 from .terminations import * # noqa: F401, F403
# Copyright (c) 2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import torch
from typing import TYPE_CHECKING
import isaaclab.utils.math as math_utils
from isaaclab.managers import SceneEntityCfg
if TYPE_CHECKING:
from isaaclab.envs import ManagerBasedEnv
def reset_object_poses_nut_pour(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
pose_range: dict[str, tuple[float, float]],
sorting_beaker_cfg: SceneEntityCfg = SceneEntityCfg("sorting_beaker"),
factory_nut_cfg: SceneEntityCfg = SceneEntityCfg("factory_nut"),
sorting_bowl_cfg: SceneEntityCfg = SceneEntityCfg("sorting_bowl"),
sorting_scale_cfg: SceneEntityCfg = SceneEntityCfg("sorting_scale"),
):
"""Reset the asset root states to a random position and orientation uniformly within the given ranges.
Args:
env: The RL environment instance.
env_ids: The environment IDs to reset the object poses for.
sorting_beaker_cfg: The configuration for the sorting beaker asset.
factory_nut_cfg: The configuration for the factory nut asset.
sorting_bowl_cfg: The configuration for the sorting bowl asset.
sorting_scale_cfg: The configuration for the sorting scale asset.
pose_range: The dictionary of pose ranges for the objects. Keys are
``x``, ``y``, ``z``, ``roll``, ``pitch``, and ``yaw``.
"""
# extract the used quantities (to enable type-hinting)
sorting_beaker = env.scene[sorting_beaker_cfg.name]
factory_nut = env.scene[factory_nut_cfg.name]
sorting_bowl = env.scene[sorting_bowl_cfg.name]
sorting_scale = env.scene[sorting_scale_cfg.name]
# get default root state
sorting_beaker_root_states = sorting_beaker.data.default_root_state[env_ids].clone()
factory_nut_root_states = factory_nut.data.default_root_state[env_ids].clone()
sorting_bowl_root_states = sorting_bowl.data.default_root_state[env_ids].clone()
sorting_scale_root_states = sorting_scale.data.default_root_state[env_ids].clone()
# get pose ranges
range_list = [pose_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z", "roll", "pitch", "yaw"]]
ranges = torch.tensor(range_list, device=sorting_beaker.device)
# randomize sorting beaker and factory nut together
rand_samples = math_utils.sample_uniform(
ranges[:, 0], ranges[:, 1], (len(env_ids), 6), device=sorting_beaker.device
)
orientations_delta = math_utils.quat_from_euler_xyz(rand_samples[:, 3], rand_samples[:, 4], rand_samples[:, 5])
positions_sorting_beaker = (
sorting_beaker_root_states[:, 0:3] + env.scene.env_origins[env_ids] + rand_samples[:, 0:3]
)
positions_factory_nut = factory_nut_root_states[:, 0:3] + env.scene.env_origins[env_ids] + rand_samples[:, 0:3]
orientations_sorting_beaker = math_utils.quat_mul(sorting_beaker_root_states[:, 3:7], orientations_delta)
orientations_factory_nut = math_utils.quat_mul(factory_nut_root_states[:, 3:7], orientations_delta)
# randomize sorting bowl
rand_samples = math_utils.sample_uniform(
ranges[:, 0], ranges[:, 1], (len(env_ids), 6), device=sorting_beaker.device
)
orientations_delta = math_utils.quat_from_euler_xyz(rand_samples[:, 3], rand_samples[:, 4], rand_samples[:, 5])
positions_sorting_bowl = sorting_bowl_root_states[:, 0:3] + env.scene.env_origins[env_ids] + rand_samples[:, 0:3]
orientations_sorting_bowl = math_utils.quat_mul(sorting_bowl_root_states[:, 3:7], orientations_delta)
# randomize scorting scale
rand_samples = math_utils.sample_uniform(
ranges[:, 0], ranges[:, 1], (len(env_ids), 6), device=sorting_beaker.device
)
orientations_delta = math_utils.quat_from_euler_xyz(rand_samples[:, 3], rand_samples[:, 4], rand_samples[:, 5])
positions_sorting_scale = sorting_scale_root_states[:, 0:3] + env.scene.env_origins[env_ids] + rand_samples[:, 0:3]
orientations_sorting_scale = math_utils.quat_mul(sorting_scale_root_states[:, 3:7], orientations_delta)
# set into the physics simulation
sorting_beaker.write_root_pose_to_sim(
torch.cat([positions_sorting_beaker, orientations_sorting_beaker], dim=-1), env_ids=env_ids
)
factory_nut.write_root_pose_to_sim(
torch.cat([positions_factory_nut, orientations_factory_nut], dim=-1), env_ids=env_ids
)
sorting_bowl.write_root_pose_to_sim(
torch.cat([positions_sorting_bowl, orientations_sorting_bowl], dim=-1), env_ids=env_ids
)
sorting_scale.write_root_pose_to_sim(
torch.cat([positions_sorting_scale, orientations_sorting_scale], dim=-1), env_ids=env_ids
)
...@@ -85,3 +85,134 @@ def task_done( ...@@ -85,3 +85,134 @@ def task_done(
done = torch.logical_and(done, wheel_vel[:, 2] < min_vel) done = torch.logical_and(done, wheel_vel[:, 2] < min_vel)
return done return done
def task_done_nut_pour(
env: ManagerBasedRLEnv,
sorting_scale_cfg: SceneEntityCfg = SceneEntityCfg("sorting_scale"),
sorting_bowl_cfg: SceneEntityCfg = SceneEntityCfg("sorting_bowl"),
sorting_beaker_cfg: SceneEntityCfg = SceneEntityCfg("sorting_beaker"),
factory_nut_cfg: SceneEntityCfg = SceneEntityCfg("factory_nut"),
sorting_bin_cfg: SceneEntityCfg = SceneEntityCfg("black_sorting_bin"),
max_bowl_to_scale_x: float = 0.055,
max_bowl_to_scale_y: float = 0.055,
max_bowl_to_scale_z: float = 0.025,
max_nut_to_bowl_x: float = 0.050,
max_nut_to_bowl_y: float = 0.050,
max_nut_to_bowl_z: float = 0.019,
max_beaker_to_bin_x: float = 0.08,
max_beaker_to_bin_y: float = 0.12,
max_beaker_to_bin_z: float = 0.07,
) -> torch.Tensor:
"""Determine if the nut pouring task is complete.
This function checks whether all success conditions for the task have been met:
1. The factory nut is in the sorting bowl
3. The sorting bowl is placed on the sorting scale
Args:
env: The RL environment instance.
sorting_scale_cfg: Configuration for the sorting scale entity.
sorting_bowl_cfg: Configuration for the sorting bowl entity.
sorting_beaker_cfg: Configuration for the sorting beaker entity.
factory_nut_cfg: Configuration for the factory nut entity.
sorting_bin_cfg: Configuration for the sorting bin entity.
max_bowl_to_scale_x: Maximum x position of the sorting bowl relative to the sorting scale for task completion.
max_bowl_to_scale_y: Maximum y position of the sorting bowl relative to the sorting scale for task completion.
max_bowl_to_scale_z: Maximum z position of the sorting bowl relative to the sorting scale for task completion.
max_nut_to_bowl_x: Maximum x position of the factory nut relative to the sorting bowl for task completion.
max_nut_to_bowl_y: Maximum y position of the factory nut relative to the sorting bowl for task completion.
max_nut_to_bowl_z: Maximum z position of the factory nut relative to the sorting bowl for task completion.
max_beaker_to_bin_x: Maximum x position of the sorting beaker relative to the sorting bin for task completion.
max_beaker_to_bin_y: Maximum y position of the sorting beaker relative to the sorting bin for task completion.
max_beaker_to_bin_z: Maximum z position of the sorting beaker relative to the sorting bin for task completion.
Returns:
Boolean tensor indicating which environments have completed the task.
"""
# Get object entities from the scene
sorting_scale: RigidObject = env.scene[sorting_scale_cfg.name]
sorting_bowl: RigidObject = env.scene[sorting_bowl_cfg.name]
factory_nut: RigidObject = env.scene[factory_nut_cfg.name]
sorting_beaker: RigidObject = env.scene[sorting_beaker_cfg.name]
sorting_bin: RigidObject = env.scene[sorting_bin_cfg.name]
# Get positions relative to environment origin
scale_pos = sorting_scale.data.root_pos_w - env.scene.env_origins
bowl_pos = sorting_bowl.data.root_pos_w - env.scene.env_origins
sorting_beaker_pos = sorting_beaker.data.root_pos_w - env.scene.env_origins
nut_pos = factory_nut.data.root_pos_w - env.scene.env_origins
bin_pos = sorting_bin.data.root_pos_w - env.scene.env_origins
# nut to bowl
nut_to_bowl_x = torch.abs(nut_pos[:, 0] - bowl_pos[:, 0])
nut_to_bowl_y = torch.abs(nut_pos[:, 1] - bowl_pos[:, 1])
nut_to_bowl_z = nut_pos[:, 2] - bowl_pos[:, 2]
# bowl to scale
bowl_to_scale_x = torch.abs(bowl_pos[:, 0] - scale_pos[:, 0])
bowl_to_scale_y = torch.abs(bowl_pos[:, 1] - scale_pos[:, 1])
bowl_to_scale_z = bowl_pos[:, 2] - scale_pos[:, 2]
# beaker to bin
beaker_to_bin_x = torch.abs(sorting_beaker_pos[:, 0] - bin_pos[:, 0])
beaker_to_bin_y = torch.abs(sorting_beaker_pos[:, 1] - bin_pos[:, 1])
beaker_to_bin_z = sorting_beaker_pos[:, 2] - bin_pos[:, 2]
done = nut_to_bowl_x < max_nut_to_bowl_x
done = torch.logical_and(done, nut_to_bowl_y < max_nut_to_bowl_y)
done = torch.logical_and(done, nut_to_bowl_z < max_nut_to_bowl_z)
done = torch.logical_and(done, bowl_to_scale_x < max_bowl_to_scale_x)
done = torch.logical_and(done, bowl_to_scale_y < max_bowl_to_scale_y)
done = torch.logical_and(done, bowl_to_scale_z < max_bowl_to_scale_z)
done = torch.logical_and(done, beaker_to_bin_x < max_beaker_to_bin_x)
done = torch.logical_and(done, beaker_to_bin_y < max_beaker_to_bin_y)
done = torch.logical_and(done, beaker_to_bin_z < max_beaker_to_bin_z)
return done
def task_done_exhaust_pipe(
env: ManagerBasedRLEnv,
blue_exhaust_pipe_cfg: SceneEntityCfg = SceneEntityCfg("blue_exhaust_pipe"),
blue_sorting_bin_cfg: SceneEntityCfg = SceneEntityCfg("blue_sorting_bin"),
max_blue_exhaust_to_bin_x: float = 0.085,
max_blue_exhaust_to_bin_y: float = 0.200,
min_blue_exhaust_to_bin_y: float = -0.090,
max_blue_exhaust_to_bin_z: float = 0.070,
) -> torch.Tensor:
"""Determine if the exhaust pipe task is complete.
This function checks whether all success conditions for the task have been met:
1. The blue exhaust pipe is placed in the correct position
Args:
env: The RL environment instance.
blue_exhaust_pipe_cfg: Configuration for the blue exhaust pipe entity.
blue_sorting_bin_cfg: Configuration for the blue sorting bin entity.
max_blue_exhaust_to_bin_x: Maximum x position of the blue exhaust pipe relative to the blue sorting bin for task completion.
max_blue_exhaust_to_bin_y: Maximum y position of the blue exhaust pipe relative to the blue sorting bin for task completion.
max_blue_exhaust_to_bin_z: Maximum z position of the blue exhaust pipe relative to the blue sorting bin for task completion.
Returns:
Boolean tensor indicating which environments have completed the task.
"""
# Get object entities from the scene
blue_exhaust_pipe: RigidObject = env.scene[blue_exhaust_pipe_cfg.name]
blue_sorting_bin: RigidObject = env.scene[blue_sorting_bin_cfg.name]
# Get positions relative to environment origin
blue_exhaust_pipe_pos = blue_exhaust_pipe.data.root_pos_w - env.scene.env_origins
blue_sorting_bin_pos = blue_sorting_bin.data.root_pos_w - env.scene.env_origins
# blue exhaust to bin
blue_exhaust_to_bin_x = torch.abs(blue_exhaust_pipe_pos[:, 0] - blue_sorting_bin_pos[:, 0])
blue_exhaust_to_bin_y = blue_exhaust_pipe_pos[:, 1] - blue_sorting_bin_pos[:, 1]
blue_exhaust_to_bin_z = blue_exhaust_pipe_pos[:, 2] - blue_sorting_bin_pos[:, 2]
done = blue_exhaust_to_bin_x < max_blue_exhaust_to_bin_x
done = torch.logical_and(done, blue_exhaust_to_bin_y < max_blue_exhaust_to_bin_y)
done = torch.logical_and(done, blue_exhaust_to_bin_y > min_blue_exhaust_to_bin_y)
done = torch.logical_and(done, blue_exhaust_to_bin_z < max_blue_exhaust_to_bin_z)
return done
# Copyright (c) 2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from pink.tasks import FrameTask
import isaaclab.controllers.utils as ControllerUtils
from isaaclab.controllers.pink_ik_cfg import PinkIKControllerCfg
from isaaclab.envs.mdp.actions.pink_actions_cfg import PinkInverseKinematicsActionCfg
from isaaclab.utils import configclass
from isaaclab_tasks.manager_based.manipulation.pick_place.nutpour_gr1t2_base_env_cfg import NutPourGR1T2BaseEnvCfg
@configclass
class NutPourGR1T2PinkIKEnvCfg(NutPourGR1T2BaseEnvCfg):
def __post_init__(self):
# post init of parent
super().__post_init__()
self.actions.gr1_action = PinkInverseKinematicsActionCfg(
pink_controlled_joint_names=[
"left_shoulder_pitch_joint",
"left_shoulder_roll_joint",
"left_shoulder_yaw_joint",
"left_elbow_pitch_joint",
"left_wrist_yaw_joint",
"left_wrist_roll_joint",
"left_wrist_pitch_joint",
"right_shoulder_pitch_joint",
"right_shoulder_roll_joint",
"right_shoulder_yaw_joint",
"right_elbow_pitch_joint",
"right_wrist_yaw_joint",
"right_wrist_roll_joint",
"right_wrist_pitch_joint",
],
# Joints to be locked in URDF
ik_urdf_fixed_joint_names=[
"left_hip_roll_joint",
"right_hip_roll_joint",
"left_hip_yaw_joint",
"right_hip_yaw_joint",
"left_hip_pitch_joint",
"right_hip_pitch_joint",
"left_knee_pitch_joint",
"right_knee_pitch_joint",
"left_ankle_pitch_joint",
"right_ankle_pitch_joint",
"left_ankle_roll_joint",
"right_ankle_roll_joint",
"L_index_proximal_joint",
"L_middle_proximal_joint",
"L_pinky_proximal_joint",
"L_ring_proximal_joint",
"L_thumb_proximal_yaw_joint",
"R_index_proximal_joint",
"R_middle_proximal_joint",
"R_pinky_proximal_joint",
"R_ring_proximal_joint",
"R_thumb_proximal_yaw_joint",
"L_index_intermediate_joint",
"L_middle_intermediate_joint",
"L_pinky_intermediate_joint",
"L_ring_intermediate_joint",
"L_thumb_proximal_pitch_joint",
"R_index_intermediate_joint",
"R_middle_intermediate_joint",
"R_pinky_intermediate_joint",
"R_ring_intermediate_joint",
"R_thumb_proximal_pitch_joint",
"L_thumb_distal_joint",
"R_thumb_distal_joint",
"head_roll_joint",
"head_pitch_joint",
"head_yaw_joint",
"waist_yaw_joint",
"waist_pitch_joint",
"waist_roll_joint",
],
hand_joint_names=[
"L_index_proximal_joint",
"L_middle_proximal_joint",
"L_pinky_proximal_joint",
"L_ring_proximal_joint",
"L_thumb_proximal_yaw_joint",
"R_index_proximal_joint",
"R_middle_proximal_joint",
"R_pinky_proximal_joint",
"R_ring_proximal_joint",
"R_thumb_proximal_yaw_joint",
"L_index_intermediate_joint",
"L_middle_intermediate_joint",
"L_pinky_intermediate_joint",
"L_ring_intermediate_joint",
"L_thumb_proximal_pitch_joint",
"R_index_intermediate_joint",
"R_middle_intermediate_joint",
"R_pinky_intermediate_joint",
"R_ring_intermediate_joint",
"R_thumb_proximal_pitch_joint",
"L_thumb_distal_joint",
"R_thumb_distal_joint",
],
# the robot in the sim scene we are controlling
asset_name="robot",
# Configuration for the IK controller
# The frames names are the ones present in the URDF file
# The urdf has to be generated from the USD that is being used in the scene
controller=PinkIKControllerCfg(
articulation_name="robot",
base_link_name="base_link",
num_hand_joints=22,
show_ik_warnings=False,
variable_input_tasks=[
FrameTask(
"GR1T2_fourier_hand_6dof_left_hand_pitch_link",
position_cost=1.0, # [cost] / [m]
orientation_cost=1.0, # [cost] / [rad]
lm_damping=10, # dampening for solver for step jumps
gain=0.1,
),
FrameTask(
"GR1T2_fourier_hand_6dof_right_hand_pitch_link",
position_cost=1.0, # [cost] / [m]
orientation_cost=1.0, # [cost] / [rad]
lm_damping=10, # dampening for solver for step jumps
gain=0.1,
),
],
fixed_input_tasks=[
# COMMENT OUT IF LOCKING WAIST/HEAD
# FrameTask(
# "GR1T2_fourier_hand_6dof_head_yaw_link",
# position_cost=1.0, # [cost] / [m]
# orientation_cost=0.05, # [cost] / [rad]
# ),
],
),
)
# Convert USD to URDF and change revolute joints to fixed
temp_urdf_output_path, temp_urdf_meshes_output_path = ControllerUtils.convert_usd_to_urdf(
self.scene.robot.spawn.usd_path, self.temp_urdf_dir, force_conversion=True
)
ControllerUtils.change_revolute_to_fixed(
temp_urdf_output_path, self.actions.gr1_action.ik_urdf_fixed_joint_names
)
# Set the URDF and mesh paths for the IK controller
self.actions.gr1_action.controller.urdf_path = temp_urdf_output_path
self.actions.gr1_action.controller.mesh_path = temp_urdf_meshes_output_path
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment