diff --git a/dex_retargeting/configs/teleop/panda_gripper.yml b/dex_retargeting/configs/teleop/panda_gripper.yml new file mode 100644 index 0000000..7d99398 --- /dev/null +++ b/dex_retargeting/configs/teleop/panda_gripper.yml @@ -0,0 +1,17 @@ +retargeting: + type: vector + urdf_path: panda_gripper/panda_v2_gripper.urdf + wrist_link_name: "base_link" + + # Target refers to the retargeting target, which is the robot hand + target_joint_names: [ "panda_finger_joint1" ] + target_origin_link_names: [ "panda_leftfinger" ] + target_task_link_names: [ "panda_rightfinger" ] + scaling_factor: 1.5 + + # 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: [ [ 4 ], [ 8 ] ] + + # A smaller alpha means stronger filtering, i.e. more smooth but also larger latency + low_pass_alpha: 0.2 diff --git a/dex_retargeting/constants.py b/dex_retargeting/constants.py index 27f7e87..700dca4 100644 --- a/dex_retargeting/constants.py +++ b/dex_retargeting/constants.py @@ -9,6 +9,7 @@ class RobotName(enum.Enum): leap = enum.auto() ability = enum.auto() inspire = enum.auto() + panda = enum.auto() class RetargetingType(enum.Enum): @@ -29,6 +30,7 @@ class HandType(enum.Enum): RobotName.leap: "leap_hand", RobotName.ability: "ability_hand", RobotName.inspire: "inspire_hand", + RobotName.panda: "panda_gripper", } ROBOT_NAMES = list(ROBOT_NAME_MAP.keys())