Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: add clip range of JointAction #1476

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
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
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,10 @@ class BinaryJointAction(ActionTerm):

cfg: actions_cfg.BinaryJointActionCfg
"""The configuration of the action term."""

_asset: Articulation
"""The articulation asset on which the action term is applied."""
_clip: dict[str, tuple] | None = None
"""The clip applied to the input action."""

def __init__(self, cfg: actions_cfg.BinaryJointActionCfg, env: ManagerBasedEnv) -> None:
# initialize the action term
Expand Down Expand Up @@ -83,6 +84,13 @@ def __init__(self, cfg: actions_cfg.BinaryJointActionCfg, env: ManagerBasedEnv)
)
self._close_command[index_list] = torch.tensor(value_list, device=self.device)

# parse clip
if cfg.clip is not None:
if isinstance(cfg.clip, dict):
self._clip = cfg.clip
else:
raise ValueError(f"Unsupported clip type: {type(cfg.clip)}. Supported types are dict.")

"""
Properties.
"""
Expand Down Expand Up @@ -115,6 +123,13 @@ def process_actions(self, actions: torch.Tensor):
binary_mask = actions < 0
# compute the command
self._processed_actions = torch.where(binary_mask, self._close_command, self._open_command)
# clip actions
if self._clip is not None:
# resolve the dictionary config
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is it possible to resolve this once at initialization and convert to a torch tensor to avoid more overhead with the loop?

index_list, _, value_list = string_utils.resolve_matching_names_values(self._clip, self._joint_names)
for index in range(len(index_list)):
min_value, max_value = value_list[index]
self._processed_actions[:, index_list[index]].clip_(min_value, max_value)

def reset(self, env_ids: Sequence[int] | None = None) -> None:
self._raw_actions[env_ids] = 0.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,8 @@ class JointAction(ActionTerm):
"""The scaling factor applied to the input action."""
_offset: torch.Tensor | float
"""The offset applied to the input action."""
_clip: dict[str, tuple] | None = None
"""The clip applied to the input action."""

def __init__(self, cfg: actions_cfg.JointActionCfg, env: ManagerBasedEnv) -> None:
# initialize the action term
Expand Down Expand Up @@ -94,6 +96,12 @@ def __init__(self, cfg: actions_cfg.JointActionCfg, env: ManagerBasedEnv) -> Non
self._offset[:, index_list] = torch.tensor(value_list, device=self.device)
else:
raise ValueError(f"Unsupported offset type: {type(cfg.offset)}. Supported types are float and dict.")
# parse clip
if cfg.clip is not None:
if isinstance(cfg.clip, dict):
self._clip = cfg.clip
else:
raise ValueError(f"Unsupported clip type: {type(cfg.clip)}. Supported types are dict.")

"""
Properties.
Expand All @@ -120,6 +128,13 @@ def process_actions(self, actions: torch.Tensor):
self._raw_actions[:] = actions
# apply the affine transformations
self._processed_actions = self._raw_actions * self._scale + self._offset
# clip actions
if self._clip is not None:
# resolve the dictionary config
index_list, _, value_list = string_utils.resolve_matching_names_values(self._clip, self._joint_names)
for index in range(len(index_list)):
min_value, max_value = value_list[index]
self._processed_actions[:, index_list[index]].clip_(min_value, max_value)

def reset(self, env_ids: Sequence[int] | None = None) -> None:
self._raw_actions[env_ids] = 0.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@ class JointPositionToLimitsAction(ActionTerm):
"""The articulation asset on which the action term is applied."""
_scale: torch.Tensor | float
"""The scaling factor applied to the input action."""
_clip: dict[str, tuple] | None = None
"""The clip applied to the input action."""

def __init__(self, cfg: actions_cfg.JointPositionToLimitsActionCfg, env: ManagerBasedEnv):
# initialize the action term
Expand Down Expand Up @@ -76,6 +78,12 @@ def __init__(self, cfg: actions_cfg.JointPositionToLimitsActionCfg, env: Manager
self._scale[:, index_list] = torch.tensor(value_list, device=self.device)
else:
raise ValueError(f"Unsupported scale type: {type(cfg.scale)}. Supported types are float and dict.")
# parse clip
if cfg.clip is not None:
if isinstance(cfg.clip, dict):
self._clip = cfg.clip
else:
raise ValueError(f"Unsupported clip type: {type(cfg.clip)}. Supported types are dict.")

"""
Properties.
Expand All @@ -102,6 +110,13 @@ def process_actions(self, actions: torch.Tensor):
self._raw_actions[:] = actions
# apply affine transformations
self._processed_actions = self._raw_actions * self._scale
# clip actions
if self._clip is not None:
# resolve the dictionary config
index_list, _, value_list = string_utils.resolve_matching_names_values(self._clip, self._joint_names)
for index in range(len(index_list)):
min_value, max_value = value_list[index]
self._processed_actions[:, index_list[index]].clip_(min_value, max_value)
# rescale the position targets if configured
# this is useful when the input actions are in the range [-1, 1]
if self.cfg.rescale_to_limits:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@

