mani-skill-nightly 2025.4.7.816__py3-none-any.whl → 2025.4.9.1837__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/fetch/fetch.py +4 -0
- mani_skill/agents/robots/panda/panda.py +8 -0
- mani_skill/agents/robots/so100/so_100.py +12 -1
- mani_skill/agents/robots/xarm6/xarm6_robotiq.py +8 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Base.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Base_Motor.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Fixed_Jaw.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Fixed_Jaw_Motor.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Lower_Arm.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Lower_Arm_Motor.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Moving_Jaw.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Rotation_Pitch.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Rotation_Pitch_Motor.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Upper_Arm.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Upper_Arm_Motor.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Wrist_Pitch_Roll.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Wrist_Pitch_Roll_Motor.stl +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/{original.urdf → so100.urdf} +136 -50
- mani_skill/envs/tasks/tabletop/pick_cube.py +56 -14
- mani_skill/envs/tasks/tabletop/pick_cube_cfgs.py +59 -0
- mani_skill/examples/demo_random_action.py +2 -0
- mani_skill/trajectory/replay_trajectory.py +1 -1
- mani_skill/utils/scene_builder/table/scene_builder.py +15 -1
- {mani_skill_nightly-2025.4.7.816.dist-info → mani_skill_nightly-2025.4.9.1837.dist-info}/METADATA +1 -1
- {mani_skill_nightly-2025.4.7.816.dist-info → mani_skill_nightly-2025.4.9.1837.dist-info}/RECORD +29 -22
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Base.STL +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Fixed_Jaw.STL +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Lower_Arm.STL +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Moving Jaw.STL +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Rotation_Pitch.STL +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Upper_Arm.STL +0 -0
- mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Wrist_Pitch_Roll.STL +0 -0
- /mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/{original.srdf → so100.srdf} +0 -0
- {mani_skill_nightly-2025.4.7.816.dist-info → mani_skill_nightly-2025.4.9.1837.dist-info}/LICENSE +0 -0
- {mani_skill_nightly-2025.4.7.816.dist-info → mani_skill_nightly-2025.4.9.1837.dist-info}/WHEEL +0 -0
- {mani_skill_nightly-2025.4.7.816.dist-info → mani_skill_nightly-2025.4.9.1837.dist-info}/top_level.txt +0 -0
@@ -416,6 +416,10 @@ class Fetch(BaseAgent):
|
|
416
416
|
T[:3, 3] = center
|
417
417
|
return sapien.Pose(T)
|
418
418
|
|
419
|
+
@property
|
420
|
+
def tcp_pos(self) -> Pose:
|
421
|
+
return (self.finger1_link.pose.p + self.finger2_link.pose.p) / 2
|
422
|
+
|
419
423
|
@property
|
420
424
|
def tcp_pose(self) -> Pose:
|
421
425
|
p = (self.finger1_link.pose.p + self.finger2_link.pose.p) / 2
|
@@ -268,6 +268,14 @@ class Panda(BaseAgent):
|
|
268
268
|
qvel = self.robot.get_qvel()[..., :-2]
|
269
269
|
return torch.max(torch.abs(qvel), 1)[0] <= threshold
|
270
270
|
|
271
|
+
@property
|
272
|
+
def tcp_pos(self):
|
273
|
+
return self.tcp.pose.p
|
274
|
+
|
275
|
+
@property
|
276
|
+
def tcp_pose(self):
|
277
|
+
return self.tcp.pose
|
278
|
+
|
271
279
|
@staticmethod
|
272
280
|
def build_grasp_pose(approaching, closing, center):
|
273
281
|
"""Build a grasp pose (panda_hand_tcp)."""
|
@@ -12,12 +12,13 @@ from mani_skill.agents.controllers import *
|
|
12
12
|
from mani_skill.agents.registration import register_agent
|
13
13
|
from mani_skill.utils import common
|
14
14
|
from mani_skill.utils.structs.actor import Actor
|
15
|
+
from mani_skill.utils.structs.pose import Pose
|
15
16
|
|
16
17
|
|
17
18
|
@register_agent()
|
18
19
|
class SO100(BaseAgent):
|
19
20
|
uid = "so100"
|
20
|
-
urdf_path = f"{PACKAGE_ASSET_DIR}/robots/so100/SO_5DOF_ARM100_8j/
|
21
|
+
urdf_path = f"{PACKAGE_ASSET_DIR}/robots/so100/SO_5DOF_ARM100_8j/so100.urdf"
|
21
22
|
urdf_config = dict(
|
22
23
|
_materials=dict(
|
23
24
|
gripper=dict(static_friction=2, dynamic_friction=2, restitution=0.0)
|
@@ -87,6 +88,10 @@ class SO100(BaseAgent):
|
|
87
88
|
# computes the tool center point as the mid point between the the fixed and moving jaw's tips
|
88
89
|
return (self.finger1_tip.pose.p + self.finger2_tip.pose.p) / 2
|
89
90
|
|
91
|
+
@property
|
92
|
+
def tcp_pose(self):
|
93
|
+
return Pose.create_from_pq(self.tcp_pos, self.finger1_link.pose.q)
|
94
|
+
|
90
95
|
def is_grasping(self, object: Actor, min_force=0.5, max_angle=110):
|
91
96
|
"""Check if the robot is grasping an object
|
92
97
|
|
@@ -116,3 +121,9 @@ class SO100(BaseAgent):
|
|
116
121
|
rforce >= min_force, torch.rad2deg(rangle) <= max_angle
|
117
122
|
)
|
118
123
|
return torch.logical_and(lflag, rflag)
|
124
|
+
|
125
|
+
def is_static(self, threshold=0.2):
|
126
|
+
qvel = self.robot.get_qvel()[
|
127
|
+
:, :-2
|
128
|
+
] # exclude the gripper joint and gripper rotation joint.
|
129
|
+
return torch.max(torch.abs(qvel), 1)[0] <= threshold
|
@@ -407,6 +407,14 @@ class XArm6Robotiq(BaseAgent):
|
|
407
407
|
qvel = self.robot.get_qvel()[..., :-6]
|
408
408
|
return torch.max(torch.abs(qvel), 1)[0] <= threshold
|
409
409
|
|
410
|
+
@property
|
411
|
+
def tcp_pos(self):
|
412
|
+
return self.tcp.pose.p
|
413
|
+
|
414
|
+
@property
|
415
|
+
def tcp_pose(self):
|
416
|
+
return self.tcp.pose
|
417
|
+
|
410
418
|
|
411
419
|
@register_agent(asset_download_ids=["xarm6"])
|
412
420
|
class XArm6RobotiqWristCamera(XArm6Robotiq):
|
Binary file
|
Binary file
|
Binary file
|
Binary file
|
Binary file
|
Binary file
|
Binary file
|
@@ -4,6 +4,12 @@
|
|
4
4
|
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
|
5
5
|
<robot
|
6
6
|
name="SO_5DOF_ARM100_8j_URDF.SLDASM">
|
7
|
+
<material name="white">
|
8
|
+
<color rgba="0.95 0.95 0.95 1" />
|
9
|
+
</material>
|
10
|
+
<material name="motor">
|
11
|
+
<color rgba="0.05 0.05 0.05 1" />
|
12
|
+
</material>
|
7
13
|
<link
|
8
14
|
name="Base">
|
9
15
|
<inertial>
|
@@ -20,18 +26,25 @@
|
|
20
26
|
iyz="2.26514711036514E-05"
|
21
27
|
izz="0.000145097720857224" />
|
22
28
|
</inertial>
|
23
|
-
<visual>
|
29
|
+
<visual name="base_link_chassis">
|
30
|
+
<origin
|
31
|
+
xyz="0 0 0"
|
32
|
+
rpy="0 0 0" />
|
33
|
+
<geometry>
|
34
|
+
<mesh filename="meshes/Base.stl" />
|
35
|
+
</geometry>
|
36
|
+
<material name="white">
|
37
|
+
</material>
|
38
|
+
</visual>
|
39
|
+
<visual name="base_link_motor">
|
24
40
|
<origin
|
25
41
|
xyz="0 0 0"
|
26
42
|
rpy="0 0 0" />
|
27
43
|
<geometry>
|
28
44
|
<mesh
|
29
|
-
filename="meshes/
|
45
|
+
filename="meshes/Base_Motor.stl" />
|
30
46
|
</geometry>
|
31
|
-
<material
|
32
|
-
name="">
|
33
|
-
<color
|
34
|
-
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
47
|
+
<material name="motor">
|
35
48
|
</material>
|
36
49
|
</visual>
|
37
50
|
<collision>
|
@@ -40,7 +53,16 @@
|
|
40
53
|
rpy="0 0 0" />
|
41
54
|
<geometry>
|
42
55
|
<mesh
|
43
|
-
filename="meshes/Base.
|
56
|
+
filename="meshes/Base.stl" />
|
57
|
+
</geometry>
|
58
|
+
</collision>
|
59
|
+
<collision>
|
60
|
+
<origin
|
61
|
+
xyz="0 0 0"
|
62
|
+
rpy="0 0 0" />
|
63
|
+
<geometry>
|
64
|
+
<mesh
|
65
|
+
filename="meshes/Base_Motor.stl" />
|
44
66
|
</geometry>
|
45
67
|
</collision>
|
46
68
|
</link>
|
@@ -60,27 +82,44 @@
|
|
60
82
|
iyz="-4.58026206663885E-06"
|
61
83
|
izz="5.86058514263952E-05" />
|
62
84
|
</inertial>
|
63
|
-
<visual>
|
85
|
+
<visual name="rotation_pitch_chassis">
|
64
86
|
<origin
|
65
87
|
xyz="0 0 0"
|
66
88
|
rpy="0 0 0" />
|
67
89
|
<geometry>
|
68
90
|
<mesh
|
69
|
-
filename="meshes/Rotation_Pitch.
|
91
|
+
filename="meshes/Rotation_Pitch.stl" />
|
70
92
|
</geometry>
|
71
|
-
<material
|
72
|
-
name="">
|
73
|
-
<color
|
74
|
-
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
93
|
+
<material name="white">
|
75
94
|
</material>
|
76
95
|
</visual>
|
96
|
+
<visual name="rotation_pitch_motor">
|
97
|
+
<origin
|
98
|
+
xyz="0 0 0"
|
99
|
+
rpy="0 0 0" />
|
100
|
+
<geometry>
|
101
|
+
<mesh
|
102
|
+
filename="meshes/Rotation_Pitch_Motor.stl" />
|
103
|
+
</geometry>
|
104
|
+
<material name="motor">
|
105
|
+
</material>
|
106
|
+
</visual>
|
107
|
+
<collision>
|
108
|
+
<origin
|
109
|
+
xyz="0 0 0"
|
110
|
+
rpy="0 0 0" />
|
111
|
+
<geometry>
|
112
|
+
<mesh
|
113
|
+
filename="meshes/Rotation_Pitch.stl" />
|
114
|
+
</geometry>
|
115
|
+
</collision>
|
77
116
|
<collision>
|
78
117
|
<origin
|
79
118
|
xyz="0 0 0"
|
80
119
|
rpy="0 0 0" />
|
81
120
|
<geometry>
|
82
121
|
<mesh
|
83
|
-
filename="meshes/
|
122
|
+
filename="meshes/Rotation_Pitch_Motor.stl" />
|
84
123
|
</geometry>
|
85
124
|
</collision>
|
86
125
|
</link>
|
@@ -119,18 +158,26 @@
|
|
119
158
|
iyz="2.11884806298698E-06"
|
120
159
|
izz="0.000213280241160769" />
|
121
160
|
</inertial>
|
122
|
-
<visual>
|
161
|
+
<visual name="upper_arm_chassis">
|
123
162
|
<origin
|
124
163
|
xyz="0 0 0"
|
125
164
|
rpy="0 0 0" />
|
126
165
|
<geometry>
|
127
166
|
<mesh
|
128
|
-
filename="meshes/Upper_Arm.
|
167
|
+
filename="meshes/Upper_Arm.stl" />
|
129
168
|
</geometry>
|
130
|
-
<material
|
131
|
-
|
132
|
-
|
133
|
-
|
169
|
+
<material name="white">
|
170
|
+
</material>
|
171
|
+
</visual>
|
172
|
+
<visual name="upper_arm_motor">
|
173
|
+
<origin
|
174
|
+
xyz="0 0 0"
|
175
|
+
rpy="0 0 0" />
|
176
|
+
<geometry>
|
177
|
+
<mesh
|
178
|
+
filename="meshes/Upper_Arm_Motor.stl" />
|
179
|
+
</geometry>
|
180
|
+
<material name="motor">
|
134
181
|
</material>
|
135
182
|
</visual>
|
136
183
|
<collision>
|
@@ -139,7 +186,16 @@
|
|
139
186
|
rpy="0 0 0" />
|
140
187
|
<geometry>
|
141
188
|
<mesh
|
142
|
-
filename="meshes/Upper_Arm.
|
189
|
+
filename="meshes/Upper_Arm.stl" />
|
190
|
+
</geometry>
|
191
|
+
</collision>
|
192
|
+
<collision>
|
193
|
+
<origin
|
194
|
+
xyz="0 0 0"
|
195
|
+
rpy="0 0 0" />
|
196
|
+
<geometry>
|
197
|
+
<mesh
|
198
|
+
filename="meshes/Upper_Arm_Motor.stl" />
|
143
199
|
</geometry>
|
144
200
|
</collision>
|
145
201
|
</link>
|
@@ -177,18 +233,26 @@
|
|
177
233
|
iyz="1.77429964684103E-06"
|
178
234
|
izz="5.08741652515214E-05" />
|
179
235
|
</inertial>
|
180
|
-
<visual>
|
236
|
+
<visual name="lower_arm_chassis">
|
237
|
+
<origin
|
238
|
+
xyz="0 0 0"
|
239
|
+
rpy="0 0 0" />
|
240
|
+
<geometry>
|
241
|
+
<mesh
|
242
|
+
filename="meshes/Lower_Arm.stl" />
|
243
|
+
</geometry>
|
244
|
+
<material name="white">
|
245
|
+
</material>
|
246
|
+
</visual>
|
247
|
+
<visual name="lower_arm_motor">
|
181
248
|
<origin
|
182
249
|
xyz="0 0 0"
|
183
250
|
rpy="0 0 0" />
|
184
251
|
<geometry>
|
185
252
|
<mesh
|
186
|
-
filename="meshes/
|
253
|
+
filename="meshes/Lower_Arm_Motor.stl" />
|
187
254
|
</geometry>
|
188
|
-
<material
|
189
|
-
name="">
|
190
|
-
<color
|
191
|
-
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
255
|
+
<material name="motor">
|
192
256
|
</material>
|
193
257
|
</visual>
|
194
258
|
<collision>
|
@@ -197,7 +261,16 @@
|
|
197
261
|
rpy="0 0 0" />
|
198
262
|
<geometry>
|
199
263
|
<mesh
|
200
|
-
filename="meshes/Lower_Arm.
|
264
|
+
filename="meshes/Lower_Arm.stl" />
|
265
|
+
</geometry>
|
266
|
+
</collision>
|
267
|
+
<collision>
|
268
|
+
<origin
|
269
|
+
xyz="0 0 0"
|
270
|
+
rpy="0 0 0" />
|
271
|
+
<geometry>
|
272
|
+
<mesh
|
273
|
+
filename="meshes/Lower_Arm_Motor.stl" />
|
201
274
|
</geometry>
|
202
275
|
</collision>
|
203
276
|
</link>
|
@@ -235,18 +308,26 @@
|
|
235
308
|
iyz="4.09549055863776E-08"
|
236
309
|
izz="3.4540143384536E-05" />
|
237
310
|
</inertial>
|
238
|
-
<visual>
|
311
|
+
<visual name="wrist_pitch_roll_chassis">
|
312
|
+
<origin
|
313
|
+
xyz="0 0 0"
|
314
|
+
rpy="0 0 0" />
|
315
|
+
<geometry>
|
316
|
+
<mesh
|
317
|
+
filename="meshes/Wrist_Pitch_Roll.stl" />
|
318
|
+
</geometry>
|
319
|
+
<material name="white">
|
320
|
+
</material>
|
321
|
+
</visual>
|
322
|
+
<visual name="wrist_pitch_roll_motor">
|
239
323
|
<origin
|
240
324
|
xyz="0 0 0"
|
241
325
|
rpy="0 0 0" />
|
242
326
|
<geometry>
|
243
327
|
<mesh
|
244
|
-
filename="meshes/
|
328
|
+
filename="meshes/Wrist_Pitch_Roll_Motor.stl" />
|
245
329
|
</geometry>
|
246
|
-
<material
|
247
|
-
name="">
|
248
|
-
<color
|
249
|
-
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
330
|
+
<material name="motor">
|
250
331
|
</material>
|
251
332
|
</visual>
|
252
333
|
<collision>
|
@@ -255,7 +336,16 @@
|
|
255
336
|
rpy="0 0 0" />
|
256
337
|
<geometry>
|
257
338
|
<mesh
|
258
|
-
filename="meshes/Wrist_Pitch_Roll.
|
339
|
+
filename="meshes/Wrist_Pitch_Roll.stl" />
|
340
|
+
</geometry>
|
341
|
+
</collision>
|
342
|
+
<collision>
|
343
|
+
<origin
|
344
|
+
xyz="0 0 0"
|
345
|
+
rpy="0 0 0" />
|
346
|
+
<geometry>
|
347
|
+
<mesh
|
348
|
+
filename="meshes/Wrist_Pitch_Roll_Motor.stl" />
|
259
349
|
</geometry>
|
260
350
|
</collision>
|
261
351
|
</link>
|
@@ -293,29 +383,28 @@
|
|
293
383
|
iyz="-1.58743247545413E-07"
|
294
384
|
izz="5.02460913506734E-05" />
|
295
385
|
</inertial>
|
296
|
-
<visual>
|
386
|
+
<visual name="fixed_jaw_chassis">
|
297
387
|
<origin
|
298
388
|
xyz="0 0 0"
|
299
389
|
rpy="0 0 0" />
|
300
390
|
<geometry>
|
301
391
|
<mesh
|
302
|
-
filename="meshes/Fixed_Jaw.
|
392
|
+
filename="meshes/Fixed_Jaw.stl" />
|
303
393
|
</geometry>
|
304
|
-
<material
|
305
|
-
name="">
|
306
|
-
<color
|
307
|
-
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
394
|
+
<material name="white">
|
308
395
|
</material>
|
309
396
|
</visual>
|
310
|
-
|
397
|
+
<visual name="fixed_jaw_motor">
|
311
398
|
<origin
|
312
399
|
xyz="0 0 0"
|
313
400
|
rpy="0 0 0" />
|
314
401
|
<geometry>
|
315
402
|
<mesh
|
316
|
-
filename="meshes/
|
403
|
+
filename="meshes/Fixed_Jaw_Motor.stl" />
|
317
404
|
</geometry>
|
318
|
-
|
405
|
+
<material name="motor">
|
406
|
+
</material>
|
407
|
+
</visual>
|
319
408
|
<collision>
|
320
409
|
<origin
|
321
410
|
xyz="0 0 0"
|
@@ -369,18 +458,15 @@
|
|
369
458
|
iyz="-1.71146075110632E-07"
|
370
459
|
izz="8.9916083370498E-06" />
|
371
460
|
</inertial>
|
372
|
-
<visual>
|
461
|
+
<visual name="moving_jaw_chassis">
|
373
462
|
<origin
|
374
463
|
xyz="0 0 0"
|
375
464
|
rpy="0 0 0" />
|
376
465
|
<geometry>
|
377
466
|
<mesh
|
378
|
-
filename="meshes/
|
467
|
+
filename="meshes/Moving_Jaw.stl" />
|
379
468
|
</geometry>
|
380
|
-
<material
|
381
|
-
name="">
|
382
|
-
<color
|
383
|
-
rgba="0.792156862745098 0.819607843137255 0.933333333333333 1" />
|
469
|
+
<material name="white">
|
384
470
|
</material>
|
385
471
|
</visual>
|
386
472
|
<collision>
|
@@ -5,8 +5,9 @@ import sapien
|
|
5
5
|
import torch
|
6
6
|
|
7
7
|
import mani_skill.envs.utils.randomization as randomization
|
8
|
-
from mani_skill.agents.robots import Fetch, Panda, XArm6Robotiq
|
8
|
+
from mani_skill.agents.robots import SO100, Fetch, Panda, XArm6Robotiq
|
9
9
|
from mani_skill.envs.sapien_env import BaseEnv
|
10
|
+
from mani_skill.envs.tasks.tabletop.pick_cube_cfgs import PICK_CUBE_CONFIGS
|
10
11
|
from mani_skill.sensors.camera import CameraConfig
|
11
12
|
from mani_skill.utils import sapien_utils
|
12
13
|
from mani_skill.utils.building import actors
|
@@ -19,7 +20,8 @@ from mani_skill.utils.structs.pose import Pose
|
|
19
20
|
class PickCubeEnv(BaseEnv):
|
20
21
|
"""
|
21
22
|
**Task Description:**
|
22
|
-
A simple task where the objective is to grasp a red cube and move it to a target goal position.
|
23
|
+
A simple task where the objective is to grasp a red cube and move it to a target goal position. This is also the *baseline* task to test whether a robot with manipulation
|
24
|
+
capabilities can be simulated and trained properly. Hence there is extra code for some robots to set them up properly in this environment as well as the table scene builder.
|
23
25
|
|
24
26
|
**Randomizations:**
|
25
27
|
- the cube's xy position is randomized on top of a table in the region [0.1, 0.1] x [-0.1, -0.1]. It is placed flat on the table
|
@@ -36,23 +38,43 @@ class PickCubeEnv(BaseEnv):
|
|
36
38
|
"panda",
|
37
39
|
"fetch",
|
38
40
|
"xarm6_robotiq",
|
41
|
+
"so100",
|
39
42
|
]
|
40
|
-
agent: Union[Panda, Fetch, XArm6Robotiq]
|
43
|
+
agent: Union[Panda, Fetch, XArm6Robotiq, SO100]
|
41
44
|
cube_half_size = 0.02
|
42
45
|
goal_thresh = 0.025
|
46
|
+
cube_spawn_half_size = 0.05
|
47
|
+
cube_spawn_center = (0, 0)
|
43
48
|
|
44
49
|
def __init__(self, *args, robot_uids="panda", robot_init_qpos_noise=0.02, **kwargs):
|
45
50
|
self.robot_init_qpos_noise = robot_init_qpos_noise
|
51
|
+
if robot_uids in PICK_CUBE_CONFIGS:
|
52
|
+
cfg = PICK_CUBE_CONFIGS[robot_uids]
|
53
|
+
else:
|
54
|
+
cfg = PICK_CUBE_CONFIGS["panda"]
|
55
|
+
self.cube_half_size = cfg["cube_half_size"]
|
56
|
+
self.goal_thresh = cfg["goal_thresh"]
|
57
|
+
self.cube_spawn_half_size = cfg["cube_spawn_half_size"]
|
58
|
+
self.cube_spawn_center = cfg["cube_spawn_center"]
|
59
|
+
self.max_goal_height = cfg["max_goal_height"]
|
60
|
+
self.sensor_cam_eye_pos = cfg["sensor_cam_eye_pos"]
|
61
|
+
self.sensor_cam_target_pos = cfg["sensor_cam_target_pos"]
|
62
|
+
self.human_cam_eye_pos = cfg["human_cam_eye_pos"]
|
63
|
+
self.human_cam_target_pos = cfg["human_cam_target_pos"]
|
46
64
|
super().__init__(*args, robot_uids=robot_uids, **kwargs)
|
47
65
|
|
48
66
|
@property
|
49
67
|
def _default_sensor_configs(self):
|
50
|
-
pose = sapien_utils.look_at(
|
68
|
+
pose = sapien_utils.look_at(
|
69
|
+
eye=self.sensor_cam_eye_pos, target=self.sensor_cam_target_pos
|
70
|
+
)
|
51
71
|
return [CameraConfig("base_camera", pose, 128, 128, np.pi / 2, 0.01, 100)]
|
52
72
|
|
53
73
|
@property
|
54
74
|
def _default_human_render_camera_configs(self):
|
55
|
-
pose = sapien_utils.look_at(
|
75
|
+
pose = sapien_utils.look_at(
|
76
|
+
eye=self.human_cam_eye_pos, target=self.human_cam_target_pos
|
77
|
+
)
|
56
78
|
return CameraConfig("render_camera", pose, 512, 512, 1, 0.01, 100)
|
57
79
|
|
58
80
|
def _load_agent(self, options: dict):
|
@@ -86,27 +108,38 @@ class PickCubeEnv(BaseEnv):
|
|
86
108
|
b = len(env_idx)
|
87
109
|
self.table_scene.initialize(env_idx)
|
88
110
|
xyz = torch.zeros((b, 3))
|
89
|
-
xyz[:, :2] =
|
111
|
+
xyz[:, :2] = (
|
112
|
+
torch.rand((b, 2)) * self.cube_spawn_half_size * 2
|
113
|
+
- self.cube_spawn_half_size
|
114
|
+
)
|
115
|
+
xyz[:, 0] += self.cube_spawn_center[0]
|
116
|
+
xyz[:, 1] += self.cube_spawn_center[1]
|
117
|
+
|
90
118
|
xyz[:, 2] = self.cube_half_size
|
91
119
|
qs = randomization.random_quaternions(b, lock_x=True, lock_y=True)
|
92
120
|
self.cube.set_pose(Pose.create_from_pq(xyz, qs))
|
93
121
|
|
94
122
|
goal_xyz = torch.zeros((b, 3))
|
95
|
-
goal_xyz[:, :2] =
|
96
|
-
|
123
|
+
goal_xyz[:, :2] = (
|
124
|
+
torch.rand((b, 2)) * self.cube_spawn_half_size * 2
|
125
|
+
- self.cube_spawn_half_size
|
126
|
+
)
|
127
|
+
goal_xyz[:, 0] += self.cube_spawn_center[0]
|
128
|
+
goal_xyz[:, 1] += self.cube_spawn_center[1]
|
129
|
+
goal_xyz[:, 2] = torch.rand((b)) * self.max_goal_height + xyz[:, 2]
|
97
130
|
self.goal_site.set_pose(Pose.create_from_pq(goal_xyz))
|
98
131
|
|
99
132
|
def _get_obs_extra(self, info: Dict):
|
100
133
|
# in reality some people hack is_grasped into observations by checking if the gripper can close fully or not
|
101
134
|
obs = dict(
|
102
135
|
is_grasped=info["is_grasped"],
|
103
|
-
tcp_pose=self.agent.
|
136
|
+
tcp_pose=self.agent.tcp_pose.raw_pose,
|
104
137
|
goal_pos=self.goal_site.pose.p,
|
105
138
|
)
|
106
139
|
if "state" in self.obs_mode:
|
107
140
|
obs.update(
|
108
141
|
obj_pose=self.cube.pose.raw_pose,
|
109
|
-
tcp_to_obj_pos=self.cube.pose.p - self.agent.
|
142
|
+
tcp_to_obj_pos=self.cube.pose.p - self.agent.tcp_pose.p,
|
110
143
|
obj_to_goal_pos=self.goal_site.pose.p - self.cube.pose.p,
|
111
144
|
)
|
112
145
|
return obs
|
@@ -127,7 +160,7 @@ class PickCubeEnv(BaseEnv):
|
|
127
160
|
|
128
161
|
def compute_dense_reward(self, obs: Any, action: torch.Tensor, info: Dict):
|
129
162
|
tcp_to_obj_dist = torch.linalg.norm(
|
130
|
-
self.cube.pose.p - self.agent.
|
163
|
+
self.cube.pose.p - self.agent.tcp_pose.p, axis=1
|
131
164
|
)
|
132
165
|
reaching_reward = 1 - torch.tanh(5 * tcp_to_obj_dist)
|
133
166
|
reward = reaching_reward
|
@@ -144,9 +177,9 @@ class PickCubeEnv(BaseEnv):
|
|
144
177
|
qvel = self.agent.robot.get_qvel()
|
145
178
|
if self.robot_uids == "panda":
|
146
179
|
qvel = qvel[..., :-2]
|
147
|
-
|
148
|
-
|
149
|
-
)
|
180
|
+
elif self.robot_uids == "so100":
|
181
|
+
qvel = qvel[..., :-1]
|
182
|
+
static_reward = 1 - torch.tanh(5 * torch.linalg.norm(qvel, axis=1))
|
150
183
|
reward += static_reward * info["is_obj_placed"]
|
151
184
|
|
152
185
|
reward[info["success"]] = 5
|
@@ -156,3 +189,12 @@ class PickCubeEnv(BaseEnv):
|
|
156
189
|
self, obs: Any, action: torch.Tensor, info: Dict
|
157
190
|
):
|
158
191
|
return self.compute_dense_reward(obs=obs, action=action, info=info) / 5
|
192
|
+
|
193
|
+
|
194
|
+
@register_env("PickCubeSO100-v1", max_episode_steps=50)
|
195
|
+
class PickCubeSO100Env(PickCubeEnv):
|
196
|
+
|
197
|
+
_sample_video_link = "https://github.com/haosulab/ManiSkill/raw/main/figures/environment_demos/PickCubeSO100-v1_rt.mp4"
|
198
|
+
|
199
|
+
def __init__(self, *args, **kwargs):
|
200
|
+
super().__init__(*args, robot_uids="so100", **kwargs)
|
@@ -0,0 +1,59 @@
|
|
1
|
+
"""
|
2
|
+
PickCube-v1 is a basic/common task which defaults to using the panda robot. It is also used as a testing task to check whether a robot with manipulation
|
3
|
+
capabilities can be simulated and trained properly. The configs below set the pick cube task differently to ensure the cube is within reach of the robot tested
|
4
|
+
and the camera angles are reasonable.
|
5
|
+
"""
|
6
|
+
PICK_CUBE_CONFIGS = {
|
7
|
+
"panda": {
|
8
|
+
"cube_half_size": 0.02,
|
9
|
+
"goal_thresh": 0.025,
|
10
|
+
"cube_spawn_half_size": 0.1,
|
11
|
+
"cube_spawn_center": (0, 0),
|
12
|
+
"max_goal_height": 0.3,
|
13
|
+
"sensor_cam_eye_pos": [
|
14
|
+
0.3,
|
15
|
+
0,
|
16
|
+
0.6,
|
17
|
+
], # sensor cam is the camera used for visual observation generation
|
18
|
+
"sensor_cam_target_pos": [-0.1, 0, 0.1],
|
19
|
+
"human_cam_eye_pos": [
|
20
|
+
0.6,
|
21
|
+
0.7,
|
22
|
+
0.6,
|
23
|
+
], # human cam is the camera used for human rendering (i.e. eval videos)
|
24
|
+
"human_cam_target_pos": [0.0, 0.0, 0.35],
|
25
|
+
},
|
26
|
+
"fetch": {
|
27
|
+
"cube_half_size": 0.02,
|
28
|
+
"goal_thresh": 0.025,
|
29
|
+
"cube_spawn_half_size": 0.1,
|
30
|
+
"cube_spawn_center": (0, 0),
|
31
|
+
"max_goal_height": 0.3,
|
32
|
+
"sensor_cam_eye_pos": [0.3, 0, 0.6],
|
33
|
+
"sensor_cam_target_pos": [-0.1, 0, 0.1],
|
34
|
+
"human_cam_eye_pos": [0.6, 0.7, 0.6],
|
35
|
+
"human_cam_target_pos": [0.0, 0.0, 0.35],
|
36
|
+
},
|
37
|
+
"xarm6_robotiq": {
|
38
|
+
"cube_half_size": 0.02,
|
39
|
+
"goal_thresh": 0.025,
|
40
|
+
"cube_spawn_half_size": 0.1,
|
41
|
+
"cube_spawn_center": (0, 0),
|
42
|
+
"max_goal_height": 0.3,
|
43
|
+
"sensor_cam_eye_pos": [0.3, 0, 0.6],
|
44
|
+
"sensor_cam_target_pos": [-0.1, 0, 0.1],
|
45
|
+
"human_cam_eye_pos": [0.6, 0.7, 0.6],
|
46
|
+
"human_cam_target_pos": [0.0, 0.0, 0.35],
|
47
|
+
},
|
48
|
+
"so100": {
|
49
|
+
"cube_half_size": 0.0125,
|
50
|
+
"goal_thresh": 0.0125 * 1.25,
|
51
|
+
"cube_spawn_half_size": 0.05,
|
52
|
+
"cube_spawn_center": (-0.46, 0),
|
53
|
+
"max_goal_height": 0.08,
|
54
|
+
"sensor_cam_eye_pos": [-0.27, 0, 0.4],
|
55
|
+
"sensor_cam_target_pos": [-0.56, 0, -0.25],
|
56
|
+
"human_cam_eye_pos": [-0.1, 0.3, 0.4],
|
57
|
+
"human_cam_target_pos": [-0.46, 0.0, 0.1],
|
58
|
+
},
|
59
|
+
}
|
@@ -80,6 +80,8 @@ def main(args: Args):
|
|
80
80
|
)
|
81
81
|
if args.robot_uids is not None:
|
82
82
|
env_kwargs["robot_uids"] = tuple(args.robot_uids.split(","))
|
83
|
+
if len(env_kwargs["robot_uids"]) == 1:
|
84
|
+
env_kwargs["robot_uids"] = env_kwargs["robot_uids"][0]
|
83
85
|
env: BaseEnv = gym.make(
|
84
86
|
args.env_id,
|
85
87
|
**env_kwargs
|
@@ -542,8 +542,8 @@ def main(args: Args):
|
|
542
542
|
and ("num_envs" not in env_kwargs or env_kwargs["num_envs"] == 1)
|
543
543
|
):
|
544
544
|
env_kwargs["sim_backend"] = "physx_cpu"
|
545
|
+
env_kwargs["num_envs"] = args.num_envs
|
545
546
|
if env_kwargs["sim_backend"] not in CPU_SIM_BACKENDS:
|
546
|
-
env_kwargs["num_envs"] = args.num_envs
|
547
547
|
record_episode_kwargs["max_steps_per_video"] = env_info["max_episode_steps"]
|
548
548
|
_, replay_result = _main(
|
549
549
|
args,
|
@@ -14,8 +14,10 @@ from mani_skill.utils.building.ground import build_ground
|
|
14
14
|
from mani_skill.utils.scene_builder import SceneBuilder
|
15
15
|
|
16
16
|
|
17
|
-
# TODO (stao): make the build and initialize api consistent with other scenes
|
18
17
|
class TableSceneBuilder(SceneBuilder):
|
18
|
+
"""A simple scene builder that adds a table to the scene such that the height of the table is at 0, and
|
19
|
+
gives reasonable initial poses for robots."""
|
20
|
+
|
19
21
|
def build(self):
|
20
22
|
builder = self.scene.create_actor_builder()
|
21
23
|
model_dir = Path(osp.dirname(__file__)) / "assets"
|
@@ -268,3 +270,15 @@ class TableSceneBuilder(SceneBuilder):
|
|
268
270
|
)
|
269
271
|
self.env.agent.reset(qpos)
|
270
272
|
self.env.agent.robot.set_pose(sapien.Pose([-0.615, 0, 0]))
|
273
|
+
elif self.env.robot_uids == "so100":
|
274
|
+
qpos = np.array([0, np.pi / 2, np.pi / 2, np.pi / 2, -np.pi / 2, 1.0])
|
275
|
+
qpos = (
|
276
|
+
self.env._episode_rng.normal(
|
277
|
+
0, self.robot_init_qpos_noise, (b, len(qpos))
|
278
|
+
)
|
279
|
+
+ qpos
|
280
|
+
)
|
281
|
+
self.env.agent.reset(qpos)
|
282
|
+
self.env.agent.robot.set_pose(
|
283
|
+
sapien.Pose([-0.725, 0, 0], q=euler2quat(0, 0, np.pi / 2))
|
284
|
+
)
|
{mani_skill_nightly-2025.4.7.816.dist-info → mani_skill_nightly-2025.4.9.1837.dist-info}/RECORD
RENAMED
@@ -24,7 +24,7 @@ mani_skill/agents/robots/anymal/anymal_c.py,sha256=p7DuLDI7yx2_C1Eg2VXpNTAKCQrEP
|
|
24
24
|
mani_skill/agents/robots/dclaw/__init__.py,sha256=t1VSGN3WYw9f3mR7_M08-VhCBQPWOi7vKz7Rz3T8KJQ,25
|
25
25
|
mani_skill/agents/robots/dclaw/dclaw.py,sha256=G5DqqRl2R8NroNyTaStdofEFW23wWqla2qy6mqkVOG8,4082
|
26
26
|
mani_skill/agents/robots/fetch/__init__.py,sha256=q3QA2oGTx-LgdmCbpe3wpj1ifoqhhFDdrMMXC43Nsuc,79
|
27
|
-
mani_skill/agents/robots/fetch/fetch.py,sha256=
|
27
|
+
mani_skill/agents/robots/fetch/fetch.py,sha256=dfyGocH4RKojvvhipkwtoIeBIoS93xyBzblNJNFIDlU,15231
|
28
28
|
mani_skill/agents/robots/floating_inspire_hand/__init__.py,sha256=JmV3QkvW1w8l_NUDdX1aFa55E7WXxnhukD-JLM99bGk,60
|
29
29
|
mani_skill/agents/robots/floating_inspire_hand/floating_inspire_hand.py,sha256=JKPeE04oMQKo1lAZ48fDvZ6669XQc6s1PKftNVme8vk,7017
|
30
30
|
mani_skill/agents/robots/floating_panda_gripper/__init__.py,sha256=AwV0Sml7DmQb6hk4FqbxHdO7_XXHHMhrOZtZRk6d-Po,57
|
@@ -39,11 +39,11 @@ mani_skill/agents/robots/koch/__init__.py,sha256=-bZbNQnXk6rlXgSkIG2umLENJkNqAQb
|
|
39
39
|
mani_skill/agents/robots/koch/koch.py,sha256=r5morOu6Fv35qpSm2OFhhO2Aaw2x9ZtT3wrET-YtiCw,6736
|
40
40
|
mani_skill/agents/robots/koch/koch_real.py,sha256=w8lIzRsAZEvLGXbC598ktpGiHKuPp3XDspmU1xYXKqc,124
|
41
41
|
mani_skill/agents/robots/panda/__init__.py,sha256=VnFJLcmPMBjo-mlBpfMo5acYKud_wngRAcf67uiugSk,102
|
42
|
-
mani_skill/agents/robots/panda/panda.py,sha256=
|
42
|
+
mani_skill/agents/robots/panda/panda.py,sha256=aufC9et7TK5Ojms03ITT3cb7jsVClcbqLquGWaXzEH4,10760
|
43
43
|
mani_skill/agents/robots/panda/panda_stick.py,sha256=ylYvjcgazMfp2k-RPbxkFByH9qyTLD8beDp2ra_WWso,5659
|
44
44
|
mani_skill/agents/robots/panda/panda_wristcam.py,sha256=eSw652CaA82YfetCqasHGAcUkaJ_aXJijJm6tHZmKyQ,875
|
45
45
|
mani_skill/agents/robots/so100/__init__.py,sha256=54RRpI3ue89zbNtSKOK8JxvSaKrHt6PXQrriTN6X01c,26
|
46
|
-
mani_skill/agents/robots/so100/so_100.py,sha256=
|
46
|
+
mani_skill/agents/robots/so100/so_100.py,sha256=UYLjB40n6lfXZnBRTBA2apjfp0MkKqsXf5aVXm5NyiI,4838
|
47
47
|
mani_skill/agents/robots/so100/so_100_real.py,sha256=-M1iRAe81AQgnM8XE32Q2jsFBmE87MGXgQwA138BVis,125
|
48
48
|
mani_skill/agents/robots/stompy/__init__.py,sha256=fNuqeJqKneHPnzvjDYtzbpV3MIGGll8-CMok89hf0zo,27
|
49
49
|
mani_skill/agents/robots/stompy/stompy.py,sha256=doBI0c4QCbjCiaHAxdngI73Ux_ISBy6N5JTgPovrX34,4052
|
@@ -65,7 +65,7 @@ mani_skill/agents/robots/xarm/__init__.py,sha256=6Mhn4vV4f9XxcK493U5W9VE6yGGgydP
|
|
65
65
|
mani_skill/agents/robots/xarm/xarm7_ability.py,sha256=yj7CUBQpbGVUiT22qweJKTniJE0DxdEyyKj329vr0HY,6106
|
66
66
|
mani_skill/agents/robots/xarm6/__init__.py,sha256=0r19OsKmm1ssKB5Rrie8syWQvpXNooVOv6m-iygrdM0,109
|
67
67
|
mani_skill/agents/robots/xarm6/xarm6_nogripper.py,sha256=FPhOpWQw5RPsSHLhZ9JWjYeh25GboO4I5_Hn05Ub84Q,7379
|
68
|
-
mani_skill/agents/robots/xarm6/xarm6_robotiq.py,sha256=
|
68
|
+
mani_skill/agents/robots/xarm6/xarm6_robotiq.py,sha256=FIc_BvV7x5Fs9GsE5-m88NaSjPitnDYIGU2ZJbqE-m4,15651
|
69
69
|
mani_skill/assets/maniskill2-scene-2.glb,sha256=C5om9o9r6B-fWoauzNfUm2WV5sh8Nf7AvZRlYo1-IXQ,4737204
|
70
70
|
mani_skill/assets/deformable_manipulation/beaker.glb,sha256=MMaoH6OruVSzO8CKuK2AMyaxA5kjsbbDQXyTVycWsPI,18104
|
71
71
|
mani_skill/assets/deformable_manipulation/bottle.glb,sha256=AHWoATBEBeesfbiYNfSB0O0PWhsH0oa2wUBv79w9AVA,36476
|
@@ -406,20 +406,26 @@ mani_skill/assets/robots/panda/sciurus17_description/meshes/visual/Base.stl,sha2
|
|
406
406
|
mani_skill/assets/robots/panda/sciurus17_description/meshes/visual/Body.stl,sha256=uzaYY9covWVKTHaflatAHHWghs-zRe52DnGhyZUe-9I,6158284
|
407
407
|
mani_skill/assets/robots/so100/LICENSE,sha256=QwcOLU5TJoTeUhuIXzhdCEEDDvorGiC6-3YTOl4TecE,11356
|
408
408
|
mani_skill/assets/robots/so100/README.md,sha256=NhEpAetOHh3fsU5LQBlE0w09TajOwCIfk7ArvyGddgU,495
|
409
|
-
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/
|
410
|
-
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/
|
411
|
-
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Base.
|
412
|
-
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/
|
409
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/so100.srdf,sha256=ntCI29IbObhjSczU0arh8E5FeAlwWLnCqEFB5gWfmfw,474
|
410
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/so100.urdf,sha256=6431c-upH-sM2gwoaFIzf3eMw7HngJv2iTpSzjsQnn0,13478
|
411
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Base.stl,sha256=u4r7AwPAEl8mWnl2Jc-vZGrCFNXS3JyYY0jEFXVeKnQ,443484
|
412
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Base_Motor.stl,sha256=qsRIXUSOykGNKpPfP3j0Sb1Zsh7BrypXkXGBn9ROpXY,154284
|
413
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Fixed_Jaw.stl,sha256=VSiGcHMDPqpMJ6gIcYCVTz8GNb1p1RfVys6S8B3SZrI,264584
|
414
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Fixed_Jaw_Motor.stl,sha256=AyG_uQLVoRnE8qk0q0vn6eqMk6AuFoXwZvmcJKXKPs8,151884
|
413
415
|
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Fixed_Jaw_part1.ply,sha256=LKjUCMOjZbrCYugtqs1sne30DpDBryjEhkjfv2NvUTA,628
|
414
416
|
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Fixed_Jaw_part2.ply,sha256=t58_KuU4NRPqVZ0ESd7dFSgaaNTvv6OHHqAk0xALrpE,879
|
415
|
-
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Lower_Arm.
|
416
|
-
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/
|
417
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Lower_Arm.stl,sha256=oEURvGXLtwKy1gI3ZN6UeIiwagn78nKAPznCJyQymj4,347184
|
418
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Lower_Arm_Motor.stl,sha256=BzaPpMUN6nDoFXrM7nEHISDAyzdPZyyFq6HQgXArxHY,151884
|
419
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Moving_Jaw.stl,sha256=bZySMCTHXm8KjYMAMXxNihfdSYgCYMvGC3_l4Mba36g,177184
|
417
420
|
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Moving_Jaw_part1.ply,sha256=0ixh1WOz04a2Ao6eEkePFDo42FnKKZOhHVK2f1iDFgI,628
|
418
421
|
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Moving_Jaw_part2.ply,sha256=XkBI9LBCrkne4D0lepfKY5HIuuG9BMe-mCuTfJn0Lxg,582
|
419
422
|
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Moving_Jaw_part3.ply,sha256=JLF3MhwnfjBw4DV7FhG_DXx39oTQm-YV5fd1jxZUqvk,701
|
420
|
-
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Rotation_Pitch.
|
421
|
-
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/
|
422
|
-
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/
|
423
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Rotation_Pitch.stl,sha256=ShR29X0o0sBlvA7eamdMs-us8RkzcpFu8eD_Mu65LPA,347584
|
424
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Rotation_Pitch_Motor.stl,sha256=9PvPGNjy6R0Sp2fBZ5QwFA3ODIHqFHjMFTv846Fi22E,154284
|
425
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Upper_Arm.stl,sha256=2XrTfJBAD-ObstWs6LQpDz0SYuE_HU8WZJRCF1LV87c,215184
|
426
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Upper_Arm_Motor.stl,sha256=uv2yy56aiE5itfvxWx9wamV3HagnZNvnA98SjZ801yM,152284
|
427
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Wrist_Pitch_Roll.stl,sha256=WOg84ciyTh-jp5Zy6pZepBQ5hsgaIThtzW2hy8_clLs,341684
|
428
|
+
mani_skill/assets/robots/so100/SO_5DOF_ARM100_8j/meshes/Wrist_Pitch_Roll_Motor.stl,sha256=iaw_sdJTb6T3xA50Sb5Lk019d2-c0EU8hCdn-YD_bBg,133684
|
423
429
|
mani_skill/assets/robots/trifinger/cube_multicolor_rrc.urdf,sha256=cJ1b7QsYy1aZpAVI-bGkL5xPyzQHToRwcwVZJLTGCuY,451
|
424
430
|
mani_skill/assets/robots/trifinger/high_table_boundary.urdf,sha256=KalDpF19dXuNua26RHGkTycz1S-DV57T-9T7NTlgOCE,1343
|
425
431
|
mani_skill/assets/robots/trifinger/table_without_border.urdf,sha256=P2y3watglInvmtgPideXQET8_KlTVzjeg9XlEW_O7lY,1545
|
@@ -574,7 +580,8 @@ mani_skill/envs/tasks/tabletop/assembling_kits.py,sha256=piXxTybVKrRr92VqIFIQsbr
|
|
574
580
|
mani_skill/envs/tasks/tabletop/lift_peg_upright.py,sha256=o6AmHyjyoT5U6IYn0tXz3MJ7PNCEqHPZf2jnFOFuW-Y,5857
|
575
581
|
mani_skill/envs/tasks/tabletop/peg_insertion_side.py,sha256=3tf9eOI4PmNGKXooZUR81AXUPuUUTgG-V4DuYxtd5dg,14033
|
576
582
|
mani_skill/envs/tasks/tabletop/pick_clutter_ycb.py,sha256=uA-kMGMAODeNvL99K1kDBrtU7b7VEkbkzUip5dJzucM,7345
|
577
|
-
mani_skill/envs/tasks/tabletop/pick_cube.py,sha256=
|
583
|
+
mani_skill/envs/tasks/tabletop/pick_cube.py,sha256=dQC3smYUttMLJHXAFMO31vFZKzQ4NFrrZ7-AdG4vfXI,8102
|
584
|
+
mani_skill/envs/tasks/tabletop/pick_cube_cfgs.py,sha256=Zz_F3QI_sSqKNDsngp1mzPgkiyewVu47N2iHz522uOg,2166
|
578
585
|
mani_skill/envs/tasks/tabletop/pick_single_ycb.py,sha256=mrqEoOa9UVF34Z5fpsvjcr683diUffsKEjJ9Zh0qfFU,10409
|
579
586
|
mani_skill/envs/tasks/tabletop/place_sphere.py,sha256=J3ReBFK7TyZQlleIFspz7Pl1wqAzaYoveGZfNNL5DVM,10101
|
580
587
|
mani_skill/envs/tasks/tabletop/plug_charger.py,sha256=0g-rkNf-oo2ovttlcQ58jqUq6So4SKvYMTHORZUOi_0,10571
|
@@ -607,7 +614,7 @@ mani_skill/evaluation/run_evaluation.py,sha256=yorphrlJKEGycHfQS8equnJHRsyjDuv77
|
|
607
614
|
mani_skill/evaluation/solution.py,sha256=e_Aa0f4sSQ56KXL7tVDPUKf7WTjcuFc5X4J76p884Zs,1269
|
608
615
|
mani_skill/examples/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
|
609
616
|
mani_skill/examples/demo_manual_control.py,sha256=PiGxRF_7mf1k_jW6ak9zDcnwcSNtXdbIoL9SZJ30tV8,8275
|
610
|
-
mani_skill/examples/demo_random_action.py,sha256=
|
617
|
+
mani_skill/examples/demo_random_action.py,sha256=qdpndV31mWxRK_340TGDXYQAV4CAkKc4DaFHmPM_7Jw,5226
|
611
618
|
mani_skill/examples/demo_reset_distribution.py,sha256=qkg9TlGjL13WfYgnoimKN5XZr2bK1WvJGvi2Lj3Tmq8,2987
|
612
619
|
mani_skill/examples/demo_robot.py,sha256=bIeHztjM0R6yJT699WQ6jkhv6LjsiP4GWa3Whyom_qM,4881
|
613
620
|
mani_skill/examples/demo_vis_pcd.py,sha256=50YT-YVeX4sEsXxHh0S9Ju_kra8ZcUzPfFpG3EgK2o4,2139
|
@@ -656,7 +663,7 @@ mani_skill/sensors/depth_camera.py,sha256=KCT7DMqQacVag_24MjkKAml87T6FtDqNS0TJFf
|
|
656
663
|
mani_skill/trajectory/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
|
657
664
|
mani_skill/trajectory/dataset.py,sha256=nrG3jkhdzRqAdjxC_c8Z4FxpkvW3A9XPvUp9-Ux_u38,6351
|
658
665
|
mani_skill/trajectory/merge_trajectory.py,sha256=zsjRMTsiIirZGIV4KrtYOM2-zoOAzd7ObZEdWGJzZbE,3685
|
659
|
-
mani_skill/trajectory/replay_trajectory.py,sha256=
|
666
|
+
mani_skill/trajectory/replay_trajectory.py,sha256=cnqQX9ThXhnTSGyzp4CrQRLESXH9UgDLe-7iJfTm67s,27000
|
660
667
|
mani_skill/trajectory/utils/__init__.py,sha256=Nchv09IpXv0FOgpf7Ng1Ekus6ZfAh3kI0KJs-79QOig,1515
|
661
668
|
mani_skill/trajectory/utils/actions/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
|
662
669
|
mani_skill/trajectory/utils/actions/conversion.py,sha256=x88C64ke44gB-HEbqq_gSRFv34L7irSwT_wYttkQUn8,12922
|
@@ -746,7 +753,7 @@ mani_skill/utils/scene_builder/robocasa/utils/placement_samplers.py,sha256=ZUbue
|
|
746
753
|
mani_skill/utils/scene_builder/robocasa/utils/scene_registry.py,sha256=16ZHhI1mgDGy3373aMVRliN8pcvrVigNJIMExyTxE1c,3770
|
747
754
|
mani_skill/utils/scene_builder/robocasa/utils/scene_utils.py,sha256=a8HnoRtbwmqQyvLQCHUXKj951G2_wlzodW_eD_CBvsc,6293
|
748
755
|
mani_skill/utils/scene_builder/table/__init__.py,sha256=g5qmrh4wZ7V_PuKv-ZU9RVwNQUbQhCshAFInAyRLuZc,45
|
749
|
-
mani_skill/utils/scene_builder/table/scene_builder.py,sha256=
|
756
|
+
mani_skill/utils/scene_builder/table/scene_builder.py,sha256=gHICuKA7fNY7AvczSNiocQ6Hzt_i_TV5HP-A-3pnCx0,9955
|
750
757
|
mani_skill/utils/scene_builder/table/assets/Dining_Table_204_1.glb,sha256=IleHi35xfR8O9atKehqjWiuC9McjEFRCBKHRF85w_Tg,150524
|
751
758
|
mani_skill/utils/scene_builder/table/assets/table.glb,sha256=yw69itZDjBFg8JXZAr9VQV-dZD-MaZChhqBSJR_nlRo,3891588
|
752
759
|
mani_skill/utils/structs/README.md,sha256=qnYKimp_ZkgNcduURrYQxVTimNmq_usDMKoQ8VtMdCs,286
|
@@ -777,8 +784,8 @@ mani_skill/vector/wrappers/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJ
|
|
777
784
|
mani_skill/vector/wrappers/gymnasium.py,sha256=v1MDPIrVACBKCulrpdXBK2jDZQI7LKYFZgGgaCC5avY,7408
|
778
785
|
mani_skill/vector/wrappers/sb3.py,sha256=SlXdiEPqcNHYMhJCzA29kBU6zK7DKTe1nc0L6Z3QQtY,4722
|
779
786
|
mani_skill/viewer/__init__.py,sha256=srvDBsk4LQU75K2VIttrhiQ68p_ro7PSDqQRls2PY5c,1722
|
780
|
-
mani_skill_nightly-2025.4.
|
781
|
-
mani_skill_nightly-2025.4.
|
782
|
-
mani_skill_nightly-2025.4.
|
783
|
-
mani_skill_nightly-2025.4.
|
784
|
-
mani_skill_nightly-2025.4.
|
787
|
+
mani_skill_nightly-2025.4.9.1837.dist-info/LICENSE,sha256=xx0jnfkXJvxRnG63LTGOxlggYnIysveWIZ6H3PNdCrQ,11357
|
788
|
+
mani_skill_nightly-2025.4.9.1837.dist-info/METADATA,sha256=kF9mo8CdLkHtPRk-tenVy2Wu5H0tCaVFRVqZnd0WNZI,9291
|
789
|
+
mani_skill_nightly-2025.4.9.1837.dist-info/WHEEL,sha256=tZoeGjtWxWRfdplE7E3d45VPlLNQnvbKiYnx7gwAy8A,92
|
790
|
+
mani_skill_nightly-2025.4.9.1837.dist-info/top_level.txt,sha256=bkBgOVl_MZMoQx2aRFsSFEYlZLxjWlip5vtJ39FB3jA,11
|
791
|
+
mani_skill_nightly-2025.4.9.1837.dist-info/RECORD,,
|
Binary file
|
Binary file
|
Binary file
|
Binary file
|
Binary file
|
Binary file
|
Binary file
|
File without changes
|
{mani_skill_nightly-2025.4.7.816.dist-info → mani_skill_nightly-2025.4.9.1837.dist-info}/LICENSE
RENAMED
File without changes
|
{mani_skill_nightly-2025.4.7.816.dist-info → mani_skill_nightly-2025.4.9.1837.dist-info}/WHEEL
RENAMED
File without changes
|
File without changes
|