Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions source/isaaclab/isaaclab/envs/mdp/events.py
Original file line number Diff line number Diff line change
Expand Up @@ -601,10 +601,10 @@ def randomize(data: torch.Tensor, params: tuple[float, float]) -> torch.Tensor:
global_indices = actuator_joint_indices[actuator_indices]
# Randomize stiffness
if stiffness_distribution_params is not None:
stiffness = actuator.stiffness[env_ids].clone()
stiffness = wp.to_torch(actuator.data.actuator_stiffness)[env_ids].clone()
stiffness[:, actuator_indices] = self.default_joint_stiffness[env_ids][:, global_indices].clone()
randomize(stiffness, stiffness_distribution_params)
actuator.stiffness[env_ids] = stiffness
actuator.data._actuator_stiffness = wp.from_torch(stiffness)
if isinstance(actuator, ImplicitActuator):
self.asset.write_joint_stiffness_to_sim(
stiffness, joint_ids=actuator.joint_indices, env_ids=env_ids
Expand All @@ -614,7 +614,7 @@ def randomize(data: torch.Tensor, params: tuple[float, float]) -> torch.Tensor:
damping = wp.to_torch(self.asset.data.actuator_damping)[env_ids].clone()
damping[:, actuator_indices] = self.default_joint_damping[env_ids][:, global_indices].clone()
randomize(damping, damping_distribution_params)
actuator.damping[env_ids] = damping
actuator.data._actuator_damping = wp.from_torch(damping)
if isinstance(actuator, ImplicitActuator):
self.asset.write_joint_damping_to_sim(damping, joint_ids=actuator.joint_indices, env_ids=env_ids)

Expand Down Expand Up @@ -803,7 +803,7 @@ def __call__(
)
# set the position limits into the physics simulation
self.asset.write_joint_position_limit_to_sim(
joint_pos_limits, joint_ids=joint_ids, env_ids=env_ids, warn_limit_violation=False
joint_pos_limits, joint_ids=joint_ids, env_ids=env_ids
)


Expand Down
12 changes: 7 additions & 5 deletions source/isaaclab/isaaclab/managers/event_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -204,6 +204,8 @@ def apply(

# iterate over all the event terms
for index, term_cfg in enumerate(self._mode_term_cfgs[mode]):
# initialize term_cfg func before call
term_cfg_func_obj = term_cfg.func(term_cfg, self._env)
if mode == "interval":
# extract time left for this term
time_left = self._interval_term_time_left[index]
Expand All @@ -219,7 +221,7 @@ def apply(
self._interval_term_time_left[index][:] = sampled_interval

# call the event term (with None for env_ids)
term_cfg.func(self._env, None, **term_cfg.params)
term_cfg_func_obj(self._env, None, **term_cfg.params)
else:
valid_env_ids = (time_left < 1e-6).nonzero().flatten()
if len(valid_env_ids) > 0:
Expand All @@ -228,7 +230,7 @@ def apply(
self._interval_term_time_left[index][valid_env_ids] = sampled_time

# call the event term
term_cfg.func(self._env, valid_env_ids, **term_cfg.params)
term_cfg_func_obj(self._env, valid_env_ids, **term_cfg.params)
elif mode == "reset":
# obtain the minimum step count between resets
min_step_count = term_cfg.min_step_count_between_reset
Expand All @@ -243,7 +245,7 @@ def apply(
self._reset_term_last_triggered_once[index][env_ids] = True

# call the event term with the environment indices
term_cfg.func(self._env, env_ids, **term_cfg.params)
term_cfg_func_obj(self._env, env_ids, **term_cfg.params)
else:
# extract last reset step for this term
last_triggered_step = self._reset_term_last_triggered_step_id[index][env_ids]
Expand All @@ -269,10 +271,10 @@ def apply(
self._reset_term_last_triggered_step_id[index][valid_env_ids] = global_env_step_count

# call the event term
term_cfg.func(self._env, valid_env_ids, **term_cfg.params)
term_cfg_func_obj(self._env, valid_env_ids, **term_cfg.params)
else:
# call the event term
term_cfg.func(self._env, env_ids, **term_cfg.params)
term_cfg_func_obj(self._env, env_ids, **term_cfg.params)

"""
Operations - Term settings.
Expand Down
84 changes: 84 additions & 0 deletions source/isaaclab_assets/isaaclab_assets/robots/shadow_hand.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""Configuration for the dexterous hand from Shadow Robot.

The following configurations are available:

* :obj:`SHADOW_HAND_CFG`: Shadow Hand with implicit actuator model.

Reference:

* https://www.shadowrobot.com/dexterous-hand-series/

"""

import isaaclab.sim as sim_utils
from isaaclab.actuators import ImplicitActuatorCfg
from isaaclab.assets.articulation import ArticulationCfg
from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR

##
# Configuration
##

SHADOW_HAND_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/ShadowRobot/ShadowHand/shadow_hand_instanceable.usd",
activate_contact_sensors=False,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=True,
retain_accelerations=True,
max_depenetration_velocity=1000.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=True,
solver_position_iteration_count=8,
solver_velocity_iteration_count=0,
sleep_threshold=0.005,
stabilization_threshold=0.0005,
),
# collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0),
joint_drive_props=sim_utils.JointDrivePropertiesCfg(drive_type="force"),
# fixed_tendons_props=sim_utils.FixedTendonPropertiesCfg(limit_stiffness=30.0, damping=0.1),
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 0.5),
rot=(1.0, 0.0, 0.0, 0.0),
joint_pos={".*": 0.0},
),
actuators={
"fingers": ImplicitActuatorCfg(
joint_names_expr=["robot0_WR.*", "robot0_(FF|MF|RF|LF|TH)J(3|2|1)", "robot0_(LF|TH)J4", "robot0_THJ0"],
effort_limit_sim={
"robot0_WRJ1": 4.785,
"robot0_WRJ0": 2.175,
"robot0_(FF|MF|RF|LF)J1": 0.7245,
"robot0_FFJ(3|2)": 0.9,
"robot0_MFJ(3|2)": 0.9,
"robot0_RFJ(3|2)": 0.9,
"robot0_LFJ(4|3|2)": 0.9,
"robot0_THJ4": 2.3722,
"robot0_THJ3": 1.45,
"robot0_THJ(2|1)": 0.99,
"robot0_THJ0": 0.81,
},
stiffness={
"robot0_WRJ.*": 5.0,
"robot0_(FF|MF|RF|LF|TH)J(3|2|1)": 1.0,
"robot0_(LF|TH)J4": 1.0,
"robot0_THJ0": 1.0,
},
damping={
"robot0_WRJ.*": 0.5,
"robot0_(FF|MF|RF|LF|TH)J(3|2|1)": 0.1,
"robot0_(LF|TH)J4": 0.1,
"robot0_THJ0": 0.1,
},
),
},
soft_joint_pos_limit_factor=1.0,
)
"""Configuration of Shadow Hand robot."""
Original file line number Diff line number Diff line change
Expand Up @@ -155,6 +155,16 @@ def joint_mask(self) -> wp.array:
"""Articulation's masked indices that denote which joints are part of the group."""
return self._joint_mask

@property
def joint_indices(self) -> slice | torch.Tensor:
"""Articulation's joint indices that are part of the group.

Note:
If :obj:`slice(None)` is returned, then the group contains all the joints in the articulation.
We do this to avoid unnecessary indexing of the joints for performance reasons.
"""
return self._joint_indices

"""
Operations.
"""
Expand Down Expand Up @@ -230,7 +240,7 @@ def _parse_joint_parameter(self, cfg_value: float | dict[str, float] | None, ori
elif isinstance(cfg_value, dict):
# if dict, then parse the regular expression
indices, _, values = string_utils.resolve_matching_names_values(cfg_value, self.joint_names)
indices_global = [self._joint_indices[i] for i in indices]
indices_global = [self._joint_indices[i].cpu() for i in indices]
wp.launch(
update_array2D_with_array1D_indexed,
dim=(self._num_envs, len(indices_global)),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1041,8 +1041,7 @@ def write_joint_damping_to_sim(

def write_joint_position_limit_to_sim(
self,
lower_limits: wp.array | float,
upper_limits: wp.array | float,
limits: wp.array | float,
joint_ids: Sequence[int] | None = None,
env_ids: Sequence[int] | None = None,
joint_mask: wp.array | None = None,
Expand All @@ -1059,13 +1058,17 @@ def write_joint_position_limit_to_sim(
env_mask: The environment mask. Shape is (num_instances,).
"""
# Resolve indices into mask, convert from partial data to complete data, handles the conversion to warp.
<<<<<<< Updated upstream
if isinstance(upper_limits, torch.Tensor):
if self._temp_joint_pos is None:
self._temp_joint_pos = wp.zeros(
(self.num_instances, self.num_joints), dtype=wp.float32, device=self.device
)
=======
if isinstance(limits, torch.Tensor):
>>>>>>> Stashed changes
upper_limits = make_complete_data_from_torch_dual_index(
upper_limits,
limits[:,0,:,0],
self.num_instances,
self.num_joints,
env_ids,
Expand All @@ -1074,13 +1077,17 @@ def write_joint_position_limit_to_sim(
device=self.device,
out=self._temp_joint_pos,
)
<<<<<<< Updated upstream
if isinstance(lower_limits, torch.Tensor):
if self._temp_joint_vel is None:
self._temp_joint_vel = wp.zeros(
(self.num_instances, self.num_joints), dtype=wp.float32, device=self.device
)
=======
if isinstance(limits, torch.Tensor):
>>>>>>> Stashed changes
lower_limits = make_complete_data_from_torch_dual_index(
lower_limits,
limits[:,0,:,1],
self.num_instances,
self.num_joints,
env_ids,
Expand Down Expand Up @@ -2290,6 +2297,11 @@ def _process_actuators_cfg(self):
f"No joints found for actuator group: {actuator_name} with joint name expression:"
f" {actuator_cfg.joint_names_expr}."
)

if len(joint_names) == self.num_joints:
joint_indices = slice(None)
else:
joint_indices = torch.tensor(joint_indices, device=self.device)
# create actuator collection
# note: for efficiency avoid indexing when over all indices
actuator: ActuatorBase = actuator_cfg.class_type(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -335,33 +335,33 @@ def compute_full_observations(self):
obs[inds] = 0.0
return obs

# def compute_full_state(self):
# states = torch.cat(
# (
# # hand
# unscale(self.hand_dof_pos, self.hand_dof_lower_limits, self.hand_dof_upper_limits),
# self.cfg.vel_obs_scale * self.hand_dof_vel,
# # object
# self.object_pos,
# self.object_rot,
# self.object_linvel,
# self.cfg.vel_obs_scale * self.object_angvel,
# # goal
# self.in_hand_pos,
# self.goal_rot,
# quat_mul(self.object_rot, quat_conjugate(self.goal_rot)),
# # fingertips
# self.fingertip_pos.view(self.num_envs, self.num_fingertips * 3),
# self.fingertip_rot.view(self.num_envs, self.num_fingertips * 4),
# self.fingertip_velocities.view(self.num_envs, self.num_fingertips * 6),
# self.cfg.force_torque_obs_scale
# * self.fingertip_force_sensors.view(self.num_envs, self.num_fingertips * 6),
# # actions
# self.actions,
# ),
# dim=-1,
# )
# return states
def compute_full_state(self):
states = torch.cat(
(
# hand
unscale(self.hand_dof_pos, self.hand_dof_lower_limits, self.hand_dof_upper_limits),
self.cfg.vel_obs_scale * self.hand_dof_vel,
# object
self.object_pos,
self.object_rot,
self.object_linvel,
self.cfg.vel_obs_scale * self.object_angvel,
# goal
self.in_hand_pos,
self.goal_rot,
quat_mul(self.object_rot, quat_conjugate(self.goal_rot)),
# fingertips
self.fingertip_pos.view(self.num_envs, self.num_fingertips * 3),
self.fingertip_rot.view(self.num_envs, self.num_fingertips * 4),
self.fingertip_velocities.view(self.num_envs, self.num_fingertips * 6),
# self.cfg.force_torque_obs_scale *
# self.fingertip_force_sensors.view(self.num_envs, self.num_fingertips * 6),
# actions
self.actions,
),
dim=-1,
)
return states


@torch.jit.script
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

"""
Shadow Hand environment.
"""

import gymnasium as gym

from . import agents

##
# Register Gym environments.
##

inhand_task_entry = "isaaclab_tasks.direct.inhand_manipulation"

gym.register(
id="Isaac-Repose-Cube-Shadow-Direct-v0",
entry_point=f"{inhand_task_entry}.inhand_manipulation_env:InHandManipulationEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.shadow_hand_env_cfg:ShadowHandEnvCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:ShadowHandPPORunnerCfg",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Repose-Cube-Shadow-OpenAI-FF-Direct-v0",
entry_point=f"{inhand_task_entry}.inhand_manipulation_env:InHandManipulationEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.shadow_hand_env_cfg:ShadowHandOpenAIEnvCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_ff_cfg.yaml",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:ShadowHandAsymFFPPORunnerCfg",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_ff_ppo_cfg.yaml",
},
)

gym.register(
id="Isaac-Repose-Cube-Shadow-OpenAI-LSTM-Direct-v0",
entry_point=f"{inhand_task_entry}.inhand_manipulation_env:InHandManipulationEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.shadow_hand_env_cfg:ShadowHandOpenAIEnvCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_lstm_cfg.yaml",
},
)

# -------
# Vision
# -------

gym.register(
id="Isaac-Repose-Cube-Shadow-Vision-Direct-v0",
entry_point=f"{__name__}.shadow_hand_vision_env:ShadowHandVisionEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.shadow_hand_vision_env:ShadowHandVisionEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:ShadowHandVisionFFPPORunnerCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_vision_cfg.yaml",
},
)

gym.register(
id="Isaac-Repose-Cube-Shadow-Vision-Direct-Play-v0",
entry_point=f"{__name__}.shadow_hand_vision_env:ShadowHandVisionEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.shadow_hand_vision_env:ShadowHandVisionEnvPlayCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:ShadowHandVisionFFPPORunnerCfg",
"rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_vision_cfg.yaml",
},
)
Loading