Skip to content

Antoiner/action clipping #2694

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

Draft
wants to merge 6 commits into
base: main
Choose a base branch
from
Draft
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
109 changes: 109 additions & 0 deletions source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,19 @@ class JointActionCfg(ActionTermCfg):

joint_names: list[str] = MISSING
"""List of joint names or regex expressions that the action will be mapped to."""

scale: float | dict[str, float] = 1.0
"""Scale factor for the action (float or dict of regex expressions). Defaults to 1.0."""

offset: float | dict[str, float] = 0.0
"""Offset factor for the action (float or dict of regex expressions). Defaults to 0.0."""

preserve_order: bool = False
"""Whether to preserve the order of the joint names in the action output. Defaults to False."""

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

Choose a reason for hiding this comment

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

Suggested change
"""Clip range for the action (dict of regex expressions). Defaults to None."""
"""Clip range for the action (dict of regex expressions). Defaults to None.
Dictionary keys should be regex expressions of joint names and values should be tuples of (lower, upper) bounds.
"""



@configclass
class JointPositionActionCfg(JointActionCfg):
Expand Down Expand Up @@ -124,6 +130,9 @@ class JointPositionToLimitsActionCfg(ActionTermCfg):
This operation is performed after applying the scale factor.
"""

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

Choose a reason for hiding this comment

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

Suggested change
"""Clip range for the action (dict of regex expressions). Defaults to None."""
"""Clip range for the action (dict of regex expressions). Defaults to None.
Dictionary keys should be regex expressions of joint names and values should be tuples of (lower, upper) bounds.
"""



@configclass
class EMAJointPositionToLimitsActionCfg(JointPositionToLimitsActionCfg):
Expand Down Expand Up @@ -155,8 +164,10 @@ class BinaryJointActionCfg(ActionTermCfg):

joint_names: list[str] = MISSING
"""List of joint names or regex expressions that the action will be mapped to."""

open_command_expr: dict[str, float] = MISSING
"""The joint command to move to *open* configuration."""

close_command_expr: dict[str, float] = MISSING
"""The joint command to move to *close* configuration."""

Expand Down Expand Up @@ -197,17 +208,28 @@ class NonHolonomicActionCfg(ActionTermCfg):

body_name: str = MISSING
"""Name of the body which has the dummy mechanism connected to."""

x_joint_name: str = MISSING
"""The dummy joint name in the x direction."""

y_joint_name: str = MISSING
"""The dummy joint name in the y direction."""

yaw_joint_name: str = MISSING
"""The dummy joint name in the yaw direction."""

scale: tuple[float, float] = (1.0, 1.0)
"""Scale factor for the action. Defaults to (1.0, 1.0)."""

offset: tuple[float, float] = (0.0, 0.0)
"""Offset factor for the action. Defaults to (0.0, 0.0)."""

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

The expected keys are "v", and "yaw". Defaults to None for no clipping.
Copy link
Collaborator

Choose a reason for hiding this comment

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

Suggested change
The expected keys are "v", and "yaw". Defaults to None for no clipping.
The expected keys are "v", and "yaw". Values are tuples of (lower, upper) bounds. Defaults to None for no clipping.

Copy link
Collaborator

Choose a reason for hiding this comment

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

or something like this. min/max or lower/upper is fine whatever is consistent through the actions.

"""


##
# Task-space Actions.
Expand Down Expand Up @@ -240,15 +262,49 @@ class OffsetCfg:

joint_names: list[str] = MISSING
"""List of joint names or regex expressions that the action will be mapped to."""

body_name: str = MISSING
"""Name of the body or frame for which IK is performed."""

body_offset: OffsetCfg | None = None
"""Offset of target frame w.r.t. to the body frame. Defaults to None, in which case no offset is applied."""

scale: float | tuple[float, ...] = 1.0
"""Scale factor for the action. Defaults to 1.0."""

controller: DifferentialIKControllerCfg = MISSING
"""The configuration for the differential IK controller."""

# TODO: Should this be simplified to a list of tuples? More compact, less readable?
# TODO: Do we want to have an homogeneous behavior for the clip range? I think we do
# or we'd need unique clip names so that it's not confusing to the user.

clip: dict[str, tuple] | None = None
"""Clip range of the controller's command in the world frame (dict of regex expressions).

The expected keys are "position", "orientation", and "wrench". Defaults to None for no clipping.
For "position" we expect a tuple of (min, max) for each dimension. (x, y, z) in this order.
For "orientation" we expect a tuple of (min, max) for each dimension. (roll, pitch, yaw) in this order.

Example:
..code-block:: python
{
"position": ((-1.0, 1.0), (-1.0, 1.0), (-1.0, 1.0)), # (x, y, z)
"orientation": ((-1.0, 1.0), (-1.0, 1.0), (-1.0, 1.0)), # (roll, pitch, yaw)
}

..note::
This means that regardless of the :attr:`controller.use_relative_mode` setting, the clip range is always
applied in the world frame. This is done so that the meaning of the clip range is consistent across
different modes.

..note::
If the :attr:`controller.command_type` is set to "pose", then both the position and orientation clip ranges
must be provided. To clip either one or the other, one can set large values to the clip range.


"""


