mani-skill-nightly 2025.5.20.817__py3-none-any.whl → 2025.5.21.816__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 +6 -1
- mani_skill/agents/robots/inspire_hand/__init__.py +2 -0
- mani_skill/agents/robots/inspire_hand/fixed_inspire_hand.py +246 -0
- mani_skill/agents/robots/inspire_hand/floating_inspire_hand.py +414 -0
- mani_skill/assets/robots/inspire_hand/README.md +23 -0
- mani_skill/assets/robots/inspire_hand/{urdf/end_effector/inspire_hand → RH56DFX-2LR/urdf}/inspire_hand_left.urdf +43 -48
- mani_skill/assets/robots/inspire_hand/RH56DFX-2LR/urdf/inspire_hand_left_floating.urdf +516 -0
- mani_skill/assets/robots/inspire_hand/{urdf/end_effector/inspire_hand → RH56DFX-2LR/urdf}/inspire_hand_right.urdf +43 -40
- mani_skill/assets/robots/inspire_hand/{urdf/end_effector/inspire_hand → RH56DFX-2LR/urdf}/inspire_hand_right_floating.urdf +43 -40
- {mani_skill_nightly-2025.5.20.817.dist-info → mani_skill_nightly-2025.5.21.816.dist-info}/METADATA +1 -1
- {mani_skill_nightly-2025.5.20.817.dist-info → mani_skill_nightly-2025.5.21.816.dist-info}/RECORD +29 -26
- mani_skill/agents/robots/floating_inspire_hand/__init__.py +0 -1
- mani_skill/agents/robots/floating_inspire_hand/floating_inspire_hand.py +0 -187
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/L_hand_base_link.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/L_thumb_metacarpal_base.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/L_wrist_link.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/R_hand_base_link.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/R_thumb_metacarpal_base.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/R_wrist_link.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/index_ring_middle.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/index_ring_proximal.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/middle_middle.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/middle_pinky_proximal.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/pinky_middle.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/thumb_distal.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/thumb_metacarpal.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/thumb_proximal.glb +0 -0
- /mani_skill/assets/robots/inspire_hand/{meshes/end_effector/inspire_hand → RH56DFX-2LR/meshes}/visual/wrist_base_link.glb +0 -0
- {mani_skill_nightly-2025.5.20.817.dist-info → mani_skill_nightly-2025.5.21.816.dist-info}/LICENSE +0 -0
- {mani_skill_nightly-2025.5.20.817.dist-info → mani_skill_nightly-2025.5.21.816.dist-info}/WHEEL +0 -0
- {mani_skill_nightly-2025.5.20.817.dist-info → mani_skill_nightly-2025.5.21.816.dist-info}/top_level.txt +0 -0
@@ -2,11 +2,16 @@ 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_inspire_hand import FloatingInspireHandRight
|
6
5
|
from .floating_panda_gripper import FloatingPandaGripper
|
7
6
|
from .floating_robotiq_2f_85_gripper import *
|
8
7
|
from .googlerobot import *
|
9
8
|
from .humanoid import Humanoid
|
9
|
+
from .inspire_hand import (
|
10
|
+
FixedInspireHandLeft,
|
11
|
+
FixedInspireHandRight,
|
12
|
+
FloatingInspireHandLeft,
|
13
|
+
FloatingInspireHandRight,
|
14
|
+
)
|
10
15
|
from .koch import *
|
11
16
|
from .panda import *
|
12
17
|
from .so100 import *
|
@@ -0,0 +1,246 @@
|
|
1
|
+
from copy import deepcopy
|
2
|
+
|
3
|
+
import numpy as np
|
4
|
+
import sapien
|
5
|
+
from transforms3d.euler import euler2quat
|
6
|
+
|
7
|
+
from mani_skill import PACKAGE_ASSET_DIR
|
8
|
+
from mani_skill.agents.base_agent import Keyframe
|
9
|
+
from mani_skill.agents.controllers import *
|
10
|
+
from mani_skill.agents.registration import register_agent
|
11
|
+
from mani_skill.agents.robots.inspire_hand.floating_inspire_hand import (
|
12
|
+
FloatingInspireHandLeft,
|
13
|
+
FloatingInspireHandRight,
|
14
|
+
)
|
15
|
+
|
16
|
+
|
17
|
+
@register_agent()
|
18
|
+
class FixedInspireHandRight(FloatingInspireHandRight):
|
19
|
+
uid = "fixed_inspire_hand_right"
|
20
|
+
urdf_path = f"{PACKAGE_ASSET_DIR}/robots/inspire_hand/RH56DFX-2LR/urdf/inspire_hand_right.urdf"
|
21
|
+
keyframes = dict(
|
22
|
+
palm_side=Keyframe(
|
23
|
+
# magic numbers below correspond with controlling joints being set to 0. The other non-active revolute joints are mimic joints
|
24
|
+
qpos=[
|
25
|
+
[
|
26
|
+
0,
|
27
|
+
0,
|
28
|
+
0,
|
29
|
+
0,
|
30
|
+
0,
|
31
|
+
0,
|
32
|
+
0,
|
33
|
+
0,
|
34
|
+
-0.16734816,
|
35
|
+
-0.16734803,
|
36
|
+
-0.16734798,
|
37
|
+
-0.167348,
|
38
|
+
-0.08147363,
|
39
|
+
-0.07234851,
|
40
|
+
]
|
41
|
+
],
|
42
|
+
pose=sapien.Pose(p=[0, 0, 0.4], q=euler2quat(0, 0, -np.pi / 2)),
|
43
|
+
),
|
44
|
+
palm_up=Keyframe(
|
45
|
+
qpos=[
|
46
|
+
[
|
47
|
+
0,
|
48
|
+
0,
|
49
|
+
0,
|
50
|
+
0,
|
51
|
+
0,
|
52
|
+
0,
|
53
|
+
0,
|
54
|
+
0,
|
55
|
+
-0.16734816,
|
56
|
+
-0.16734803,
|
57
|
+
-0.16734798,
|
58
|
+
-0.167348,
|
59
|
+
-0.08147363,
|
60
|
+
-0.07234851,
|
61
|
+
]
|
62
|
+
],
|
63
|
+
pose=sapien.Pose(p=[0, 0, 0.4], q=euler2quat(np.pi / 2, 0, -np.pi / 2)),
|
64
|
+
),
|
65
|
+
)
|
66
|
+
|
67
|
+
@property
|
68
|
+
def _controller_configs(self):
|
69
|
+
wrist_joint_pos = PDJointPosControllerConfig(
|
70
|
+
joint_names=["right_hand_wrist_pitch_joint", "right_hand_wrist_yaw_joint"],
|
71
|
+
lower=None,
|
72
|
+
upper=None,
|
73
|
+
stiffness=1e3,
|
74
|
+
damping=1e2,
|
75
|
+
force_limit=100,
|
76
|
+
normalize_action=False,
|
77
|
+
)
|
78
|
+
fingers_joint_pos = PDJointPosControllerConfig(
|
79
|
+
joint_names=[
|
80
|
+
"right_hand_thumb_CMC_yaw_joint",
|
81
|
+
"right_hand_thumb_CMC_pitch_joint",
|
82
|
+
"right_hand_index_MCP_joint",
|
83
|
+
"right_hand_middle_MCP_joint",
|
84
|
+
"right_hand_ring_MCP_joint",
|
85
|
+
"right_hand_pinky_MCP_joint",
|
86
|
+
],
|
87
|
+
lower=None,
|
88
|
+
upper=None,
|
89
|
+
stiffness=1e3,
|
90
|
+
damping=1e2,
|
91
|
+
force_limit=20,
|
92
|
+
normalize_action=False,
|
93
|
+
)
|
94
|
+
passive = PassiveControllerConfig(
|
95
|
+
joint_names=[
|
96
|
+
"right_hand_thumb_MCP_joint",
|
97
|
+
"right_hand_thumb_IP_joint",
|
98
|
+
"right_hand_index_PIP_joint",
|
99
|
+
"right_hand_middle_PIP_joint",
|
100
|
+
"right_hand_ring_PIP_joint",
|
101
|
+
"right_hand_pinky_PIP_joint",
|
102
|
+
],
|
103
|
+
damping=0.001,
|
104
|
+
force_limit=20,
|
105
|
+
)
|
106
|
+
|
107
|
+
wrist_joint_delta_pos = deepcopy(wrist_joint_pos)
|
108
|
+
wrist_joint_delta_pos.use_delta = True
|
109
|
+
wrist_joint_delta_pos.normalize_action = True
|
110
|
+
wrist_joint_delta_pos.lower = -0.1
|
111
|
+
wrist_joint_delta_pos.upper = 0.1
|
112
|
+
|
113
|
+
fingers_joint_delta_pos = deepcopy(fingers_joint_pos)
|
114
|
+
fingers_joint_delta_pos.use_delta = True
|
115
|
+
fingers_joint_delta_pos.normalize_action = True
|
116
|
+
fingers_joint_delta_pos.lower = -0.1
|
117
|
+
fingers_joint_delta_pos.upper = 0.1
|
118
|
+
|
119
|
+
return dict(
|
120
|
+
pd_joint_pos=dict(
|
121
|
+
wrist=wrist_joint_pos,
|
122
|
+
fingers=fingers_joint_pos,
|
123
|
+
passive=passive,
|
124
|
+
),
|
125
|
+
pd_joint_delta_pos=dict(
|
126
|
+
wrist=wrist_joint_delta_pos,
|
127
|
+
fingers=fingers_joint_delta_pos,
|
128
|
+
passive=passive,
|
129
|
+
),
|
130
|
+
)
|
131
|
+
|
132
|
+
|
133
|
+
@register_agent()
|
134
|
+
class FixedInspireHandLeft(FloatingInspireHandLeft):
|
135
|
+
uid = "fixed_inspire_hand_left"
|
136
|
+
urdf_path = f"{PACKAGE_ASSET_DIR}/robots/inspire_hand/RH56DFX-2LR/urdf/inspire_hand_left.urdf"
|
137
|
+
keyframes = dict(
|
138
|
+
palm_side=Keyframe(
|
139
|
+
# magic numbers below correspond with controlling joints being set to 0. The other non-active revolute joints are mimic joints
|
140
|
+
qpos=[
|
141
|
+
[
|
142
|
+
0,
|
143
|
+
0,
|
144
|
+
0,
|
145
|
+
0,
|
146
|
+
0,
|
147
|
+
0,
|
148
|
+
0,
|
149
|
+
0,
|
150
|
+
-0.16734816,
|
151
|
+
-0.16734803,
|
152
|
+
-0.16734798,
|
153
|
+
-0.167348,
|
154
|
+
-0.08147363,
|
155
|
+
-0.07234851,
|
156
|
+
]
|
157
|
+
],
|
158
|
+
pose=sapien.Pose(p=[0, 0, 0.4], q=euler2quat(0, 0, -np.pi / 2)),
|
159
|
+
),
|
160
|
+
palm_up=Keyframe(
|
161
|
+
qpos=[
|
162
|
+
[
|
163
|
+
0,
|
164
|
+
0,
|
165
|
+
0,
|
166
|
+
0,
|
167
|
+
0,
|
168
|
+
0,
|
169
|
+
0,
|
170
|
+
0,
|
171
|
+
-0.16734816,
|
172
|
+
-0.16734803,
|
173
|
+
-0.16734798,
|
174
|
+
-0.167348,
|
175
|
+
-0.08147363,
|
176
|
+
-0.07234851,
|
177
|
+
]
|
178
|
+
],
|
179
|
+
pose=sapien.Pose(p=[0, 0, 0.4], q=euler2quat(np.pi / 2, 0, -np.pi / 2)),
|
180
|
+
),
|
181
|
+
)
|
182
|
+
|
183
|
+
@property
|
184
|
+
def _controller_configs(self):
|
185
|
+
wrist_joint_pos = PDJointPosControllerConfig(
|
186
|
+
joint_names=["left_hand_wrist_pitch_joint", "left_hand_wrist_yaw_joint"],
|
187
|
+
lower=None,
|
188
|
+
upper=None,
|
189
|
+
stiffness=1e3,
|
190
|
+
damping=1e2,
|
191
|
+
force_limit=100,
|
192
|
+
normalize_action=False,
|
193
|
+
)
|
194
|
+
fingers_joint_pos = PDJointPosControllerConfig(
|
195
|
+
joint_names=[
|
196
|
+
"left_hand_thumb_CMC_yaw_joint",
|
197
|
+
"left_hand_thumb_CMC_pitch_joint",
|
198
|
+
"left_hand_index_MCP_joint",
|
199
|
+
"left_hand_middle_MCP_joint",
|
200
|
+
"left_hand_ring_MCP_joint",
|
201
|
+
"left_hand_pinky_MCP_joint",
|
202
|
+
],
|
203
|
+
lower=None,
|
204
|
+
upper=None,
|
205
|
+
stiffness=1e3,
|
206
|
+
damping=1e2,
|
207
|
+
force_limit=20,
|
208
|
+
normalize_action=False,
|
209
|
+
)
|
210
|
+
passive = PassiveControllerConfig(
|
211
|
+
joint_names=[
|
212
|
+
"left_hand_thumb_MCP_joint",
|
213
|
+
"left_hand_thumb_IP_joint",
|
214
|
+
"left_hand_index_PIP_joint",
|
215
|
+
"left_hand_middle_PIP_joint",
|
216
|
+
"left_hand_ring_PIP_joint",
|
217
|
+
"left_hand_pinky_PIP_joint",
|
218
|
+
],
|
219
|
+
damping=0.001,
|
220
|
+
force_limit=20,
|
221
|
+
)
|
222
|
+
|
223
|
+
wrist_joint_delta_pos = deepcopy(wrist_joint_pos)
|
224
|
+
wrist_joint_delta_pos.use_delta = True
|
225
|
+
wrist_joint_delta_pos.normalize_action = True
|
226
|
+
wrist_joint_delta_pos.lower = -0.1
|
227
|
+
wrist_joint_delta_pos.upper = 0.1
|
228
|
+
|
229
|
+
fingers_joint_delta_pos = deepcopy(fingers_joint_pos)
|
230
|
+
fingers_joint_delta_pos.use_delta = True
|
231
|
+
fingers_joint_delta_pos.normalize_action = True
|
232
|
+
fingers_joint_delta_pos.lower = -0.1
|
233
|
+
fingers_joint_delta_pos.upper = 0.1
|
234
|
+
|
235
|
+
return dict(
|
236
|
+
pd_joint_pos=dict(
|
237
|
+
wrist=wrist_joint_pos,
|
238
|
+
fingers=fingers_joint_pos,
|
239
|
+
passive=passive,
|
240
|
+
),
|
241
|
+
pd_joint_delta_pos=dict(
|
242
|
+
wrist=wrist_joint_delta_pos,
|
243
|
+
fingers=fingers_joint_delta_pos,
|
244
|
+
passive=passive,
|
245
|
+
),
|
246
|
+
)
|
@@ -0,0 +1,414 @@
|
|
1
|
+
from copy import deepcopy
|
2
|
+
|
3
|
+
import numpy as np
|
4
|
+
import sapien
|
5
|
+
from transforms3d.euler import euler2quat
|
6
|
+
|
7
|
+
from mani_skill import PACKAGE_ASSET_DIR
|
8
|
+
from mani_skill.agents.base_agent import BaseAgent, Keyframe
|
9
|
+
from mani_skill.agents.controllers import *
|
10
|
+
from mani_skill.agents.registration import register_agent
|
11
|
+
|
12
|
+
|
13
|
+
@register_agent()
|
14
|
+
class FloatingInspireHandRight(BaseAgent):
|
15
|
+
uid = "floating_inspire_hand_right"
|
16
|
+
urdf_path = f"{PACKAGE_ASSET_DIR}/robots/inspire_hand/RH56DFX-2LR/urdf/inspire_hand_right_floating.urdf"
|
17
|
+
urdf_config = dict(
|
18
|
+
_materials=dict(
|
19
|
+
finger=dict(static_friction=2.0, dynamic_friction=2.0, restitution=0.0)
|
20
|
+
),
|
21
|
+
link=dict(
|
22
|
+
right_hand_hand_base_link=dict(
|
23
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
24
|
+
),
|
25
|
+
right_hand_thumb_distal=dict(
|
26
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
27
|
+
),
|
28
|
+
right_hand_thumb_metacarpal=dict(
|
29
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
30
|
+
),
|
31
|
+
right_hand_thumb_proximal=dict(
|
32
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
33
|
+
),
|
34
|
+
right_hand_index_proximal=dict(
|
35
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
36
|
+
),
|
37
|
+
right_hand_index_middle=dict(
|
38
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
39
|
+
),
|
40
|
+
right_hand_middle_proximal=dict(
|
41
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
42
|
+
),
|
43
|
+
right_hand_middle_middle=dict(
|
44
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
45
|
+
),
|
46
|
+
right_hand_ring_proximal=dict(
|
47
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
48
|
+
),
|
49
|
+
right_hand_ring_middle=dict(
|
50
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
51
|
+
),
|
52
|
+
right_hand_pinky_proximal=dict(
|
53
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
54
|
+
),
|
55
|
+
right_hand_pinky_middle=dict(
|
56
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
57
|
+
),
|
58
|
+
),
|
59
|
+
)
|
60
|
+
disable_self_collisions = True
|
61
|
+
# you could model all of the fingers and disable certain impossible self collisions that occur
|
62
|
+
# but it is simpler and faster to just disable all self collisions. It is highly unlikely the hand self-collides to begin with
|
63
|
+
# due to the design of the hand
|
64
|
+
|
65
|
+
root_joint_names = [
|
66
|
+
"root_x_axis_joint",
|
67
|
+
"root_y_axis_joint",
|
68
|
+
"root_z_axis_joint",
|
69
|
+
"root_x_rot_joint",
|
70
|
+
"root_y_rot_joint",
|
71
|
+
"root_z_rot_joint",
|
72
|
+
]
|
73
|
+
|
74
|
+
keyframes = dict(
|
75
|
+
palm_side=Keyframe(
|
76
|
+
# magic numbers below correspond with controlling joints being set to 0. The other non-active revolute joints are mimic joints
|
77
|
+
qpos=[
|
78
|
+
[
|
79
|
+
0,
|
80
|
+
0,
|
81
|
+
0,
|
82
|
+
0,
|
83
|
+
0,
|
84
|
+
0,
|
85
|
+
0,
|
86
|
+
0,
|
87
|
+
0,
|
88
|
+
0,
|
89
|
+
0,
|
90
|
+
0,
|
91
|
+
0,
|
92
|
+
0,
|
93
|
+
-0.16734816,
|
94
|
+
-0.16734803,
|
95
|
+
-0.16734798,
|
96
|
+
-0.167348,
|
97
|
+
-0.08147363,
|
98
|
+
-0.07234851,
|
99
|
+
]
|
100
|
+
],
|
101
|
+
pose=sapien.Pose(p=[0, 0, 0.4], q=euler2quat(0, 0, -np.pi / 2)),
|
102
|
+
),
|
103
|
+
palm_up=Keyframe(
|
104
|
+
qpos=[
|
105
|
+
[
|
106
|
+
0,
|
107
|
+
0,
|
108
|
+
0,
|
109
|
+
0,
|
110
|
+
0,
|
111
|
+
0,
|
112
|
+
0,
|
113
|
+
0,
|
114
|
+
0,
|
115
|
+
0,
|
116
|
+
0,
|
117
|
+
0,
|
118
|
+
0,
|
119
|
+
0,
|
120
|
+
-0.16734816,
|
121
|
+
-0.16734803,
|
122
|
+
-0.16734798,
|
123
|
+
-0.167348,
|
124
|
+
-0.08147363,
|
125
|
+
-0.07234851,
|
126
|
+
]
|
127
|
+
],
|
128
|
+
pose=sapien.Pose(p=[0, 0, 0.4], q=euler2quat(np.pi / 2, 0, -np.pi / 2)),
|
129
|
+
),
|
130
|
+
)
|
131
|
+
|
132
|
+
@property
|
133
|
+
def _controller_configs(self):
|
134
|
+
float_pd_joint_pos = PDJointPosControllerConfig(
|
135
|
+
joint_names=self.root_joint_names,
|
136
|
+
lower=None,
|
137
|
+
upper=None,
|
138
|
+
stiffness=1e3,
|
139
|
+
damping=1e2,
|
140
|
+
force_limit=100,
|
141
|
+
normalize_action=False,
|
142
|
+
)
|
143
|
+
wrist_joint_pos = PDJointPosControllerConfig(
|
144
|
+
joint_names=["right_hand_wrist_pitch_joint", "right_hand_wrist_yaw_joint"],
|
145
|
+
lower=None,
|
146
|
+
upper=None,
|
147
|
+
stiffness=1e3,
|
148
|
+
damping=1e2,
|
149
|
+
force_limit=100,
|
150
|
+
normalize_action=False,
|
151
|
+
)
|
152
|
+
fingers_joint_pos = PDJointPosControllerConfig(
|
153
|
+
joint_names=[
|
154
|
+
"right_hand_thumb_CMC_yaw_joint",
|
155
|
+
"right_hand_thumb_CMC_pitch_joint",
|
156
|
+
"right_hand_index_MCP_joint",
|
157
|
+
"right_hand_middle_MCP_joint",
|
158
|
+
"right_hand_ring_MCP_joint",
|
159
|
+
"right_hand_pinky_MCP_joint",
|
160
|
+
],
|
161
|
+
lower=None,
|
162
|
+
upper=None,
|
163
|
+
stiffness=1e3,
|
164
|
+
damping=1e2,
|
165
|
+
force_limit=20,
|
166
|
+
normalize_action=False,
|
167
|
+
)
|
168
|
+
passive = PassiveControllerConfig(
|
169
|
+
joint_names=[
|
170
|
+
"right_hand_thumb_MCP_joint",
|
171
|
+
"right_hand_thumb_IP_joint",
|
172
|
+
"right_hand_index_PIP_joint",
|
173
|
+
"right_hand_middle_PIP_joint",
|
174
|
+
"right_hand_ring_PIP_joint",
|
175
|
+
"right_hand_pinky_PIP_joint",
|
176
|
+
],
|
177
|
+
damping=0.001, # NOTE (stao): This magic number is necessary for physx to simulate correctly...
|
178
|
+
force_limit=20,
|
179
|
+
)
|
180
|
+
|
181
|
+
wrist_joint_delta_pos = deepcopy(wrist_joint_pos)
|
182
|
+
wrist_joint_delta_pos.use_delta = True
|
183
|
+
wrist_joint_delta_pos.normalize_action = True
|
184
|
+
wrist_joint_delta_pos.lower = -0.1
|
185
|
+
wrist_joint_delta_pos.upper = 0.1
|
186
|
+
|
187
|
+
fingers_joint_delta_pos = deepcopy(fingers_joint_pos)
|
188
|
+
fingers_joint_delta_pos.use_delta = True
|
189
|
+
fingers_joint_delta_pos.normalize_action = True
|
190
|
+
fingers_joint_delta_pos.lower = -0.1
|
191
|
+
fingers_joint_delta_pos.upper = 0.1
|
192
|
+
|
193
|
+
float_pd_joint_delta_pos = deepcopy(float_pd_joint_pos)
|
194
|
+
float_pd_joint_delta_pos.use_delta = True
|
195
|
+
float_pd_joint_delta_pos.normalize_action = True
|
196
|
+
float_pd_joint_delta_pos.lower = -0.1
|
197
|
+
float_pd_joint_delta_pos.upper = 0.1
|
198
|
+
|
199
|
+
return dict(
|
200
|
+
pd_joint_pos=dict(
|
201
|
+
root=float_pd_joint_pos,
|
202
|
+
wrist=wrist_joint_pos,
|
203
|
+
fingers=fingers_joint_pos,
|
204
|
+
passive=passive,
|
205
|
+
),
|
206
|
+
pd_joint_delta_pos=dict(
|
207
|
+
root=float_pd_joint_delta_pos,
|
208
|
+
wrist=wrist_joint_delta_pos,
|
209
|
+
fingers=fingers_joint_delta_pos,
|
210
|
+
passive=passive,
|
211
|
+
),
|
212
|
+
)
|
213
|
+
|
214
|
+
|
215
|
+
@register_agent()
|
216
|
+
class FloatingInspireHandLeft(BaseAgent):
|
217
|
+
uid = "floating_inspire_hand_left"
|
218
|
+
urdf_path = f"{PACKAGE_ASSET_DIR}/robots/inspire_hand/RH56DFX-2LR/urdf/inspire_hand_left_floating.urdf"
|
219
|
+
urdf_config = dict(
|
220
|
+
_materials=dict(
|
221
|
+
finger=dict(static_friction=2.0, dynamic_friction=2.0, restitution=0.0)
|
222
|
+
),
|
223
|
+
link=dict(
|
224
|
+
left_hand_hand_base_link=dict(
|
225
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
226
|
+
),
|
227
|
+
left_hand_thumb_distal=dict(
|
228
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
229
|
+
),
|
230
|
+
left_hand_thumb_metacarpal=dict(
|
231
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
232
|
+
),
|
233
|
+
left_hand_thumb_proximal=dict(
|
234
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
235
|
+
),
|
236
|
+
left_hand_index_proximal=dict(
|
237
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
238
|
+
),
|
239
|
+
left_hand_index_middle=dict(
|
240
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
241
|
+
),
|
242
|
+
left_hand_middle_proximal=dict(
|
243
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
244
|
+
),
|
245
|
+
left_hand_middle_middle=dict(
|
246
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
247
|
+
),
|
248
|
+
left_hand_ring_proximal=dict(
|
249
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
250
|
+
),
|
251
|
+
left_hand_ring_middle=dict(
|
252
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
253
|
+
),
|
254
|
+
left_hand_pinky_proximal=dict(
|
255
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
256
|
+
),
|
257
|
+
left_hand_pinky_middle=dict(
|
258
|
+
material="finger", patch_radius=0.1, min_patch_radius=0.1
|
259
|
+
),
|
260
|
+
),
|
261
|
+
)
|
262
|
+
disable_self_collisions = True
|
263
|
+
# you could model all of the fingers and disable certain impossible self collisions that occur
|
264
|
+
# but it is simpler and faster to just disable all self collisions. It is highly unlikely the hand self-collides to begin with
|
265
|
+
# due to the design of the hand
|
266
|
+
|
267
|
+
root_joint_names = [
|
268
|
+
"root_x_axis_joint",
|
269
|
+
"root_y_axis_joint",
|
270
|
+
"root_z_axis_joint",
|
271
|
+
"root_x_rot_joint",
|
272
|
+
"root_y_rot_joint",
|
273
|
+
"root_z_rot_joint",
|
274
|
+
]
|
275
|
+
|
276
|
+
keyframes = dict(
|
277
|
+
palm_side=Keyframe(
|
278
|
+
# magic numbers below correspond with controlling joints being set to 0. The other non-active revolute joints are mimic joints
|
279
|
+
qpos=[
|
280
|
+
[
|
281
|
+
0,
|
282
|
+
0,
|
283
|
+
0,
|
284
|
+
0,
|
285
|
+
0,
|
286
|
+
0,
|
287
|
+
0,
|
288
|
+
0,
|
289
|
+
0,
|
290
|
+
0,
|
291
|
+
0,
|
292
|
+
0,
|
293
|
+
0,
|
294
|
+
0,
|
295
|
+
-0.16734816,
|
296
|
+
-0.16734803,
|
297
|
+
-0.16734798,
|
298
|
+
-0.167348,
|
299
|
+
-0.08147363,
|
300
|
+
-0.07234851,
|
301
|
+
]
|
302
|
+
],
|
303
|
+
pose=sapien.Pose(p=[0, 0, 0.4], q=euler2quat(0, 0, -np.pi / 2)),
|
304
|
+
),
|
305
|
+
palm_up=Keyframe(
|
306
|
+
qpos=[
|
307
|
+
[
|
308
|
+
0,
|
309
|
+
0,
|
310
|
+
0,
|
311
|
+
0,
|
312
|
+
0,
|
313
|
+
0,
|
314
|
+
0,
|
315
|
+
0,
|
316
|
+
0,
|
317
|
+
0,
|
318
|
+
0,
|
319
|
+
0,
|
320
|
+
0,
|
321
|
+
0,
|
322
|
+
-0.16734816,
|
323
|
+
-0.16734803,
|
324
|
+
-0.16734798,
|
325
|
+
-0.167348,
|
326
|
+
-0.08147363,
|
327
|
+
-0.07234851,
|
328
|
+
]
|
329
|
+
],
|
330
|
+
pose=sapien.Pose(p=[0, 0, 0.4], q=euler2quat(np.pi / 2, 0, -np.pi / 2)),
|
331
|
+
),
|
332
|
+
)
|
333
|
+
|
334
|
+
@property
|
335
|
+
def _controller_configs(self):
|
336
|
+
float_pd_joint_pos = PDJointPosControllerConfig(
|
337
|
+
joint_names=self.root_joint_names,
|
338
|
+
lower=None,
|
339
|
+
upper=None,
|
340
|
+
stiffness=1e3,
|
341
|
+
damping=1e2,
|
342
|
+
force_limit=100,
|
343
|
+
normalize_action=False,
|
344
|
+
)
|
345
|
+
wrist_joint_pos = PDJointPosControllerConfig(
|
346
|
+
joint_names=["left_hand_wrist_pitch_joint", "left_hand_wrist_yaw_joint"],
|
347
|
+
lower=None,
|
348
|
+
upper=None,
|
349
|
+
stiffness=1e3,
|
350
|
+
damping=1e2,
|
351
|
+
force_limit=100,
|
352
|
+
normalize_action=False,
|
353
|
+
)
|
354
|
+
fingers_joint_pos = PDJointPosControllerConfig(
|
355
|
+
joint_names=[
|
356
|
+
"left_hand_thumb_CMC_yaw_joint",
|
357
|
+
"left_hand_thumb_CMC_pitch_joint",
|
358
|
+
"left_hand_index_MCP_joint",
|
359
|
+
"left_hand_middle_MCP_joint",
|
360
|
+
"left_hand_ring_MCP_joint",
|
361
|
+
"left_hand_pinky_MCP_joint",
|
362
|
+
],
|
363
|
+
lower=None,
|
364
|
+
upper=None,
|
365
|
+
stiffness=1e3,
|
366
|
+
damping=1e2,
|
367
|
+
force_limit=20,
|
368
|
+
normalize_action=False,
|
369
|
+
)
|
370
|
+
passive = PassiveControllerConfig(
|
371
|
+
joint_names=[
|
372
|
+
"left_hand_thumb_MCP_joint",
|
373
|
+
"left_hand_thumb_IP_joint",
|
374
|
+
"left_hand_index_PIP_joint",
|
375
|
+
"left_hand_middle_PIP_joint",
|
376
|
+
"left_hand_ring_PIP_joint",
|
377
|
+
"left_hand_pinky_PIP_joint",
|
378
|
+
],
|
379
|
+
damping=0.001, # NOTE (stao): This magic number is necessary for physx to simulate correctly...
|
380
|
+
force_limit=20,
|
381
|
+
)
|
382
|
+
|
383
|
+
wrist_joint_delta_pos = deepcopy(wrist_joint_pos)
|
384
|
+
wrist_joint_delta_pos.use_delta = True
|
385
|
+
wrist_joint_delta_pos.normalize_action = True
|
386
|
+
wrist_joint_delta_pos.lower = -0.1
|
387
|
+
wrist_joint_delta_pos.upper = 0.1
|
388
|
+
|
389
|
+
fingers_joint_delta_pos = deepcopy(fingers_joint_pos)
|
390
|
+
fingers_joint_delta_pos.use_delta = True
|
391
|
+
fingers_joint_delta_pos.normalize_action = True
|
392
|
+
fingers_joint_delta_pos.lower = -0.1
|
393
|
+
fingers_joint_delta_pos.upper = 0.1
|
394
|
+
|
395
|
+
float_pd_joint_delta_pos = deepcopy(float_pd_joint_pos)
|
396
|
+
float_pd_joint_delta_pos.use_delta = True
|
397
|
+
float_pd_joint_delta_pos.normalize_action = True
|
398
|
+
float_pd_joint_delta_pos.lower = -0.1
|
399
|
+
float_pd_joint_delta_pos.upper = 0.1
|
400
|
+
|
401
|
+
return dict(
|
402
|
+
pd_joint_pos=dict(
|
403
|
+
root=float_pd_joint_pos,
|
404
|
+
wrist=wrist_joint_pos,
|
405
|
+
fingers=fingers_joint_pos,
|
406
|
+
passive=passive,
|
407
|
+
),
|
408
|
+
pd_joint_delta_pos=dict(
|
409
|
+
root=float_pd_joint_delta_pos,
|
410
|
+
wrist=wrist_joint_delta_pos,
|
411
|
+
fingers=fingers_joint_delta_pos,
|
412
|
+
passive=passive,
|
413
|
+
),
|
414
|
+
)
|
@@ -0,0 +1,23 @@
|
|
1
|
+
# Inspire Hand
|
2
|
+
|
3
|
+
This is the folder for the dexterous Inspire Robotics Hands. It has a CC BY-NC-SA 4.0 license. The URDF is based on the one provided by the Inspire Robotics support team (which is not publicly available at the time of writing).
|
4
|
+
|
5
|
+
Currently the RH56DFX-2L/R with wrist model is supported.
|
6
|
+
|
7
|
+
Changes Made:
|
8
|
+
- Tuned the joint axes/signs to match the real robot.
|
9
|
+
- Tuned the limits of some joints to match the current multipliers and offsets
|
10
|
+
- To support simulation in physx, the 2 underactuated thumb joints have one of their mimic tags modified to depend on the parent joint instead of the grandparent joint.
|
11
|
+
- Added a floating base version of the inspire hand.
|
12
|
+
|
13
|
+
## Notes
|
14
|
+
|
15
|
+
### Current Issues
|
16
|
+
|
17
|
+
There are still some small issues with the provided URDF from Inspire Robotics. They are noted below, to be removed once fixed:
|
18
|
+
- The mimic joint offsets are not tuned, needs system ID.
|
19
|
+
- Some joint limits are not tuned for mimic joints, need system ID. Currently there is some extra space in the limits that should be shrunk once offsets are identified.
|
20
|
+
- Some other joints might move by a little bit (up to 0.001 radian change) when another joint moves. Also likely due to physx issues.
|
21
|
+
### Simulation
|
22
|
+
|
23
|
+
It is unclear why but for the physx backends a damping of 0.001 (or some small value) needed to be set on the mimic joints for them to simulate stably. This is done at the controller level at the moment in ManiSkill.
|