mani-skill-nightly 2025.10.21.2002__py3-none-any.whl → 2025.10.22.143__py3-none-any.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- mani_skill/agents/robots/__init__.py +1 -0
- mani_skill/agents/robots/floating_ability_hand/__init__.py +1 -0
- mani_skill/agents/robots/floating_ability_hand/floating_ability_hand.py +217 -0
- mani_skill/assets/robots/ability_hand/ability_hand_left_floating.urdf +554 -0
- mani_skill/assets/robots/ability_hand/ability_hand_right_floating.urdf +554 -0
- mani_skill/envs/sapien_env.py +4 -1
- mani_skill/envs/tasks/dexterity/__init__.py +1 -0
- mani_skill/envs/tasks/dexterity/insert_flower.py +180 -0
- mani_skill/utils/assets/data.py +5 -0
- mani_skill/utils/structs/types.py +3 -1
- mani_skill/utils/wrappers/record.py +4 -3
- {mani_skill_nightly-2025.10.21.2002.dist-info → mani_skill_nightly-2025.10.22.143.dist-info}/METADATA +1 -1
- {mani_skill_nightly-2025.10.21.2002.dist-info → mani_skill_nightly-2025.10.22.143.dist-info}/RECORD +17 -12
- {mani_skill_nightly-2025.10.21.2002.dist-info → mani_skill_nightly-2025.10.22.143.dist-info}/WHEEL +0 -0
- {mani_skill_nightly-2025.10.21.2002.dist-info → mani_skill_nightly-2025.10.22.143.dist-info}/licenses/LICENSE +0 -0
- {mani_skill_nightly-2025.10.21.2002.dist-info → mani_skill_nightly-2025.10.22.143.dist-info}/licenses/LICENSE-3RD-PARTY +0 -0
- {mani_skill_nightly-2025.10.21.2002.dist-info → mani_skill_nightly-2025.10.22.143.dist-info}/top_level.txt +0 -0
|
@@ -2,6 +2,7 @@ from .allegro_hand import *
|
|
|
2
2
|
from .anymal import ANYmalC
|
|
3
3
|
from .dclaw import DClaw
|
|
4
4
|
from .fetch import Fetch
|
|
5
|
+
from .floating_ability_hand import FloatingAbilityHandRight
|
|
5
6
|
from .floating_panda_gripper import FloatingPandaGripper
|
|
6
7
|
from .floating_robotiq_2f_85_gripper import *
|
|
7
8
|
from .googlerobot import *
|
|
@@ -0,0 +1 @@
|
|
|
1
|
+
from .floating_ability_hand import FloatingAbilityHandRight
|
|
@@ -0,0 +1,217 @@
|
|
|
1
|
+
from copy import deepcopy
|
|
2
|
+
from typing import Dict, Tuple
|
|
3
|
+
|
|
4
|
+
import numpy as np
|
|
5
|
+
import sapien
|
|
6
|
+
import sapien.physx as physx
|
|
7
|
+
|
|
8
|
+
from mani_skill import PACKAGE_ASSET_DIR
|
|
9
|
+
from mani_skill.agents.base_agent import BaseAgent, Keyframe
|
|
10
|
+
from mani_skill.agents.controllers import *
|
|
11
|
+
from mani_skill.agents.registration import register_agent
|
|
12
|
+
from mani_skill.utils import sapien_utils
|
|
13
|
+
|
|
14
|
+
|
|
15
|
+
@register_agent()
|
|
16
|
+
class FloatingAbilityHandRight(BaseAgent):
|
|
17
|
+
uid = "floating_ability_hand_right"
|
|
18
|
+
urdf_path = f"{PACKAGE_ASSET_DIR}/robots/ability_hand/ability_hand_right_floating.urdf"
|
|
19
|
+
urdf_config = dict(
|
|
20
|
+
_materials=dict(
|
|
21
|
+
front_finger=dict(
|
|
22
|
+
static_friction=2.0, dynamic_friction=1.5, restitution=0.0
|
|
23
|
+
)
|
|
24
|
+
),
|
|
25
|
+
link=dict(
|
|
26
|
+
thumnb_L2=dict(
|
|
27
|
+
material="front_finger", patch_radius=0.05, min_patch_radius=0.04
|
|
28
|
+
),
|
|
29
|
+
index_L2=dict(
|
|
30
|
+
material="front_finger", patch_radius=0.05, min_patch_radius=0.04
|
|
31
|
+
),
|
|
32
|
+
middle_L2=dict(
|
|
33
|
+
material="front_finger", patch_radius=0.05, min_patch_radius=0.04
|
|
34
|
+
),
|
|
35
|
+
ring_L2=dict(
|
|
36
|
+
material="front_finger", patch_radius=0.05, min_patch_radius=0.04
|
|
37
|
+
),
|
|
38
|
+
pinky_L2=dict(
|
|
39
|
+
material="front_finger", patch_radius=0.05, min_patch_radius=0.04
|
|
40
|
+
),
|
|
41
|
+
),
|
|
42
|
+
)
|
|
43
|
+
|
|
44
|
+
keyframes = dict(
|
|
45
|
+
rest=Keyframe(
|
|
46
|
+
qpos=np.array(
|
|
47
|
+
[
|
|
48
|
+
0.0,
|
|
49
|
+
0.0,
|
|
50
|
+
0.0,
|
|
51
|
+
0.0,
|
|
52
|
+
0.0,
|
|
53
|
+
0.0,
|
|
54
|
+
0.0,
|
|
55
|
+
0.0,
|
|
56
|
+
0.0,
|
|
57
|
+
0.0,
|
|
58
|
+
0.0,
|
|
59
|
+
0.0,
|
|
60
|
+
0.0,
|
|
61
|
+
0.0,
|
|
62
|
+
0.0,
|
|
63
|
+
0.0,
|
|
64
|
+
]
|
|
65
|
+
),
|
|
66
|
+
pose=sapien.Pose(p=[0, 0, 0]),
|
|
67
|
+
)
|
|
68
|
+
)
|
|
69
|
+
|
|
70
|
+
root_joint_names = [
|
|
71
|
+
"root_x_axis_joint",
|
|
72
|
+
"root_y_axis_joint",
|
|
73
|
+
"root_z_axis_joint",
|
|
74
|
+
"root_x_rot_joint",
|
|
75
|
+
"root_y_rot_joint",
|
|
76
|
+
"root_z_rot_joint",
|
|
77
|
+
]
|
|
78
|
+
|
|
79
|
+
def __init__(self, *args, **kwargs):
|
|
80
|
+
|
|
81
|
+
self.hand_joint_names = [
|
|
82
|
+
"index_q1",
|
|
83
|
+
"middle_q1",
|
|
84
|
+
"ring_q1",
|
|
85
|
+
"pinky_q1",
|
|
86
|
+
"index_q2",
|
|
87
|
+
"middle_q2",
|
|
88
|
+
"ring_q2",
|
|
89
|
+
"pinky_q2",
|
|
90
|
+
|
|
91
|
+
# "thumb_q1",
|
|
92
|
+
# "index_q1",
|
|
93
|
+
# "middle_q1",
|
|
94
|
+
# "ring_q1",
|
|
95
|
+
# "pinky_q1",
|
|
96
|
+
# "thumb_q2",
|
|
97
|
+
# "index_q2",
|
|
98
|
+
# "middle_q2",
|
|
99
|
+
# "ring_q2",
|
|
100
|
+
# "pinky_q2",
|
|
101
|
+
]
|
|
102
|
+
self.thumb_joint_names = [
|
|
103
|
+
"thumb_q1",
|
|
104
|
+
"thumb_q2"
|
|
105
|
+
]
|
|
106
|
+
self.hand_stiffness = 1e3
|
|
107
|
+
self.hand_damping = 1e2
|
|
108
|
+
self.hand_force_limit = 50
|
|
109
|
+
|
|
110
|
+
self.ee_link_name = "base"
|
|
111
|
+
|
|
112
|
+
super().__init__(*args, **kwargs)
|
|
113
|
+
|
|
114
|
+
@property
|
|
115
|
+
def _controller_configs(self):
|
|
116
|
+
# -------------------------------------------------------------------------- #
|
|
117
|
+
# Arm
|
|
118
|
+
# -------------------------------------------------------------------------- #
|
|
119
|
+
float_pd_joint_pos = PDJointPosControllerConfig(
|
|
120
|
+
joint_names=self.root_joint_names,
|
|
121
|
+
lower=None,
|
|
122
|
+
upper=None,
|
|
123
|
+
stiffness=1e3,
|
|
124
|
+
damping=1e2,
|
|
125
|
+
force_limit=100,
|
|
126
|
+
normalize_action=False,
|
|
127
|
+
)
|
|
128
|
+
|
|
129
|
+
# -------------------------------------------------------------------------- #
|
|
130
|
+
# Hand
|
|
131
|
+
# -------------------------------------------------------------------------- #
|
|
132
|
+
hand_joint_pos = PDJointPosMimicControllerConfig(
|
|
133
|
+
self.hand_joint_names,
|
|
134
|
+
None,# [0, 0, 0, 0, 0, 0, 0, 0, -2.0943951, 0],
|
|
135
|
+
None, # [2.0943951, 2.0943951, 2.0943951, 2.0943951, 2.65860, 2.65860, 2.65860, 2.65860, 0, 2.0943951],
|
|
136
|
+
self.hand_stiffness,
|
|
137
|
+
self.hand_damping,
|
|
138
|
+
self.hand_force_limit,
|
|
139
|
+
mimic={
|
|
140
|
+
"index_q2": {
|
|
141
|
+
"joint": "index_q1",
|
|
142
|
+
"multiplier": 1.05851325,
|
|
143
|
+
"offset": 0.72349796,
|
|
144
|
+
},
|
|
145
|
+
"middle_q2": {
|
|
146
|
+
"joint": "middle_q1",
|
|
147
|
+
"multiplier": 1.05851325,
|
|
148
|
+
"offset": 0.72349796,
|
|
149
|
+
},
|
|
150
|
+
"ring_q2": {
|
|
151
|
+
"joint": "ring_q1",
|
|
152
|
+
"multiplier": 1.05851325,
|
|
153
|
+
"offset": 0.72349796,
|
|
154
|
+
},
|
|
155
|
+
"pinky_q2": {
|
|
156
|
+
"joint": "pinky_q1",
|
|
157
|
+
"multiplier": 1.05851325,
|
|
158
|
+
"offset": 0.72349796,
|
|
159
|
+
},
|
|
160
|
+
},
|
|
161
|
+
normalize_action=False,
|
|
162
|
+
)
|
|
163
|
+
thumb_joint_pos = PDJointPosControllerConfig(
|
|
164
|
+
self.thumb_joint_names,
|
|
165
|
+
None, # [0, 0, 0, 0, 0, 0, 0, 0, -2.0943951, 0],
|
|
166
|
+
None, # [2.0943951, 2.0943951, 2.0943951, 2.0943951, 2.65860, 2.65860, 2.65860, 2.65860, 0, 2.0943951],
|
|
167
|
+
self.hand_stiffness,
|
|
168
|
+
self.hand_damping,
|
|
169
|
+
self.hand_force_limit,
|
|
170
|
+
normalize_action=False,
|
|
171
|
+
)
|
|
172
|
+
# hand_target_delta_pos.use_target = True
|
|
173
|
+
|
|
174
|
+
controller_configs = dict(
|
|
175
|
+
pd_joint_pos=dict(
|
|
176
|
+
root=float_pd_joint_pos, hand=hand_joint_pos, thumb=thumb_joint_pos
|
|
177
|
+
),
|
|
178
|
+
# pd_joint_pos=dict(arm=arm_pd_joint_pos, gripper=hand_target_delta_pos),
|
|
179
|
+
# pd_ee_delta_pose=dict(
|
|
180
|
+
# arm=arm_pd_ee_delta_pose, gripper=hand_target_delta_pos
|
|
181
|
+
# ),
|
|
182
|
+
# pd_ee_target_delta_pose=dict(
|
|
183
|
+
# arm=arm_pd_ee_target_delta_pose, gripper=hand_target_delta_pos
|
|
184
|
+
# ),
|
|
185
|
+
)
|
|
186
|
+
|
|
187
|
+
# Make a deepcopy in case users modify any config
|
|
188
|
+
return deepcopy_dict(controller_configs)
|
|
189
|
+
|
|
190
|
+
def _after_init(self):
|
|
191
|
+
hand_front_link_names = [
|
|
192
|
+
"thumb_L2",
|
|
193
|
+
"index_L2",
|
|
194
|
+
"middle_L2",
|
|
195
|
+
"ring_L2",
|
|
196
|
+
"pinky_L2",
|
|
197
|
+
]
|
|
198
|
+
self.hand_front_links = sapien_utils.get_objs_by_names(
|
|
199
|
+
self.robot.get_links(), hand_front_link_names
|
|
200
|
+
)
|
|
201
|
+
|
|
202
|
+
finger_tip_link_names = [
|
|
203
|
+
"thumb_tip",
|
|
204
|
+
"index_tip",
|
|
205
|
+
"middle_tip",
|
|
206
|
+
"ring_tip",
|
|
207
|
+
"pinky_tip",
|
|
208
|
+
]
|
|
209
|
+
self.finger_tip_links = sapien_utils.get_objs_by_names(
|
|
210
|
+
self.robot.get_links(), finger_tip_link_names
|
|
211
|
+
)
|
|
212
|
+
|
|
213
|
+
self.tcp = sapien_utils.get_obj_by_name(
|
|
214
|
+
self.robot.get_links(), self.ee_link_name
|
|
215
|
+
)
|
|
216
|
+
|
|
217
|
+
self.queries: Dict[str, Tuple[physx.PhysxGpuContactQuery, Tuple[int]]] = dict()
|