import omni.log

import omni.isaac.lab.utils.string as string_utils
from omni.isaac.lab.assets.articulation import Articulation
from omni.isaac.lab.managers.action_manager import ActionTerm
from omni.isaac.lab.utils.math import euler_xyz_from_quat
Expand Down Expand Up @@ -59,6 +60,8 @@ class NonHolonomicAction(ActionTerm):
"""The scaling factor applied to the input action. Shape is (1, 2)."""
_offset: torch.Tensor
"""The offset applied to the input action. Shape is (1, 2)."""
_clip: dict[str, tuple] | None = None
"""The clip applied to the input action."""

def __init__(self, cfg: actions_cfg.NonHolonomicActionCfg, env: ManagerBasedEnv):
# initialize the action term
Expand Down Expand Up @@ -104,6 +107,12 @@ def __init__(self, cfg: actions_cfg.NonHolonomicActionCfg, env: ManagerBasedEnv)
# save the scale and offset as tensors
self._scale = torch.tensor(self.cfg.scale, device=self.device).unsqueeze(0)
self._offset = torch.tensor(self.cfg.offset, device=self.device).unsqueeze(0)
# parse clip
if cfg.clip is not None:
if isinstance(cfg.clip, dict):
self._clip = cfg.clip
else:
raise ValueError(f"Unsupported clip type: {type(cfg.clip)}. Supported types are dict.")

"""
Properties.
Expand All @@ -129,6 +138,13 @@ def process_actions(self, actions):
# store the raw actions
self._raw_actions[:] = actions
self._processed_actions = self.raw_actions * self._scale + self._offset
# clip actions
if self._clip is not None:
# resolve the dictionary config
index_list, _, value_list = string_utils.resolve_matching_names_values(self._clip, self._joint_names)
for index in range(len(index_list)):
min_value, max_value = value_list[index]
self._processed_actions[:, index_list[index]].clip_(min_value, max_value)

def apply_actions(self):
# obtain current heading
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import omni.log

import omni.isaac.lab.utils.math as math_utils
import omni.isaac.lab.utils.string as string_utils
from omni.isaac.lab.assets.articulation import Articulation
from omni.isaac.lab.controllers.differential_ik import DifferentialIKController
from omni.isaac.lab.managers.action_manager import ActionTerm
Expand Down Expand Up @@ -42,6 +43,8 @@ class DifferentialInverseKinematicsAction(ActionTerm):
"""The articulation asset on which the action term is applied."""
_scale: torch.Tensor
"""The scaling factor applied to the input action. Shape is (1, action_dim)."""
_clip: dict[str, tuple] | None = None
"""The clip applied to the input action."""

def __init__(self, cfg: actions_cfg.DifferentialInverseKinematicsActionCfg, env: ManagerBasedEnv):
# initialize the action term
Expand Down Expand Up @@ -101,6 +104,13 @@ def __init__(self, cfg: actions_cfg.DifferentialInverseKinematicsActionCfg, env:
else:
self._offset_pos, self._offset_rot = None, None

# parse clip
if cfg.clip is not None:
if isinstance(cfg.clip, dict):
self._clip = cfg.clip
else:
raise ValueError(f"Unsupported clip type: {type(cfg.clip)}. Supported types are dict.")

"""
Properties.
"""
Expand All @@ -125,6 +135,13 @@ def process_actions(self, actions: torch.Tensor):
# store the raw actions
self._raw_actions[:] = actions
self._processed_actions[:] = self.raw_actions * self._scale
# clip actions
if self._clip is not None:
# resolve the dictionary config
index_list, _, value_list = string_utils.resolve_matching_names_values(self._clip, self._joint_names)
for index in range(len(index_list)):
min_value, max_value = value_list[index]
self._processed_actions[:, index_list[index]].clip_(min_value, max_value)
# obtain quantities from simulation
ee_pos_curr, ee_quat_curr = self._compute_frame_pose()
# set command into controller
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,9 @@ class for more details.
debug_vis: bool = False
"""Whether to visualize debug information. Defaults to False."""

clip: dict[str, tuple] | None = None
"""Clip range for the action (dict of regex expressions). Defaults to None."""


##
# Command manager.
Expand Down