Skip to content

Commit 1b3bc58

Browse files
committed
Moving pink ik controller components into sub-directory, updating tests and cleaning up
1 parent da62a71 commit 1b3bc58

File tree

12 files changed

+32
-67
lines changed

12 files changed

+32
-67
lines changed

source/isaaclab/isaaclab/controllers/pink_ik.py renamed to source/isaaclab/isaaclab/controllers/pink_ik/pink_ik.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,9 +18,9 @@
1818
from pinocchio.robot_wrapper import RobotWrapper
1919

2020
from isaaclab.assets import ArticulationCfg
21-
from isaaclab.controllers.null_space_posture_task import NullSpacePostureTask
2221
from isaaclab.utils.string import resolve_matching_names_values
2322

23+
from .null_space_posture_task import NullSpacePostureTask
2424
from .pink_ik_cfg import PinkIKControllerCfg
2525

2626

@@ -51,7 +51,7 @@ def __init__(self, cfg: PinkIKControllerCfg, robot_cfg: ArticulationCfg, device:
5151

5252
# Use resolve_matching_names_values to match Pink joint names to joint_pos values
5353
indices, names, values = resolve_matching_names_values(
54-
joint_pos_dict, pink_joint_names, preserve_order=False, require_all_keys_matched=False
54+
joint_pos_dict, pink_joint_names, preserve_order=False, strict=False
5555
)
5656
if len(indices) != len(pink_joint_names):
5757
unmatched = [name for name in pink_joint_names if name not in names]

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55

66
from dataclasses import MISSING
77

8-
from isaaclab.controllers.pink_ik_cfg import PinkIKControllerCfg
8+
from isaaclab.controllers.pink_ik import PinkIKControllerCfg
99
from isaaclab.managers.action_manager import ActionTerm, ActionTermCfg
1010
from isaaclab.utils import configclass
1111

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

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -60,9 +60,7 @@ def __init__(self, cfg: pink_actions_cfg.PinkInverseKinematicsActionCfg, env: Ma
6060
self._ik_controllers = []
6161
for _ in range(env.num_envs):
6262
self._ik_controllers.append(
63-
PinkIKController(
64-
cfg=copy.deepcopy(self.cfg.controller), robot_cfg=env.scene.cfg.robot, device=self.device
65-
)
63+
PinkIKController(cfg=self.cfg.controller.copy(), robot_cfg=env.scene.cfg.robot, device=self.device)
6664
)
6765

6866
# Create tensors to store raw and processed actions

source/isaaclab/isaaclab/utils/string.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -275,7 +275,7 @@ def resolve_matching_names_values(
275275
data: dict[str, Any],
276276
list_of_strings: Sequence[str],
277277
preserve_order: bool = False,
278-
require_all_keys_matched: bool = True,
278+
strict: bool = True,
279279
) -> tuple[list[int], list[str], list[Any]]:
280280
"""Match a list of regular expressions in a dictionary against a list of strings and return
281281
the matched indices, names, and values.
@@ -296,15 +296,15 @@ def resolve_matching_names_values(
296296
data: A dictionary of regular expressions and values to match the strings in the list.
297297
list_of_strings: A list of strings to match.
298298
preserve_order: Whether to preserve the order of the query keys in the returned values. Defaults to False.
299-
require_all_keys_matched: Whether to require that all keys in the dictionary are matched. Defaults to True.
299+
strict: Whether to require that all keys in the dictionary get matched. Defaults to True.
300300
301301
Returns:
302302
A tuple of lists containing the matched indices, names, and values.
303303
304304
Raises:
305305
TypeError: When the input argument :attr:`data` is not a dictionary.
306306
ValueError: When multiple matches are found for a string in the dictionary.
307-
ValueError: When not all regular expressions in the data keys are matched (if require_all_keys_matched is True).
307+
ValueError: When not all regular expressions in the data keys are matched (if strict is True).
308308
"""
309309
# check valid input
310310
if not isinstance(data, dict):
@@ -358,7 +358,7 @@ def resolve_matching_names_values(
358358
names_list = names_list_reorder
359359
values_list = values_list_reorder
360360
# check that all regular expressions are matched
361-
if require_all_keys_matched and not all(keys_match_found):
361+
if strict and not all(keys_match_found):
362362
# make this print nicely aligned for debugging
363363
msg = "\n"
364364
for key, value in zip(data.keys(), keys_match_found):

source/isaaclab/test/controllers/test_pink_ik.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,10 @@
44
# SPDX-License-Identifier: BSD-3-Clause
55

66
"""Launch Isaac Sim Simulator first."""
7-
import json
8-
import os
9-
import sys
10-
117
# Import pinocchio in the main script to force the use of the dependencies installed by IsaacLab and not the one installed by Isaac Sim
128
# pinocchio is required by the Pink IK controller
9+
import sys
10+
1311
if sys.platform != "win32":
1412
import pinocchio # noqa: F401
1513

@@ -22,7 +20,9 @@
2220

2321
import contextlib
2422
import gymnasium as gym
23+
import json
2524
import numpy as np
25+
import os
2626
import torch
2727

2828
import pytest

source/isaaclab/test/utils/test_string.py

Lines changed: 17 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -162,15 +162,28 @@ def test_resolve_matching_names_values_with_basic_strings():
162162
query_names = {"a|c": 1, "b": 0, "f": 2}
163163
with pytest.raises(ValueError):
164164
_ = string_utils.resolve_matching_names_values(query_names, target_names)
165-
# test require_all_keys_matched=False
165+
166+
167+
def test_resolve_matching_names_values_with_strict_false():
168+
"""Test resolving matching names with strict=False parameter."""
169+
# list of strings
170+
target_names = ["a", "b", "c", "d", "e"]
171+
# test strict=False
166172
data = {"a|c": 1, "b": 2, "f": 3}
167-
index_list, names_list, values_list = string_utils.resolve_matching_names_values(
168-
data, target_names, require_all_keys_matched=False
169-
)
173+
index_list, names_list, values_list = string_utils.resolve_matching_names_values(data, target_names, strict=False)
170174
assert index_list == [0, 1, 2]
171175
assert names_list == ["a", "b", "c"]
172176
assert values_list == [1, 2, 1]
173177

178+
# test failure case: multiple matches for a string (should still raise ValueError even with strict=False)
179+
data = {"a|c": 1, "a": 2, "b": 3}
180+
with pytest.raises(ValueError, match="Multiple matches for 'a':"):
181+
_ = string_utils.resolve_matching_names_values(data, target_names, strict=False)
182+
183+
# test failure case: invalid input type (should still raise TypeError even with strict=False)
184+
with pytest.raises(TypeError, match="Input argument `data` should be a dictionary"):
185+
_ = string_utils.resolve_matching_names_values("not_a_dict", target_names, strict=False)
186+
174187

175188
def test_resolve_matching_names_values_with_basic_strings_and_preserved_order():
176189
"""Test resolving matching names with a basic expression."""

source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_pink_ik_env_cfg.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,7 @@
66
from pink.tasks import DampingTask, FrameTask
77

88
import isaaclab.controllers.utils as ControllerUtils
9-
from isaaclab.controllers.null_space_posture_task import NullSpacePostureTask
10-
from isaaclab.controllers.pink_ik_cfg import PinkIKControllerCfg
9+
from isaaclab.controllers.pink_ik import NullSpacePostureTask, PinkIKControllerCfg
1110
from isaaclab.devices import DevicesCfg
1211
from isaaclab.devices.openxr import OpenXRDeviceCfg
1312
from isaaclab.devices.openxr.retargeters import GR1T2RetargeterCfg

source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_pink_ik_env_cfg.py

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,8 +6,7 @@
66
from pink.tasks import DampingTask, FrameTask
77

88
import isaaclab.controllers.utils as ControllerUtils
9-
from isaaclab.controllers.null_space_posture_task import NullSpacePostureTask
10-
from isaaclab.controllers.pink_ik_cfg import PinkIKControllerCfg
9+
from isaaclab.controllers.pink_ik import NullSpacePostureTask, PinkIKControllerCfg
1110
from isaaclab.devices import DevicesCfg
1211
from isaaclab.devices.openxr import OpenXRDeviceCfg
1312
from isaaclab.devices.openxr.retargeters import GR1T2RetargeterCfg

0 commit comments

Comments
 (0)