@configclass
class OperationalSpaceControllerActionCfg(ActionTermCfg):
Expand Down Expand Up @@ -310,3 +366,56 @@ class OffsetCfg:
Note: Functional only when ``nullspace_control`` is set to ``"position"`` within the
``OperationalSpaceControllerCfg``.
"""

# TODO: Here the clip effects are not homogeneous, I don't like that depending on the controller mode the behavior
# is different. It makes it hard to understand what does what. Should we have an explicit velocity clip?

clip_position: list[tuple[float, float]] | None = None
"""Clip range for the position targets. Defaults to None for no clipping.

The expected format is a list of tuples, each containing two values. When using the controller in ``"abs"`` mode
this limits the reachable range of the end-effector in the world frame. When using the controller in ``"rel"`` mode
this limits the maximum velocity of the end-effector in the task frame. This must match the number of active axes
in :attr:`controller_cfg.motion_control_axes_task`.

Example:
..code-block:: python
clip_position = [
(min_x, max_x),
(min_y, max_y),
(min_z, max_z),
]
"""
clip_orientation: list[tuple[float, float]] | None = None
"""Clip range for the orientation targets. Defaults to None for no clipping.

The expected format is a list of tuples, each containing two values. When using the controller in ``"abs"`` mode
this limits the reachable range of the end-effector in the world frame. When using the controller in ``"rel"`` mode
this limits the maximum velocity of the end-effector in the task frame. This must match the number of active axes
in :attr:`controller_cfg.motion_control_axes_task`.

Example:
..code-block:: python
clip_orientation = [
(min_roll, max_roll),
(min_pitch, max_pitch),
(min_yaw, max_yaw),
]
"""
clip_wrench: list[tuple[float, float]] | None = None
"""Clip range for the absolute wrench targets. Defaults to None for no clipping.

The expected format is a list of tuples, each containing two values. This effectively limits
the maximum force and torque that can be commanded in the task frame.

Example:
..code-block:: python
clip_wrench = [
(min_fx, max_fx),
(min_fy, max_fy),
(min_fz, max_fz),
(min_tx, max_tx),
(min_ty, max_ty),
(min_tz, max_tz),
]
"""
Original file line number Diff line number Diff line change
Expand Up @@ -84,17 +84,6 @@ def __init__(self, cfg: actions_cfg.BinaryJointActionCfg, env: ManagerBasedEnv)
)
self._close_command[index_list] = torch.tensor(value_list, device=self.device)

# parse clip
if self.cfg.clip is not None:
if isinstance(cfg.clip, dict):
self._clip = torch.tensor([[-float("inf"), float("inf")]], device=self.device).repeat(
self.num_envs, self.action_dim, 1
)
index_list, _, value_list = string_utils.resolve_matching_names_values(self.cfg.clip, self._joint_names)
self._clip[:, index_list] = torch.tensor(value_list, device=self.device)
else:
raise ValueError(f"Unsupported clip type: {type(cfg.clip)}. Supported types are dict.")

"""
Properties.
"""
Expand Down Expand Up @@ -127,10 +116,6 @@ 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)
if self.cfg.clip is not None:
self._processed_actions = torch.clamp(
self._processed_actions, min=self._clip[:, :, 0], max=self._clip[:, :, 1]
)

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 @@ -109,11 +109,17 @@ def __init__(self, cfg: actions_cfg.NonHolonomicActionCfg, env: ManagerBasedEnv)
self._offset = torch.tensor(self.cfg.offset, device=self.device).unsqueeze(0)
# parse clip
if self.cfg.clip is not None:
allowed_clipping_keys = ["v", "yaw"]
if isinstance(cfg.clip, dict):
for key in self.cfg.clip.keys():
if key not in allowed_clipping_keys:
raise ValueError(f"Unsupported clip key: {key}. Supported keys are {allowed_clipping_keys}.")
self._clip = torch.tensor([[-float("inf"), float("inf")]], device=self.device).repeat(
self.num_envs, self.action_dim, 1
)
index_list, _, value_list = string_utils.resolve_matching_names_values(self.cfg.clip, self._joint_names)
index_list, _, value_list = string_utils.resolve_matching_names_values(
self.cfg.clip, allowed_clipping_keys
)
self._clip[:, index_list] = torch.tensor(value_list, device=self.device)
else:
raise ValueError(f"Unsupported clip type: {type(cfg.clip)}. Supported types are dict.")
Expand Down
Loading