Skip to content

Commit 768e9a3

Browse files
Reworked the code to split between position and orientation rather than pose_abs and pos_rel.
1 parent 39dffbb commit 768e9a3

File tree

2 files changed

+170
-138
lines changed

2 files changed

+170
-138
lines changed

source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py

Lines changed: 19 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -367,52 +367,50 @@ class OffsetCfg:
367367
``OperationalSpaceControllerCfg``.
368368
"""
369369

370-
# TODO: Here the clip effects are not homogeneous, but they have unique names that relate
371-
# to specific control modes so it's fine to me.
370+
# TODO: Here the clip effects are not homogeneous, I don't like that depending on the controller mode the behavior
371+
# is different. It makes it hard to understand what does what. Should we have an explicit velocity clip?
372372

373-
clip_pose_abs: list[tuple[float, float]] | None = None
374-
"""Clip range for the absolute pose targets. Defaults to None for no clipping.
375-
376-
The expected format is a list of tuples, each containing two values. This effectively bounds
377-
the reachable range of the end-effector in the world frame.
373+
clip_position: list[tuple[float, float]] | None = None
374+
"""Clip range for the position targets. Defaults to None for no clipping.
375+
376+
The expected format is a list of tuples, each containing two values. When using the controller in ``"abs"`` mode
377+
this limits the reachable range of the end-effector in the world frame. When using the controller in ``"rel"`` mode
378+
this limits the maximum velocity of the end-effector in the task frame. This must match the number of active axes
379+
in :attr:`controller_cfg.motion_control_axes_task`.
378380
379381
Example:
380382
..code-block:: python
381-
clip_pose_abs = [
383+
clip_position = [
382384
(min_x, max_x),
383385
(min_y, max_y),
384386
(min_z, max_z),
385-
(min_roll, max_roll),
386-
(min_pitch, max_pitch),
387-
(min_yaw, max_yaw),
388387
]
389388
"""
390-
clip_pose_rel: list[tuple[float, float]] | None = None
391-
"""Clip range for the relative pose targets. Defaults to None for no clipping.
389+
clip_orientation: list[tuple[float, float]] | None = None
390+
"""Clip range for the orientation targets. Defaults to None for no clipping.
392391
393-
The expected format is a list of tuples, each containing two values. This effectively limits
394-
the end-effector's velocity in the task frame.
392+
The expected format is a list of tuples, each containing two values. When using the controller in ``"abs"`` mode
393+
this limits the reachable range of the end-effector in the world frame. When using the controller in ``"rel"`` mode
394+
this limits the maximum velocity of the end-effector in the task frame. This must match the number of active axes
395+
in :attr:`controller_cfg.motion_control_axes_task`.
395396
396397
Example:
397398
..code-block:: python
398-
clip_pose_rel = [
399-
(min_x, max_x),
400-
(min_y, max_y),
401-
(min_z, max_z),
399+
clip_orientation = [
402400
(min_roll, max_roll),
403401
(min_pitch, max_pitch),
404402
(min_yaw, max_yaw),
405403
]
406404
"""
407-
clip_wrench_abs: list[tuple[float, float]] | None = None
405+
clip_wrench: list[tuple[float, float]] | None = None
408406
"""Clip range for the absolute wrench targets. Defaults to None for no clipping.
409407
410408
The expected format is a list of tuples, each containing two values. This effectively limits
411409
the maximum force and torque that can be commanded in the task frame.
412410
413411
Example:
414412
..code-block:: python
415-
clip_wrench_abs = [
413+
clip_wrench = [
416414
(min_fx, max_fx),
417415
(min_fy, max_fy),
418416
(min_fz, max_fz),

0 commit comments

Comments
 (0)