mani-skill-nightly 2025.5.30.2218__py3-none-any.whl → 2025.6.7.814__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/widowxai/__init__.py +2 -0
- mani_skill/agents/robots/widowxai/widowxai.py +163 -0
- mani_skill/agents/robots/widowxai/widowxai_wristcam.py +32 -0
- mani_skill/envs/tasks/tabletop/pick_cube.py +35 -18
- mani_skill/envs/tasks/tabletop/pick_cube_cfgs.py +11 -0
- mani_skill/envs/tasks/tabletop/plug_charger.py +0 -9
- mani_skill/examples/benchmarking/plot_results.py +6 -9
- mani_skill/examples/demo_reset_distribution.py +1 -1
- mani_skill/utils/assets/data.py +5 -0
- mani_skill/utils/scene_builder/table/scene_builder.py +3 -0
- {mani_skill_nightly-2025.5.30.2218.dist-info → mani_skill_nightly-2025.6.7.814.dist-info}/METADATA +1 -1
- {mani_skill_nightly-2025.5.30.2218.dist-info → mani_skill_nightly-2025.6.7.814.dist-info}/RECORD +16 -13
- {mani_skill_nightly-2025.5.30.2218.dist-info → mani_skill_nightly-2025.6.7.814.dist-info}/LICENSE +0 -0
- {mani_skill_nightly-2025.5.30.2218.dist-info → mani_skill_nightly-2025.6.7.814.dist-info}/WHEEL +0 -0
- {mani_skill_nightly-2025.5.30.2218.dist-info → mani_skill_nightly-2025.6.7.814.dist-info}/top_level.txt +0 -0
@@ -0,0 +1,163 @@
|
|
1
|
+
import copy
|
2
|
+
|
3
|
+
import numpy as np
|
4
|
+
import sapien
|
5
|
+
import torch
|
6
|
+
|
7
|
+
from mani_skill import 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
|
+
from mani_skill.utils import common, sapien_utils
|
12
|
+
from mani_skill.utils.structs.actor import Actor
|
13
|
+
|
14
|
+
|
15
|
+
@register_agent(asset_download_ids=["widowxai"])
|
16
|
+
class WidowXAI(BaseAgent):
|
17
|
+
uid = "widowxai"
|
18
|
+
urdf_path = f"{ASSET_DIR}/robots/widowxai/wxai_base.urdf"
|
19
|
+
urdf_config = dict(
|
20
|
+
_materials=dict(
|
21
|
+
gripper=dict(static_friction=2.0, dynamic_friction=2.0, restitution=0.0)
|
22
|
+
),
|
23
|
+
link=dict(
|
24
|
+
gripper_left=dict(
|
25
|
+
material="gripper", patch_radius=0.1, min_patch_radius=0.1
|
26
|
+
),
|
27
|
+
gripper_right=dict(
|
28
|
+
material="gripper", patch_radius=0.1, min_patch_radius=0.1
|
29
|
+
),
|
30
|
+
),
|
31
|
+
)
|
32
|
+
|
33
|
+
keyframes = dict(
|
34
|
+
ready_to_grasp=Keyframe(
|
35
|
+
qpos=np.array(
|
36
|
+
[
|
37
|
+
0.0,
|
38
|
+
1.38,
|
39
|
+
1.04,
|
40
|
+
-1.26,
|
41
|
+
0.0,
|
42
|
+
0.0,
|
43
|
+
0.026,
|
44
|
+
0.026,
|
45
|
+
]
|
46
|
+
),
|
47
|
+
pose=sapien.Pose(),
|
48
|
+
)
|
49
|
+
)
|
50
|
+
|
51
|
+
arm_joint_names = [
|
52
|
+
"joint_0",
|
53
|
+
"joint_1",
|
54
|
+
"joint_2",
|
55
|
+
"joint_3",
|
56
|
+
"joint_4",
|
57
|
+
"joint_5",
|
58
|
+
"left_carriage_joint",
|
59
|
+
]
|
60
|
+
gripper_joint_names = [
|
61
|
+
# only control the control joint, not the mimicked one
|
62
|
+
# "right_carriage_joint",
|
63
|
+
"left_carriage_joint",
|
64
|
+
]
|
65
|
+
ee_link_name = "ee_gripper_link"
|
66
|
+
arm_stiffness = 1e3
|
67
|
+
arm_damping = 1e2
|
68
|
+
arm_force_limit = 100
|
69
|
+
gripper_stiffness = 1e3
|
70
|
+
gripper_damping = 1e2
|
71
|
+
gripper_force_limit = 100
|
72
|
+
|
73
|
+
@property
|
74
|
+
def _controller_configs(self):
|
75
|
+
arm_pd_joint_pos = PDJointPosControllerConfig(
|
76
|
+
self.arm_joint_names,
|
77
|
+
lower=None,
|
78
|
+
upper=None,
|
79
|
+
stiffness=self.arm_stiffness,
|
80
|
+
damping=self.arm_damping,
|
81
|
+
force_limit=self.arm_force_limit,
|
82
|
+
normalize_action=False,
|
83
|
+
)
|
84
|
+
arm_pd_joint_delta_pos = PDJointPosControllerConfig(
|
85
|
+
self.arm_joint_names,
|
86
|
+
lower=-0.1,
|
87
|
+
upper=0.1,
|
88
|
+
stiffness=self.arm_stiffness,
|
89
|
+
damping=self.arm_damping,
|
90
|
+
force_limit=self.arm_force_limit,
|
91
|
+
use_delta=True,
|
92
|
+
use_target=False,
|
93
|
+
)
|
94
|
+
gripper_pd_joint_pos = PDJointPosControllerConfig(
|
95
|
+
self.gripper_joint_names,
|
96
|
+
lower=0.0,
|
97
|
+
upper=0.044,
|
98
|
+
stiffness=self.gripper_stiffness,
|
99
|
+
damping=self.gripper_damping,
|
100
|
+
)
|
101
|
+
arm_pd_joint_target_delta_pos = copy.deepcopy(arm_pd_joint_delta_pos)
|
102
|
+
arm_pd_joint_target_delta_pos.use_target = True
|
103
|
+
|
104
|
+
controller_configs = dict(
|
105
|
+
pd_joint_delta_pos=dict(
|
106
|
+
arm=arm_pd_joint_delta_pos,
|
107
|
+
gripper=gripper_pd_joint_pos,
|
108
|
+
),
|
109
|
+
pd_joint_pos=dict(arm=arm_pd_joint_pos, gripper=gripper_pd_joint_pos),
|
110
|
+
pd_joint_target_delta_pos=dict(
|
111
|
+
arm=arm_pd_joint_target_delta_pos,
|
112
|
+
gripper=gripper_pd_joint_pos,
|
113
|
+
),
|
114
|
+
)
|
115
|
+
return deepcopy_dict(controller_configs)
|
116
|
+
|
117
|
+
def _after_loading_articulation(self):
|
118
|
+
self.finger1_link = self.robot.links_map["gripper_left"]
|
119
|
+
self.finger2_link = self.robot.links_map["gripper_right"]
|
120
|
+
self.tcp = sapien_utils.get_obj_by_name(
|
121
|
+
self.robot.get_links(), self.ee_link_name
|
122
|
+
)
|
123
|
+
|
124
|
+
@property
|
125
|
+
def tcp_pos(self):
|
126
|
+
return self.tcp.pose.p
|
127
|
+
|
128
|
+
@property
|
129
|
+
def tcp_pose(self):
|
130
|
+
return self.tcp.pose
|
131
|
+
|
132
|
+
def is_grasping(self, object: Actor, min_force=0.2, max_angle=85):
|
133
|
+
"""Check if the robot is grasping an object
|
134
|
+
|
135
|
+
Args:
|
136
|
+
object (Actor): The object to check if the robot is grasping
|
137
|
+
min_force (float, optional): Minimum force before the robot is considered to be grasping the object in Newtons. Defaults to 0.5.
|
138
|
+
max_angle (int, optional): Maximum angle of contact to consider grasping. Defaults to 85.
|
139
|
+
"""
|
140
|
+
l_contact_forces = self.scene.get_pairwise_contact_forces(
|
141
|
+
self.finger1_link, object
|
142
|
+
)
|
143
|
+
r_contact_forces = self.scene.get_pairwise_contact_forces(
|
144
|
+
self.finger2_link, object
|
145
|
+
)
|
146
|
+
lforce = torch.linalg.norm(l_contact_forces, axis=1)
|
147
|
+
rforce = torch.linalg.norm(r_contact_forces, axis=1)
|
148
|
+
ldirection = self.finger1_link.pose.to_transformation_matrix()[..., :3, 1]
|
149
|
+
rdirection = -self.finger2_link.pose.to_transformation_matrix()[..., :3, 1]
|
150
|
+
langle = common.compute_angle_between(ldirection, l_contact_forces)
|
151
|
+
rangle = common.compute_angle_between(rdirection, r_contact_forces)
|
152
|
+
lflag = torch.logical_and(
|
153
|
+
lforce >= min_force, torch.rad2deg(langle) <= max_angle
|
154
|
+
)
|
155
|
+
rflag = torch.logical_and(
|
156
|
+
rforce >= min_force, torch.rad2deg(rangle) <= max_angle
|
157
|
+
)
|
158
|
+
_is_grasped = torch.logical_and(lflag, rflag)
|
159
|
+
return _is_grasped
|
160
|
+
|
161
|
+
def is_static(self, threshold: float = 0.2):
|
162
|
+
qvel = self.robot.get_qvel()[..., :-2]
|
163
|
+
return torch.max(torch.abs(qvel), 1)[0] <= threshold
|
@@ -0,0 +1,32 @@
|
|
1
|
+
import numpy as np
|
2
|
+
import sapien
|
3
|
+
|
4
|
+
from mani_skill import ASSET_DIR
|
5
|
+
from mani_skill.agents.registration import register_agent
|
6
|
+
from mani_skill.sensors.camera import CameraConfig
|
7
|
+
from mani_skill.utils import sapien_utils
|
8
|
+
|
9
|
+
from .widowxai import WidowXAI
|
10
|
+
|
11
|
+
|
12
|
+
@register_agent(asset_download_ids=["widowxai"])
|
13
|
+
class WidowXAIWristCam(WidowXAI):
|
14
|
+
"""WidowX AI robot with a Intel Realsense D405 mounted on the gripper"""
|
15
|
+
|
16
|
+
uid = "widowxai_wristcam"
|
17
|
+
urdf_path = f"{ASSET_DIR}/robots/widowxai/wxai_follower.urdf"
|
18
|
+
|
19
|
+
@property
|
20
|
+
def _sensor_configs(self):
|
21
|
+
return [
|
22
|
+
CameraConfig(
|
23
|
+
uid="wrist_camera",
|
24
|
+
pose=sapien.Pose(p=[0, 0, 0], q=[1, 0, 0, 0]),
|
25
|
+
width=128,
|
26
|
+
height=128,
|
27
|
+
fov=np.pi / 2,
|
28
|
+
near=0.01,
|
29
|
+
far=100,
|
30
|
+
mount=self.robot.links_map["camera_link"],
|
31
|
+
)
|
32
|
+
]
|
@@ -5,7 +5,7 @@ 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 SO100, Fetch, Panda, XArm6Robotiq
|
8
|
+
from mani_skill.agents.robots import SO100, Fetch, Panda, WidowXAI, XArm6Robotiq
|
9
9
|
from mani_skill.envs.sapien_env import BaseEnv
|
10
10
|
from mani_skill.envs.tasks.tabletop.pick_cube_cfgs import PICK_CUBE_CONFIGS
|
11
11
|
from mani_skill.sensors.camera import CameraConfig
|
@@ -15,23 +15,23 @@ from mani_skill.utils.registration import register_env
|
|
15
15
|
from mani_skill.utils.scene_builder.table import TableSceneBuilder
|
16
16
|
from mani_skill.utils.structs.pose import Pose
|
17
17
|
|
18
|
+
PICK_CUBE_DOC_STRING = """**Task Description:**
|
19
|
+
A simple task where the objective is to grasp a red cube with the {robot_id} robot and move it to a target goal position. This is also the *baseline* task to test whether a robot with manipulation
|
20
|
+
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.
|
18
21
|
|
19
|
-
|
20
|
-
|
21
|
-
|
22
|
-
|
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.
|
22
|
+
**Randomizations:**
|
23
|
+
- 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
|
24
|
+
- the cube's z-axis rotation is randomized to a random angle
|
25
|
+
- the target goal position (marked by a green sphere) of the cube has its xy position randomized in the region [0.1, 0.1] x [-0.1, -0.1] and z randomized in [0, 0.3]
|
25
26
|
|
26
|
-
|
27
|
-
|
28
|
-
|
29
|
-
|
27
|
+
**Success Conditions:**
|
28
|
+
- the cube position is within `goal_thresh` (default 0.025m) euclidean distance of the goal position
|
29
|
+
- the robot is static (q velocity < 0.2)
|
30
|
+
"""
|
30
31
|
|
31
|
-
|
32
|
-
|
33
|
-
|
34
|
-
"""
|
32
|
+
|
33
|
+
@register_env("PickCube-v1", max_episode_steps=50)
|
34
|
+
class PickCubeEnv(BaseEnv):
|
35
35
|
|
36
36
|
_sample_video_link = "https://github.com/haosulab/ManiSkill/raw/main/figures/environment_demos/PickCube-v1_rt.mp4"
|
37
37
|
SUPPORTED_ROBOTS = [
|
@@ -39,8 +39,9 @@ class PickCubeEnv(BaseEnv):
|
|
39
39
|
"fetch",
|
40
40
|
"xarm6_robotiq",
|
41
41
|
"so100",
|
42
|
+
"widowxai",
|
42
43
|
]
|
43
|
-
agent: Union[Panda, Fetch, XArm6Robotiq, SO100]
|
44
|
+
agent: Union[Panda, Fetch, XArm6Robotiq, SO100, WidowXAI]
|
44
45
|
cube_half_size = 0.02
|
45
46
|
goal_thresh = 0.025
|
46
47
|
cube_spawn_half_size = 0.05
|
@@ -175,7 +176,7 @@ class PickCubeEnv(BaseEnv):
|
|
175
176
|
reward += place_reward * is_grasped
|
176
177
|
|
177
178
|
qvel = self.agent.robot.get_qvel()
|
178
|
-
if self.robot_uids
|
179
|
+
if self.robot_uids in ["panda", "widowxai"]:
|
179
180
|
qvel = qvel[..., :-2]
|
180
181
|
elif self.robot_uids == "so100":
|
181
182
|
qvel = qvel[..., :-1]
|
@@ -191,10 +192,26 @@ class PickCubeEnv(BaseEnv):
|
|
191
192
|
return self.compute_dense_reward(obs=obs, action=action, info=info) / 5
|
192
193
|
|
193
194
|
|
195
|
+
PickCubeEnv.__doc__ = PICK_CUBE_DOC_STRING.format(robot_id="Panda")
|
196
|
+
|
197
|
+
|
194
198
|
@register_env("PickCubeSO100-v1", max_episode_steps=50)
|
195
199
|
class PickCubeSO100Env(PickCubeEnv):
|
196
|
-
|
197
200
|
_sample_video_link = "https://github.com/haosulab/ManiSkill/raw/main/figures/environment_demos/PickCubeSO100-v1_rt.mp4"
|
198
201
|
|
199
202
|
def __init__(self, *args, **kwargs):
|
200
203
|
super().__init__(*args, robot_uids="so100", **kwargs)
|
204
|
+
|
205
|
+
|
206
|
+
PickCubeSO100Env.__doc__ = PICK_CUBE_DOC_STRING.format(robot_id="SO100")
|
207
|
+
|
208
|
+
|
209
|
+
@register_env("PickCubeWidowXAI-v1", max_episode_steps=50)
|
210
|
+
class PickCubeWidowXAIEnv(PickCubeEnv):
|
211
|
+
_sample_video_link = "https://github.com/haosulab/ManiSkill/raw/main/figures/environment_demos/PickCubeWidowXAI-v1_rt.mp4"
|
212
|
+
|
213
|
+
def __init__(self, *args, **kwargs):
|
214
|
+
super().__init__(*args, robot_uids="widowxai", **kwargs)
|
215
|
+
|
216
|
+
|
217
|
+
PickCubeWidowXAIEnv.__doc__ = PICK_CUBE_DOC_STRING.format(robot_id="WidowXAI")
|
@@ -56,4 +56,15 @@ PICK_CUBE_CONFIGS = {
|
|
56
56
|
"human_cam_eye_pos": [-0.1, 0.3, 0.4],
|
57
57
|
"human_cam_target_pos": [-0.46, 0.0, 0.1],
|
58
58
|
},
|
59
|
+
"widowxai": {
|
60
|
+
"cube_half_size": 0.018,
|
61
|
+
"goal_thresh": 0.018 * 1.25,
|
62
|
+
"cube_spawn_half_size": 0.05,
|
63
|
+
"cube_spawn_center": (-0.25, 0),
|
64
|
+
"max_goal_height": 0.2,
|
65
|
+
"sensor_cam_eye_pos": [0.0, 0, 0.35],
|
66
|
+
"sensor_cam_target_pos": [-0.2, 0, 0.1],
|
67
|
+
"human_cam_eye_pos": [0.45, 0.5, 0.5],
|
68
|
+
"human_cam_target_pos": [-0.2, 0.0, 0.2],
|
69
|
+
},
|
59
70
|
}
|
@@ -276,12 +276,3 @@ class PlugChargerEnv(BaseEnv):
|
|
276
276
|
goal_pose=self.goal_pose.raw_pose,
|
277
277
|
)
|
278
278
|
return obs
|
279
|
-
|
280
|
-
def compute_dense_reward(self, obs: Any, action: torch.Tensor, info: Dict):
|
281
|
-
return torch.zeros(self.num_envs, device=self.device)
|
282
|
-
|
283
|
-
def compute_normalized_dense_reward(
|
284
|
-
self, obs: Any, action: torch.Tensor, info: Dict
|
285
|
-
):
|
286
|
-
max_reward = 1.0
|
287
|
-
return self.compute_dense_reward(obs=obs, action=action, info=info) / max_reward
|
@@ -175,7 +175,7 @@ def main(args):
|
|
175
175
|
|
176
176
|
# generate plot for RT/google dataset settings, which is 1x 640x480 cameras
|
177
177
|
for obs_mode in ["RGB", "Depth"]:
|
178
|
-
fig, ax = plt.subplots(
|
178
|
+
fig, ax = plt.subplots()
|
179
179
|
ax.set_title(f"{args.env_id}: FPS with 1x 640x480 {obs_mode} Cameras")
|
180
180
|
draw_bar_plot_envs_vs_fps(ax, data, {"env_id": args.env_id, "obs_mode": obs_mode.lower(), "num_cameras": 1, "camera_width": 640, "camera_height": 480}, annotate_label="env.step/gpu_mem_use")
|
181
181
|
plt.legend()
|
@@ -187,7 +187,7 @@ def main(args):
|
|
187
187
|
|
188
188
|
# generate plot for droit dataset settings, which is 3x 320x180 cameras
|
189
189
|
for obs_mode in ["RGB", "Depth"]:
|
190
|
-
fig, ax = plt.subplots(
|
190
|
+
fig, ax = plt.subplots()
|
191
191
|
ax.set_title(f"{args.env_id}: FPS with 3x 320x180 {obs_mode} Cameras")
|
192
192
|
draw_bar_plot_envs_vs_fps(ax, data, {"env_id": args.env_id, "obs_mode": obs_mode.lower(), "num_cameras": 3, "camera_width": 320, "camera_height": 180}, annotate_label="env.step/gpu_mem_use")
|
193
193
|
save_path = osp.join(root_save_path, f"fps_droid_dataset_setup_{obs_mode.lower()}.png")
|
@@ -224,19 +224,16 @@ def main(args):
|
|
224
224
|
print(f"Saved figure to {save_path}")
|
225
225
|
|
226
226
|
|
227
|
-
|
228
|
-
|
229
227
|
### Special figures for maniskill ###
|
230
|
-
if "
|
228
|
+
if "ManiSkill3" in data.keys():
|
231
229
|
# Generate line plots of rendering FPS for different env_ids against number of parallel environments
|
232
|
-
fig, ax = plt.subplots(figsize=(10,
|
230
|
+
fig, ax = plt.subplots(figsize=(10, 6))
|
233
231
|
ax.grid(True)
|
234
232
|
ax.set_xlabel("Number of Parallel Environments")
|
235
233
|
ax.set_ylabel("FPS")
|
236
234
|
ax.set_title("Simulation+Rendering FPS vs Number of Parallel Environments for Different Tasks")
|
237
|
-
|
238
|
-
df =
|
239
|
-
df = df[(df["obs_mode"] == "rgb") & (df["num_envs"] >= 16) & (df["num_cameras"] == 1) & (df["camera_width"] == 128)]
|
235
|
+
df = data["ManiSkill3"]
|
236
|
+
df = df[(df["obs_mode"] == "rgb") & (df["num_envs"] >= 16) & (df["num_envs"] <= 1024) & (df["num_cameras"] == 1) & (df["camera_width"] == 128)]
|
240
237
|
env_ids = df["env_id"].unique()
|
241
238
|
for i, env_id in enumerate(env_ids):
|
242
239
|
env_df = df[df["env_id"] == env_id].sort_values("num_envs")
|
mani_skill/utils/assets/data.py
CHANGED
@@ -188,6 +188,11 @@ def initialize_data_sources():
|
|
188
188
|
url="https://github.com/haosulab/ManiSkill-XArm6/archive/refs/tags/v0.1.1.zip",
|
189
189
|
target_path="robots/xarm6",
|
190
190
|
)
|
191
|
+
DATA_SOURCES["widowxai"] = DataSource(
|
192
|
+
source_type="robot",
|
193
|
+
url="https://github.com/TrossenRobotics/ManiSkill-WidowX_AI/archive/refs/tags/v0.1.0.zip",
|
194
|
+
target_path="robots/widowxai",
|
195
|
+
)
|
191
196
|
|
192
197
|
|
193
198
|
def expand_data_group_into_individual_data_source_ids(data_group_id: str):
|
@@ -270,6 +270,9 @@ class TableSceneBuilder(SceneBuilder):
|
|
270
270
|
)
|
271
271
|
self.env.agent.reset(qpos)
|
272
272
|
self.env.agent.robot.set_pose(sapien.Pose([-0.615, 0, 0]))
|
273
|
+
elif self.env.robot_uids in ["widowxai", "widowxai_wristcam"]:
|
274
|
+
qpos = self.env.agent.keyframes["ready_to_grasp"].qpos
|
275
|
+
self.env.agent.reset(qpos)
|
273
276
|
elif self.env.robot_uids == "so100":
|
274
277
|
qpos = np.array([0, np.pi / 2, np.pi / 2, np.pi / 2, -np.pi / 2, 1.0])
|
275
278
|
qpos = (
|
{mani_skill_nightly-2025.5.30.2218.dist-info → mani_skill_nightly-2025.6.7.814.dist-info}/RECORD
RENAMED
@@ -15,7 +15,7 @@ mani_skill/agents/controllers/pd_joint_pos_vel.py,sha256=wgiXmenTVIao1Tm1vtdJWTZ
|
|
15
15
|
mani_skill/agents/controllers/pd_joint_vel.py,sha256=VZF06ISCkdKBX_fUHxb7mdl9GN1Lob5dhrFGlwCx16Q,1957
|
16
16
|
mani_skill/agents/controllers/utils/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
|
17
17
|
mani_skill/agents/controllers/utils/kinematics.py,sha256=FiSE1nfZejShEqvua9buzA_SCBuEP9OiAd7LpLbSp44,10415
|
18
|
-
mani_skill/agents/robots/__init__.py,sha256=
|
18
|
+
mani_skill/agents/robots/__init__.py,sha256=lvW8t2bn2UjuWZ7PsYiKqMnHaMLvGVw6itBhxwHaauk,737
|
19
19
|
mani_skill/agents/robots/allegro_hand/__init__.py,sha256=PWH6MMv2i5g1xi76_E-YJLtKFLVKxkJgQ96GD_YeQN4,104
|
20
20
|
mani_skill/agents/robots/allegro_hand/allegro.py,sha256=MnU04fCcvppTGJHdhgvs2OqUKToQtNMXbs2bFM5sXiU,4896
|
21
21
|
mani_skill/agents/robots/allegro_hand/allegro_touch.py,sha256=CMnGIf1JT7jbrM5jc-OHfODeYiwrUp8rzuS9rUMzmK4,5805
|
@@ -62,6 +62,9 @@ mani_skill/agents/robots/ur_e/__init__.py,sha256=oO05yUDMLyjnHKvIKpqhPhzOHaKzan6
|
|
62
62
|
mani_skill/agents/robots/ur_e/ur_10e.py,sha256=DzkVpxiYYAhV3_44r2oz8xcRFdMoyqIXeAHDJflOpFU,1301
|
63
63
|
mani_skill/agents/robots/widowx/__init__.py,sha256=RJxgMecbFZ7waMEQSwlv6tbkGUeXnMBKwsG8Ojl3OwA,31
|
64
64
|
mani_skill/agents/robots/widowx/widowx.py,sha256=3QpXCvgFDnPYOmrbDGxqVVjSyXzG1FG_76tyEe3AMP4,2415
|
65
|
+
mani_skill/agents/robots/widowxai/__init__.py,sha256=CduO9Os3_TTvz6MBuMYUv8Cem3wDL2-DPm8BTX45KuY,79
|
66
|
+
mani_skill/agents/robots/widowxai/widowxai.py,sha256=gz_NM80xkHQO-3XsSgtkdKCBw3am554TTOx8sOSJtGA,5437
|
67
|
+
mani_skill/agents/robots/widowxai/widowxai_wristcam.py,sha256=IDOArvYzlLkMwC35Bby8lZNa2pcDiGc_lmbO2rYtKYs,918
|
65
68
|
mani_skill/agents/robots/xarm/__init__.py,sha256=6Mhn4vV4f9XxcK493U5W9VE6yGGgydPbVQLo9iOu8BA,40
|
66
69
|
mani_skill/agents/robots/xarm/xarm7_ability.py,sha256=yj7CUBQpbGVUiT22qweJKTniJE0DxdEyyKj329vr0HY,6106
|
67
70
|
mani_skill/agents/robots/xarm6/__init__.py,sha256=0r19OsKmm1ssKB5Rrie8syWQvpXNooVOv6m-iygrdM0,109
|
@@ -602,11 +605,11 @@ mani_skill/envs/tasks/tabletop/assembling_kits.py,sha256=piXxTybVKrRr92VqIFIQsbr
|
|
602
605
|
mani_skill/envs/tasks/tabletop/lift_peg_upright.py,sha256=o6AmHyjyoT5U6IYn0tXz3MJ7PNCEqHPZf2jnFOFuW-Y,5857
|
603
606
|
mani_skill/envs/tasks/tabletop/peg_insertion_side.py,sha256=3tf9eOI4PmNGKXooZUR81AXUPuUUTgG-V4DuYxtd5dg,14033
|
604
607
|
mani_skill/envs/tasks/tabletop/pick_clutter_ycb.py,sha256=uA-kMGMAODeNvL99K1kDBrtU7b7VEkbkzUip5dJzucM,7345
|
605
|
-
mani_skill/envs/tasks/tabletop/pick_cube.py,sha256=
|
606
|
-
mani_skill/envs/tasks/tabletop/pick_cube_cfgs.py,sha256=
|
608
|
+
mani_skill/envs/tasks/tabletop/pick_cube.py,sha256=wC2DdKKxROaG2oWovbKGlPyuKLd217nlFA2Vp7d97j0,8717
|
609
|
+
mani_skill/envs/tasks/tabletop/pick_cube_cfgs.py,sha256=ns0bhw6nrJElSR9nGruGYECyzeAJgq4nd2HraEHI5A0,2564
|
607
610
|
mani_skill/envs/tasks/tabletop/pick_single_ycb.py,sha256=mrqEoOa9UVF34Z5fpsvjcr683diUffsKEjJ9Zh0qfFU,10409
|
608
611
|
mani_skill/envs/tasks/tabletop/place_sphere.py,sha256=J3ReBFK7TyZQlleIFspz7Pl1wqAzaYoveGZfNNL5DVM,10101
|
609
|
-
mani_skill/envs/tasks/tabletop/plug_charger.py,sha256=
|
612
|
+
mani_skill/envs/tasks/tabletop/plug_charger.py,sha256=nqxrafAtziJGjwBVhB3OjfA4UxVSIoJxrAWzA9_YMuY,10347
|
610
613
|
mani_skill/envs/tasks/tabletop/poke_cube.py,sha256=KV6mp-Xgm9h4GYUcAUop2AZ4IECTdQKEMRRd9NThyBo,9343
|
611
614
|
mani_skill/envs/tasks/tabletop/pull_cube.py,sha256=tyy9KOgBjQOHjFrVK2-hNQPCPDjJ7Y61ZtbwPX_6gvk,5548
|
612
615
|
mani_skill/envs/tasks/tabletop/pull_cube_tool.py,sha256=NaZpdbYYL4zC41GVY__eq4uRIQpVXthzAqe5oSq8YWU,9951
|
@@ -638,7 +641,7 @@ mani_skill/examples/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSu
|
|
638
641
|
mani_skill/examples/demo_manual_control.py,sha256=Z17ER37oehS8VgtDO_4dwiy5jDgL93nT9IdCsNDf0Es,8275
|
639
642
|
mani_skill/examples/demo_manual_control_continuous.py,sha256=tnCnKX2v1iIhtXwvWR2NzXgpf3e0y2-qAO91jJBLIO0,9679
|
640
643
|
mani_skill/examples/demo_random_action.py,sha256=qdpndV31mWxRK_340TGDXYQAV4CAkKc4DaFHmPM_7Jw,5226
|
641
|
-
mani_skill/examples/demo_reset_distribution.py,sha256=
|
644
|
+
mani_skill/examples/demo_reset_distribution.py,sha256=m1I5WQptBJrXvFPdUi7TIzR_Q--_wGAFkbcKNKWlq2U,2988
|
642
645
|
mani_skill/examples/demo_robot.py,sha256=bIeHztjM0R6yJT699WQ6jkhv6LjsiP4GWa3Whyom_qM,4881
|
643
646
|
mani_skill/examples/demo_vis_pcd.py,sha256=50YT-YVeX4sEsXxHh0S9Ju_kra8ZcUzPfFpG3EgK2o4,2139
|
644
647
|
mani_skill/examples/demo_vis_segmentation.py,sha256=HESY-_XjQbofBZQbUl_fuAupQpr3H4ZerPzwGBBR12I,4281
|
@@ -646,7 +649,7 @@ mani_skill/examples/demo_vis_textures.py,sha256=m1hcOFQyMXu_C8ncnVHdhEksKBs-0e6H
|
|
646
649
|
mani_skill/examples/benchmarking/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
|
647
650
|
mani_skill/examples/benchmarking/gpu_sim.py,sha256=_Dm7IbjQgWtvq-T3XxJ0-aeFMDAB8QWgcqTA24OsdIQ,9935
|
648
651
|
mani_skill/examples/benchmarking/isaac_lab_gpu_sim.py,sha256=tATuRyJi37xHzCzbs-B3e0PS-l9oYj9FcLJC9F9Dtec,5581
|
649
|
-
mani_skill/examples/benchmarking/plot_results.py,sha256=
|
652
|
+
mani_skill/examples/benchmarking/plot_results.py,sha256=ou2lE3jNALaWMy1muPbZ0JeV6rpmm4VBDPFpcDeyaSI,12452
|
650
653
|
mani_skill/examples/benchmarking/profiling.py,sha256=ROtHXNrqHAlJkqc-30wynrQ3GxvYjuIIDJ_ozbClcQA,8656
|
651
654
|
mani_skill/examples/benchmarking/envs/__init__.py,sha256=lW_XjPqNAGLRaFbssHiOnSBboTTJO_--0GVduOh18Q8,101
|
652
655
|
mani_skill/examples/benchmarking/envs/isaaclab/__init__.py,sha256=ncUw7bBTKE1zi6c4lHor_S7X8E4iaxMIjlI3YPpGgcw,867
|
@@ -712,7 +715,7 @@ mani_skill/utils/registration.py,sha256=u8ftfGvQP4qzlKNqLQjGi3cRF_-h6Rz-28xbLkW_
|
|
712
715
|
mani_skill/utils/sapien_utils.py,sha256=QMV0jRZO51KzIMB5CVW_Ne-4fPw0-mqM4a3yhNZaMYo,16430
|
713
716
|
mani_skill/utils/assets/README.md,sha256=5kkmsIiV64ySEGO34HaAlpjXTyrGs1KTV5WnofK46G0,70
|
714
717
|
mani_skill/utils/assets/__init__.py,sha256=gQVKwAczcImTXArSltBWKlSUUuguO12sZYO3Jh5KLso,159
|
715
|
-
mani_skill/utils/assets/data.py,sha256=
|
718
|
+
mani_skill/utils/assets/data.py,sha256=xEuibRoEPBDN_vEU-MM5UWf6VDb1omE6BfZKPvlMPdI,8807
|
716
719
|
mani_skill/utils/building/__init__.py,sha256=quCI5WYGhzGLMVg_NDyYv2G_MxRTBL8R6XD4a6iY8qc,218
|
717
720
|
mani_skill/utils/building/_mjcf_loader.py,sha256=SqzSoRootFvItHrzwrDuSHScePxbaPqWb7262M7HzIU,37011
|
718
721
|
mani_skill/utils/building/actor_builder.py,sha256=BSRLXMfxbFyT_R5-WFNGcTFFa0e2HToLqQFvpOy9DqA,14915
|
@@ -785,7 +788,7 @@ mani_skill/utils/scene_builder/robocasa/utils/placement_samplers.py,sha256=ZUbue
|
|
785
788
|
mani_skill/utils/scene_builder/robocasa/utils/scene_registry.py,sha256=16ZHhI1mgDGy3373aMVRliN8pcvrVigNJIMExyTxE1c,3770
|
786
789
|
mani_skill/utils/scene_builder/robocasa/utils/scene_utils.py,sha256=a8HnoRtbwmqQyvLQCHUXKj951G2_wlzodW_eD_CBvsc,6293
|
787
790
|
mani_skill/utils/scene_builder/table/__init__.py,sha256=g5qmrh4wZ7V_PuKv-ZU9RVwNQUbQhCshAFInAyRLuZc,45
|
788
|
-
mani_skill/utils/scene_builder/table/scene_builder.py,sha256=
|
791
|
+
mani_skill/utils/scene_builder/table/scene_builder.py,sha256=J24fto2sbT0lhYHthG8xqHRtjehAkYAz_HNmGK35dL8,10132
|
789
792
|
mani_skill/utils/scene_builder/table/assets/Dining_Table_204_1.glb,sha256=IleHi35xfR8O9atKehqjWiuC9McjEFRCBKHRF85w_Tg,150524
|
790
793
|
mani_skill/utils/scene_builder/table/assets/table.glb,sha256=yw69itZDjBFg8JXZAr9VQV-dZD-MaZChhqBSJR_nlRo,3891588
|
791
794
|
mani_skill/utils/structs/README.md,sha256=qnYKimp_ZkgNcduURrYQxVTimNmq_usDMKoQ8VtMdCs,286
|
@@ -817,8 +820,8 @@ mani_skill/vector/wrappers/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJ
|
|
817
820
|
mani_skill/vector/wrappers/gymnasium.py,sha256=v1MDPIrVACBKCulrpdXBK2jDZQI7LKYFZgGgaCC5avY,7408
|
818
821
|
mani_skill/vector/wrappers/sb3.py,sha256=SlXdiEPqcNHYMhJCzA29kBU6zK7DKTe1nc0L6Z3QQtY,4722
|
819
822
|
mani_skill/viewer/__init__.py,sha256=srvDBsk4LQU75K2VIttrhiQ68p_ro7PSDqQRls2PY5c,1722
|
820
|
-
mani_skill_nightly-2025.
|
821
|
-
mani_skill_nightly-2025.
|
822
|
-
mani_skill_nightly-2025.
|
823
|
-
mani_skill_nightly-2025.
|
824
|
-
mani_skill_nightly-2025.
|
823
|
+
mani_skill_nightly-2025.6.7.814.dist-info/LICENSE,sha256=xx0jnfkXJvxRnG63LTGOxlggYnIysveWIZ6H3PNdCrQ,11357
|
824
|
+
mani_skill_nightly-2025.6.7.814.dist-info/METADATA,sha256=4rF4IKuYYzAgblhivBT2Lwbxu13igRFqhZJAkEg8s6k,9409
|
825
|
+
mani_skill_nightly-2025.6.7.814.dist-info/WHEEL,sha256=tZoeGjtWxWRfdplE7E3d45VPlLNQnvbKiYnx7gwAy8A,92
|
826
|
+
mani_skill_nightly-2025.6.7.814.dist-info/top_level.txt,sha256=bkBgOVl_MZMoQx2aRFsSFEYlZLxjWlip5vtJ39FB3jA,11
|
827
|
+
mani_skill_nightly-2025.6.7.814.dist-info/RECORD,,
|
{mani_skill_nightly-2025.5.30.2218.dist-info → mani_skill_nightly-2025.6.7.814.dist-info}/LICENSE
RENAMED
File without changes
|
{mani_skill_nightly-2025.5.30.2218.dist-info → mani_skill_nightly-2025.6.7.814.dist-info}/WHEEL
RENAMED
File without changes
|
File without changes
|