Skip to content

Commit

Permalink
[add] add ability hand
Browse files Browse the repository at this point in the history
  • Loading branch information
yzqin committed Feb 13, 2024
1 parent 454483d commit 30eb81e
Show file tree
Hide file tree
Showing 6 changed files with 43 additions and 7 deletions.
13 changes: 13 additions & 0 deletions dex_retargeting/configs/offline/ability_hand_right.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
retargeting:
type: position
urdf_path: ability_hand/ability_hand_right.urdf
wrist_link_name: "base_link"

target_joint_names: null
target_link_names: [ "thumb_tip", "index_tip", "middle_tip", "ring_tip", "pinky_tip" ]

target_link_human_indices: [ 4, 8, 12, 16, 20 ]

# A smaller alpha means stronger filtering, i.e. more smooth but also larger latency
# 1 means no filter while 0 means not moving
low_pass_alpha: 1
17 changes: 17 additions & 0 deletions dex_retargeting/configs/teleop/ability_hand_right.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
retargeting:
type: vector
urdf_path: ability_hand/ability_hand_right.urdf
wrist_link_name: "base_link"

# Target refers to the retargeting target, which is the robot hand
target_joint_names: null
target_origin_link_names: [ "base_link", "base_link", "base_link", "base_link", "base_link" ]
target_task_link_names: [ "thumb_tip", "index_tip", "middle_tip", "ring_tip", "pinky_tip", ]
scaling_factor: 1.0

# Source refers to the retargeting input, which usually corresponds to the human hand
# The joint indices of human hand joint which corresponds to each link in the target_link_names
target_link_human_indices: [ [ 0, 0, 0, 0, 0 ], [ 4, 8, 12, 16, 20 ] ]

# A smaller alpha means stronger filtering, i.e. more smooth but also larger latency
low_pass_alpha: 0.2
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@ retargeting:

# Target refers to the retargeting target, which is the robot hand
target_joint_names: null
wrist_link_name: "palm"
finger_tip_link_names: [ "thtip", "fftip", "mftip", "rftip", "lftip" ]
scaling_factor: 1.2

Expand Down
2 changes: 2 additions & 0 deletions dex_retargeting/constants.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ class RobotName(enum.Enum):
shadow = enum.auto()
svh = enum.auto()
leap = enum.auto()
ability = enum.auto()


class RetargetingType(enum.Enum):
Expand All @@ -25,6 +26,7 @@ class HandType(enum.Enum):
RobotName.shadow: "shadow_hand",
RobotName.svh: "schunk_svh_hand",
RobotName.leap: "leap_hand",
RobotName.ability: "ability_hand",
}

ROBOT_NAMES = list(ROBOT_NAME_MAP.keys())
Expand Down
11 changes: 7 additions & 4 deletions tests/test_retargeting_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,14 @@
"allegro_left": "teleop/allegro_hand_left.yml",
"shadow_right": "teleop/shadow_hand_right.yml",
"svh_right": "teleop/schunk_svh_hand_right.yml",
"leap_right": "teleop/leap_hand_right.yml",
"ability_right": "teleop/ability_hand_right.yml",
}
POSITION_CONFIG_DICT = {
"allegro_right": "offline/allegro_hand_right.yml",
# "allegro_left": "offline/allegro_hand_left.yml",
# "shadow_right": "offline/shadow_hand_right.yml",
# "svh_right": "offline/schunk_svh_hand_right.yml",
"shadow_right": "offline/shadow_hand_right.yml",
"svh_right": "offline/schunk_svh_hand_right.yml",
"leap_right": "offline/leap_hand_right.yml",
}
DEXPILOT_CONFIG_DICT = {
"allegro_right": "teleop/allegro_hand_right_dexpilot.yml",
Expand All @@ -30,7 +32,8 @@ class TestRetargetingConfig:
RetargetingConfig.set_default_urdf_dir(str(robot_dir.absolute()))

config_paths = (
list(VECTOR_CONFIG_DICT.values()) + list(POSITION_CONFIG_DICT.values()) + list(DEXPILOT_CONFIG_DICT.values())
list(VECTOR_CONFIG_DICT.values()) + list(POSITION_CONFIG_DICT.values()) + list(
DEXPILOT_CONFIG_DICT.values())
)

@pytest.mark.parametrize("config_path", config_paths)
Expand Down
6 changes: 4 additions & 2 deletions tests/test_sapien_optimizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
import pytest
import sapien.core as sapien

from dex_retargeting.constants import ROBOT_NAMES, get_default_config_path, RetargetingType, HandType
from dex_retargeting.constants import ROBOT_NAMES, get_default_config_path, RetargetingType, HandType, RobotName
from dex_retargeting.optimizer import VectorOptimizer, PositionOptimizer
from dex_retargeting.retargeting_config import RetargetingConfig

Expand All @@ -15,6 +15,8 @@ class TestSapienOptimizer:
config_dir = Path(__file__).parent.parent / "dex_retargeting" / "configs"
robot_dir = Path(__file__).parent.parent / "assets" / "robots" / "hands"
RetargetingConfig.set_default_urdf_dir(str(robot_dir.absolute()))
DEXPILOT_ROBOT_NAMES = ROBOT_NAMES.copy()
DEXPILOT_ROBOT_NAMES.remove(RobotName.ability)

@staticmethod
def generate_vector_retargeting_data_gt(robot: sapien.Articulation, optimizer: VectorOptimizer):
Expand Down Expand Up @@ -125,7 +127,7 @@ def test_vector_optimizer(self, robot_name, hand_type):
print(f"Retargeting computation for {robot_name.name} takes {tac - tic}s for {num_optimization} times")
assert np.mean(errors["pos"]) < 1e-2

@pytest.mark.parametrize("robot_name", ROBOT_NAMES)
@pytest.mark.parametrize("robot_name", DEXPILOT_ROBOT_NAMES)
@pytest.mark.parametrize("hand_type", [name for name in HandType][:1])
def test_dexpilot_optimizer(self, robot_name, hand_type):
config_path = get_default_config_path(robot_name, RetargetingType.dexpilot, hand_type)
Expand Down

0 comments on commit 30eb81e

Please sign in to comment.