Skip to content

Commit efd9d1d

Browse files
addressed the comment from James partially.
1 parent da721f5 commit efd9d1d

File tree

2 files changed

+35
-6
lines changed

2 files changed

+35
-6
lines changed

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

Lines changed: 30 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,11 @@ class JointActionCfg(ActionTermCfg):
3636
"""Whether to preserve the order of the joint names in the action output. Defaults to False."""
3737

3838
clip: dict[str, tuple] | None = None
39-
"""Clip range for the action (dict of regex expressions). Defaults to None."""
39+
"""Clip range for the action (dict of regex expressions). Defaults to None.
40+
41+
Dictionary keys should be regex expressions of joint names and values should be tuples of
42+
(lower, upper) bounds.
43+
"""
4044

4145

4246
@configclass
@@ -131,7 +135,11 @@ class JointPositionToLimitsActionCfg(ActionTermCfg):
131135
"""
132136

133137
clip: dict[str, tuple] | None = None
134-
"""Clip range for the action (dict of regex expressions). Defaults to None."""
138+
"""Clip range for the action (dict of regex expressions). Defaults to None.
139+
140+
Dictionary keys should be regex expressions of joint names and values should be tuples of
141+
(lower, upper) bounds.
142+
"""
135143

136144

137145
@configclass
@@ -228,6 +236,7 @@ class NonHolonomicActionCfg(ActionTermCfg):
228236
"""Clip range for the action (dict of regex expressions).
229237
230238
The expected keys are "v", and "yaw". Defaults to None for no clipping.
239+
Values should be tuples of (lower, upper) bounds.
231240
"""
232241

233242

@@ -346,13 +355,22 @@ class OffsetCfg:
346355
"""The configuration for the operational space controller."""
347356

348357
position_scale: float = 1.0
349-
"""Scale factor for the position targets. Defaults to 1.0."""
358+
"""Scale factor for the position targets. Defaults to 1.0.
359+
360+
Note: The scaling is applied before the clipping of the position targets.
361+
"""
350362

351363
orientation_scale: float = 1.0
352-
"""Scale factor for the orientation (quad for ``pose_abs`` or axis-angle for ``pose_rel``). Defaults to 1.0."""
364+
"""Scale factor for the orientation (quad for ``pose_abs`` or axis-angle for ``pose_rel``). Defaults to 1.0.
365+
366+
Note: The scaling is applied before the clipping of the orientation targets.
367+
"""
353368

354369
wrench_scale: float = 1.0
355-
"""Scale factor for the wrench targets. Defaults to 1.0."""
370+
"""Scale factor for the wrench targets. Defaults to 1.0.
371+
372+
Note: The scaling is applied before the clipping of the wrench targets.
373+
"""
356374

357375
stiffness_scale: float = 1.0
358376
"""Scale factor for the stiffness commands. Defaults to 1.0."""
@@ -377,6 +395,8 @@ class OffsetCfg:
377395
this limits the reachable range of the end-effector in the world frame. When using the controller in ``"rel"`` mode
378396
this limits the maximum velocity of the end-effector in the task frame. This must match the number of active axes
379397
in :attr:`controller_cfg.motion_control_axes_task`.
398+
399+
Note: The clipping is applied after the scale factor is applied.
380400
381401
Example:
382402
..code-block:: python
@@ -392,7 +412,9 @@ class OffsetCfg:
392412
The expected format is a list of tuples, each containing two values. When using the controller in ``"abs"`` mode
393413
this limits the reachable range of the end-effector in the world frame. When using the controller in ``"rel"`` mode
394414
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`.
415+
in :attr:`controller_cfg.motion_control_axes_task`. Angles are given in the following order: (roll, pitch, yaw).
416+
417+
Note: The clipping is applied after the scale factor is applied.
396418
397419
Example:
398420
..code-block:: python
@@ -408,6 +430,8 @@ class OffsetCfg:
408430
The expected format is a list of tuples, each containing two values. This effectively limits
409431
the maximum force and torque that can be commanded in the task frame.
410432
433+
Note: The clipping is applied after the scale factor is applied.
434+
411435
Example:
412436
..code-block:: python
413437
clip_wrench = [

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

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -886,6 +886,7 @@ def _preprocess_actions(self, actions: torch.Tensor):
886886
)
887887
else:
888888
self._processed_actions[:, self._pose_abs_idx : self._pose_abs_idx + 3] *= self._position_scale
889+
889890
if self._clip_orientation is not None:
890891
normed_quat = math_utils.normalize(
891892
self.processed_actions[:, self._pose_abs_idx + 3 : self._pose_abs_idx + 7] * self._orientation_scale
@@ -897,6 +898,7 @@ def _preprocess_actions(self, actions: torch.Tensor):
897898
)
898899
else:
899900
self._processed_actions[:, self._pose_abs_idx + 3 : self._pose_abs_idx + 7] *= self._orientation_scale
901+
900902
if self._pose_rel_idx is not None:
901903
if self._clip_position is not None:
902904
self._processed_actions[:, self._pose_rel_idx : self._pose_rel_idx + 3] = torch.clamp(
@@ -906,6 +908,7 @@ def _preprocess_actions(self, actions: torch.Tensor):
906908
)
907909
else:
908910
self._processed_actions[:, self._pose_rel_idx : self._pose_rel_idx + 3] *= self._position_scale
911+
909912
if self._clip_orientation is not None:
910913
rpy = (
911914
self.processed_actions[:, self._pose_rel_idx + 3 : self._pose_rel_idx + 6] * self._orientation_scale
@@ -914,6 +917,7 @@ def _preprocess_actions(self, actions: torch.Tensor):
914917
self.processed_actions[:, self._pose_rel_idx + 3 : self._pose_rel_idx + 6] = rpy_clamped
915918
else:
916919
self._processed_actions[:, self._pose_rel_idx + 3 : self._pose_rel_idx + 6] *= self._orientation_scale
920+
917921
if self._wrench_abs_idx is not None:
918922
if self.cfg.clip_wrench is not None:
919923
self._processed_actions[:, self._wrench_abs_idx : self._wrench_abs_idx + 6] = torch.clamp(
@@ -923,6 +927,7 @@ def _preprocess_actions(self, actions: torch.Tensor):
923927
)
924928
else:
925929
self._processed_actions[:, self._wrench_abs_idx : self._wrench_abs_idx + 6] *= self._wrench_scale
930+
926931
if self._damping_ratio_idx is not None:
927932
self._processed_actions[
928933
:, self._damping_ratio_idx : self._damping_ratio_idx + 6

0 commit comments

Comments
 (0)