Skip to content

Commit da721f5

Browse files
pre-commits
1 parent 768e9a3 commit da721f5

File tree

2 files changed

+47
-26
lines changed

2 files changed

+47
-26
lines changed

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -368,11 +368,11 @@ class OffsetCfg:
368368
"""
369369

370370
# 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?
371+
# is different. It makes it hard to understand what does what. Should we have an explicit velocity clip?
372372

373373
clip_position: list[tuple[float, float]] | None = None
374374
"""Clip range for the position targets. Defaults to None for no clipping.
375-
375+
376376
The expected format is a list of tuples, each containing two values. When using the controller in ``"abs"`` mode
377377
this limits the reachable range of the end-effector in the world frame. When using the controller in ``"rel"`` mode
378378
this limits the maximum velocity of the end-effector in the task frame. This must match the number of active axes

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

Lines changed: 45 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -172,7 +172,7 @@ def __init__(self, cfg: actions_cfg.DifferentialInverseKinematicsActionCfg, env:
172172
out = torch.tensor(self.cfg.clip["position"][0], device=self.device)
173173
print(self._clip.shape, out.shape)
174174
print(out)
175-
175+
176176
self._clip[:, 0] = torch.tensor(self.cfg.clip["position"][0], device=self.device)
177177
self._clip[:, 1] = torch.tensor(self.cfg.clip["position"][1], device=self.device)
178178
self._clip[:, 2] = torch.tensor(self.cfg.clip["position"][2], device=self.device)
@@ -245,7 +245,9 @@ def process_actions(self, actions: torch.Tensor):
245245
ee_pos_curr, ee_quat_curr, self._processed_actions
246246
)
247247
# Cast the target_quat_w to euler angles
248-
target_euler_angles_w = torch.transpose(torch.stack(math_utils.euler_xyz_from_quat(target_quat_w)), 0, 1)
248+
target_euler_angles_w = torch.transpose(
249+
torch.stack(math_utils.euler_xyz_from_quat(target_quat_w)), 0, 1
250+
)
249251
# Clip the pose
250252
clamped_target_position_w = torch.clamp(
251253
target_position_w, min=self._clip[:, :3, 0], max=self._clip[:, :3, 1]
@@ -272,7 +274,9 @@ def process_actions(self, actions: torch.Tensor):
272274
self._processed_actions[:, :3], min=self._clip[:, :3, 0], max=self._clip[:, :3, 1]
273275
)
274276
# Cast the target quaternion to euler angles
275-
target_euler_angles_w = torch.transpose(torch.stack(math_utils.euler_xyz_from_quat(self._processed_actions[:, 3:7])), 0, 1)
277+
target_euler_angles_w = torch.transpose(
278+
torch.stack(math_utils.euler_xyz_from_quat(self._processed_actions[:, 3:7])), 0, 1
279+
)
276280
# Clip the euler angles
277281
clamped_target_euler_angles_w = torch.clamp(
278282
target_euler_angles_w, min=self._clip[:, 3:, 0], max=self._clip[:, 3:, 1]
@@ -598,7 +602,7 @@ def reset(self, env_ids: Sequence[int] | None = None) -> None:
598602
self._contact_sensor.reset(env_ids)
599603
if self._task_frame_transformer is not None:
600604
self._task_frame_transformer.reset(env_ids)
601-
605+
602606
"""
603607
Parameter modification functions.
604608
"""
@@ -615,18 +619,20 @@ def set_clipping_values(
615619
for wrench. The setter performs a direct assignment so no copy is made. If a list is provided, it must be a list
616620
of tuples, each containing two values. The setter will convert the list to a tensor and assign it to the clipping
617621
values.
618-
622+
619623
Args:
620624
position_clip: The clipping values for the position command.
621625
orientation_clip: The clipping values for the orientation command.
622626
wrench_clip: The clipping values for the wrench command.
623627
"""
624-
628+
625629
if position_clip is not None:
626630
position_clip = self._validate_clipping_values(self._clip_position.shape, position_clip, "position_clip")
627631
self._clip_position = position_clip
628632
if orientation_clip is not None:
629-
orientation_clip = self._validate_clipping_values(self._clip_orientation.shape, orientation_clip, "orientation_clip")
633+
orientation_clip = self._validate_clipping_values(
634+
self._clip_orientation.shape, orientation_clip, "orientation_clip"
635+
)
630636
self._clip_orientation = orientation_clip
631637
if wrench_clip is not None:
632638
wrench_clip = self._validate_clipping_values(self._clip_wrench.shape, wrench_clip, "wrench_clip")
@@ -881,7 +887,9 @@ def _preprocess_actions(self, actions: torch.Tensor):
881887
else:
882888
self._processed_actions[:, self._pose_abs_idx : self._pose_abs_idx + 3] *= self._position_scale
883889
if self._clip_orientation is not None:
884-
normed_quat = math_utils.normalize(self.processed_actions[:, self._pose_abs_idx + 3 : self._pose_abs_idx + 7] * self._orientation_scale)
890+
normed_quat = math_utils.normalize(
891+
self.processed_actions[:, self._pose_abs_idx + 3 : self._pose_abs_idx + 7] * self._orientation_scale
892+
)
885893
rpy = torch.transpose(torch.stack(math_utils.euler_xyz_from_quat(normed_quat)), 0, 1)
886894
rpy_clamped = torch.clamp(rpy, min=self._clip_orientation[:, :, 0], max=self._clip_orientation[:, :, 1])
887895
self.processed_actions[:, self._pose_abs_idx + 3 : self._pose_abs_idx + 7] = (
@@ -899,7 +907,9 @@ def _preprocess_actions(self, actions: torch.Tensor):
899907
else:
900908
self._processed_actions[:, self._pose_rel_idx : self._pose_rel_idx + 3] *= self._position_scale
901909
if self._clip_orientation is not None:
902-
rpy = self.processed_actions[:, self._pose_rel_idx + 3 : self._pose_rel_idx + 6] * self._orientation_scale
910+
rpy = (
911+
self.processed_actions[:, self._pose_rel_idx + 3 : self._pose_rel_idx + 6] * self._orientation_scale
912+
)
903913
rpy_clamped = torch.clamp(rpy, min=self._clip_orientation[:, :, 0], max=self._clip_orientation[:, :, 1])
904914
self.processed_actions[:, self._pose_rel_idx + 3 : self._pose_rel_idx + 6] = rpy_clamped
905915
else:
@@ -926,7 +936,7 @@ def _preprocess_actions(self, actions: torch.Tensor):
926936
@staticmethod
927937
def _gen_clip(control_flags, clip_cfg: list[tuple[float, float]], name: str) -> list[tuple[float, float]]:
928938
"""Generates the clipping configuration for the operational space controller.
929-
939+
930940
The expected format is a list of tuples, each containing two values. Note that the order in which the tuples are provided
931941
must match the order of the active axes in motion_control_axes_task.
932942
@@ -938,15 +948,19 @@ def _gen_clip(control_flags, clip_cfg: list[tuple[float, float]], name: str) ->
938948
allowed_names = ["clip_position", "clip_orientation", "clip_wrench"]
939949
if name not in allowed_names:
940950
raise ValueError(f"Expected {name} to be one of {allowed_names} but got {name}")
941-
951+
942952
# Iterate over the control flags and add the corresponding clip to the list
943953
if name == "clip_position":
944954
control_flags = control_flags[:3]
945955
elif name == "clip_orientation":
946956
control_flags = control_flags[3:]
947957
# Ensure the length of the clip_cfg is the same as the number of active axes
948958
if len(clip_cfg) != sum(control_flags):
949-
raise ValueError(f"{name} must be a list of tuples of the same length as there are active axes in motion_control_axes_task. There are {sum(control_flags)} active axes and {len(clip_cfg)} tuples in {name}.")
959+
raise ValueError(
960+
f"{name} must be a list of tuples of the same length as there are active axes in"
961+
f" motion_control_axes_task. There are {sum(control_flags)} active axes and {len(clip_cfg)} tuples in"
962+
f" {name}."
963+
)
950964
clip_pose_abs_new = []
951965
for i, flag in enumerate(control_flags):
952966
# If the axis is active, add the corresponding clip
@@ -959,48 +973,56 @@ def _gen_clip(control_flags, clip_cfg: list[tuple[float, float]], name: str) ->
959973
clip_pose_abs_new.append(clip)
960974
else:
961975
# If the axis is not active, add a clip of (-inf, inf). (Don't clip)
962-
clip_pose_abs_new.append((-float('inf'), float('inf')))
963-
return clip_pose_abs_new
976+
clip_pose_abs_new.append((-float("inf"), float("inf")))
977+
return clip_pose_abs_new
964978

965979
def _parse_clipping_cfg(self, cfg: actions_cfg.OperationalSpaceControllerActionCfg) -> None:
966980
"""Parses the clipping configuration for the operational space controller.
967-
981+
968982
Args:
969983
cfg: The configuration of the action term.
970984
"""
971985

972986
# Parse clip_position
973987
if cfg.clip_position is not None:
974-
clip_position = self._gen_clip(self.cfg.controller_cfg.motion_control_axes_task, cfg.clip_position, "clip_position")
988+
clip_position = self._gen_clip(
989+
self.cfg.controller_cfg.motion_control_axes_task, cfg.clip_position, "clip_position"
990+
)
975991
self._clip_position = torch.zeros((self.num_envs, 3, 2), device=self.device)
976992
self._clip_position[:] = torch.tensor(clip_position, device=self.device)
977993
else:
978994
self._clip_position = None
979995

980996
# Parse clip_orientation
981997
if cfg.clip_orientation is not None:
982-
clip_orientation = self._gen_clip(self.cfg.controller_cfg.motion_control_axes_task, cfg.clip_orientation, "clip_orientation")
998+
clip_orientation = self._gen_clip(
999+
self.cfg.controller_cfg.motion_control_axes_task, cfg.clip_orientation, "clip_orientation"
1000+
)
9831001
self._clip_orientation = torch.zeros((self.num_envs, 3, 2), device=self.device)
9841002
self._clip_orientation[:] = torch.tensor(clip_orientation, device=self.device)
9851003
else:
9861004
self._clip_orientation = None
9871005

988-
# Parse clip_wrench
1006+
# Parse clip_wrench
9891007
if cfg.clip_wrench is not None:
990-
clip_wrench = self._gen_clip(self.cfg.controller_cfg.contact_wrench_control_axes_task, cfg.clip_wrench, "clip_wrench")
1008+
clip_wrench = self._gen_clip(
1009+
self.cfg.controller_cfg.contact_wrench_control_axes_task, cfg.clip_wrench, "clip_wrench"
1010+
)
9911011
self._clip_wrench = torch.zeros((self.num_envs, 6, 2), device=self.device)
9921012
self._clip_wrench[:] = torch.tensor(clip_wrench, device=self.device)
9931013
else:
9941014
self._clip_wrench = None
9951015

996-
def _validate_clipping_values(self, target_shape: torch.Tensor, value: list[tuple[float, float]] | torch.Tensor, name: str) -> torch.Tensor:
1016+
def _validate_clipping_values(
1017+
self, target_shape: torch.Tensor, value: list[tuple[float, float]] | torch.Tensor, name: str
1018+
) -> torch.Tensor:
9971019
"""Validates the clipping values for the operational space controller.
9981020
9991021
Args:
10001022
target_shape: The shape of the target tensor.
10011023
value: The clipping values to validate.
10021024
name: The name of the clipping configuration.
1003-
1025+
10041026
Returns:
10051027
The validated clipping values.
10061028
@@ -1012,7 +1034,7 @@ def _validate_clipping_values(self, target_shape: torch.Tensor, value: list[tupl
10121034
allowed_names = ["position_clip", "orientation_clip", "wrench_clip"]
10131035
if name not in allowed_names:
10141036
raise ValueError(f"Expected {name} to be one of {allowed_names} but got {name}")
1015-
1037+
10161038
if isinstance(value, torch.Tensor):
10171039
if value.shape != target_shape:
10181040
raise ValueError(f"Expected {name} to be a tensor of shape {target_shape} but got {value.shape}")
@@ -1030,7 +1052,7 @@ def _validate_clipping_values(self, target_shape: torch.Tensor, value: list[tupl
10301052
else:
10311053
raise ValueError(f"Expected {name} to be a tensor or a list but got {type(value)}")
10321054
return tensor_clip
1033-
1055+
10341056
def _validate_scale_values(self, value: float | torch.Tensor, name: str) -> torch.Tensor:
10351057
"""Validates the scale values for the operational space controller.
10361058
@@ -1055,4 +1077,3 @@ def _validate_scale_values(self, value: float | torch.Tensor, name: str) -> torc
10551077
else:
10561078
raise ValueError(f"Expected {name} to be a tensor or a float but got {type(value)}")
10571079
return value
1058-

0 commit comments

Comments
 (0)