mani-skill-nightly 2025.6.28.2200__py3-none-any.whl → 2025.7.8.44__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/envs/tasks/tabletop/__init__.py +2 -1
- mani_skill/envs/tasks/tabletop/stack_pyramid.py +177 -0
- mani_skill/examples/motionplanning/panda/run.py +3 -2
- mani_skill/examples/motionplanning/panda/solutions/__init__.py +2 -1
- mani_skill/examples/motionplanning/panda/solutions/stack_pyramid.py +135 -0
- mani_skill/utils/download_demo.py +1 -0
- {mani_skill_nightly-2025.6.28.2200.dist-info → mani_skill_nightly-2025.7.8.44.dist-info}/METADATA +1 -1
- {mani_skill_nightly-2025.6.28.2200.dist-info → mani_skill_nightly-2025.7.8.44.dist-info}/RECORD +11 -9
- {mani_skill_nightly-2025.6.28.2200.dist-info → mani_skill_nightly-2025.7.8.44.dist-info}/LICENSE +0 -0
- {mani_skill_nightly-2025.6.28.2200.dist-info → mani_skill_nightly-2025.7.8.44.dist-info}/WHEEL +0 -0
- {mani_skill_nightly-2025.6.28.2200.dist-info → mani_skill_nightly-2025.7.8.44.dist-info}/top_level.txt +0 -0
@@ -15,4 +15,5 @@ from .poke_cube import PokeCubeEnv
|
|
15
15
|
from .place_sphere import PlaceSphereEnv
|
16
16
|
from .roll_ball import RollBallEnv
|
17
17
|
from .push_t import PushTEnv
|
18
|
-
from .pull_cube_tool import PullCubeToolEnv
|
18
|
+
from .pull_cube_tool import PullCubeToolEnv
|
19
|
+
from .stack_pyramid import StackPyramidEnv
|
@@ -0,0 +1,177 @@
|
|
1
|
+
from typing import Any, Dict, Union
|
2
|
+
|
3
|
+
import numpy as np
|
4
|
+
import sapien
|
5
|
+
import torch
|
6
|
+
|
7
|
+
from mani_skill.agents.robots import Fetch, Panda
|
8
|
+
from mani_skill.envs.sapien_env import BaseEnv
|
9
|
+
from mani_skill.envs.utils import randomization
|
10
|
+
from mani_skill.utils.geometry.rotation_conversions import (
|
11
|
+
euler_angles_to_matrix,
|
12
|
+
matrix_to_quaternion,
|
13
|
+
)
|
14
|
+
from mani_skill.sensors.camera import CameraConfig
|
15
|
+
from mani_skill.utils import common, sapien_utils
|
16
|
+
from mani_skill.utils.building import actors
|
17
|
+
from mani_skill.utils.registration import register_env
|
18
|
+
from mani_skill.utils.scene_builder.table import TableSceneBuilder
|
19
|
+
from mani_skill.utils.structs.pose import Pose
|
20
|
+
from mani_skill.utils.logging_utils import logger
|
21
|
+
|
22
|
+
@register_env("StackPyramid-v1", max_episode_steps=250)
|
23
|
+
class StackPyramidEnv(BaseEnv):
|
24
|
+
"""
|
25
|
+
**Task Description:**
|
26
|
+
- The goal is to pick up a red cube, place it next to the green cube, and stack the blue cube on top of the red and green cube without it falling off.
|
27
|
+
|
28
|
+
**Randomizations:**
|
29
|
+
- all cubes have their z-axis rotation randomized
|
30
|
+
- all cubes have their xy positions on top of the table scene randomized. The positions are sampled such that the cubes do not collide with each other
|
31
|
+
|
32
|
+
**Success Conditions:**
|
33
|
+
- the blue cube is static
|
34
|
+
- the blue cube is on top of both the red and green cube (to within half of the cube size)
|
35
|
+
- none of the red, green, blue cubes are grasped by the robot (robot must let go of the cubes)
|
36
|
+
|
37
|
+
_sample_video_link = "https://github.com/haosulab/ManiSkill/raw/main/figures/environment_demos/StackPyramid-v1_rt.mp4"
|
38
|
+
|
39
|
+
"""
|
40
|
+
|
41
|
+
SUPPORTED_ROBOTS = ["panda_wristcam", "panda", "fetch"]
|
42
|
+
SUPPORTED_REWARD_MODES = ["none", "sparse"]
|
43
|
+
|
44
|
+
agent: Union[Panda, Fetch]
|
45
|
+
|
46
|
+
def __init__(
|
47
|
+
self, *args, robot_uids="panda_wristcam", robot_init_qpos_noise=0.02, **kwargs
|
48
|
+
):
|
49
|
+
self.robot_init_qpos_noise = robot_init_qpos_noise
|
50
|
+
super().__init__(*args, robot_uids=robot_uids, **kwargs)
|
51
|
+
|
52
|
+
@property
|
53
|
+
def _default_sensor_configs(self):
|
54
|
+
pose = sapien_utils.look_at(eye=[0.3, 0, 0.4], target=[-0.05, 0, 0.1])
|
55
|
+
return [CameraConfig("base_camera", pose, 128, 128, np.pi / 2, 0.01, 100)]
|
56
|
+
|
57
|
+
@property
|
58
|
+
def _default_human_render_camera_configs(self):
|
59
|
+
pose = sapien_utils.look_at([0.6, 0.7, 0.6], [0.0, 0.0, 0.35])
|
60
|
+
return CameraConfig("render_camera", pose, 512, 512, 1, 0.01, 100)
|
61
|
+
|
62
|
+
|
63
|
+
def _load_scene(self, options: dict):
|
64
|
+
self.cube_half_size = common.to_tensor([0.02] * 3)
|
65
|
+
self.table_scene = TableSceneBuilder(
|
66
|
+
env=self, robot_init_qpos_noise=self.robot_init_qpos_noise
|
67
|
+
)
|
68
|
+
self.table_scene.build()
|
69
|
+
self.cubeA = actors.build_cube(
|
70
|
+
self.scene, half_size=0.02, color=[1, 0, 0, 1], name="cubeA", initial_pose=sapien.Pose(p=[0, 0, 0.2])
|
71
|
+
)
|
72
|
+
self.cubeB = actors.build_cube(
|
73
|
+
self.scene, half_size=0.02, color=[0, 1, 0, 1], name="cubeB", initial_pose=sapien.Pose(p=[1, 0, 0.2])
|
74
|
+
)
|
75
|
+
self.cubeC = actors.build_cube(
|
76
|
+
self.scene, half_size=0.02, color=[0, 0, 1, 1], name="cubeC", initial_pose=sapien.Pose(p=[-1, 0, 0.2])
|
77
|
+
)
|
78
|
+
|
79
|
+
def _initialize_episode(self, env_idx: torch.Tensor, options: dict):
|
80
|
+
with torch.device(self.device):
|
81
|
+
b = len(env_idx)
|
82
|
+
self.table_scene.initialize(env_idx)
|
83
|
+
|
84
|
+
xyz = torch.zeros((b, 3), device=self.device)
|
85
|
+
xyz[:, 2] = 0.02
|
86
|
+
xy = xyz[:, :2]
|
87
|
+
region = [[-0.1, -0.2], [0.1, 0.2]]
|
88
|
+
sampler = randomization.UniformPlacementSampler(bounds=region, batch_size=b, device=self.device)
|
89
|
+
radius = torch.linalg.norm(torch.tensor([0.02, 0.02]))
|
90
|
+
cubeA_xy = xy + sampler.sample(radius, 100)
|
91
|
+
cubeB_xy = xy + sampler.sample(radius, 100, verbose=False)
|
92
|
+
cubeC_xy = xy + sampler.sample(radius, 100, verbose=False)
|
93
|
+
|
94
|
+
# Cube A
|
95
|
+
xyz[:, :2] = cubeA_xy
|
96
|
+
|
97
|
+
qs = randomization.random_quaternions(
|
98
|
+
b,
|
99
|
+
lock_x=True,
|
100
|
+
lock_y=True,
|
101
|
+
lock_z=False,
|
102
|
+
)
|
103
|
+
|
104
|
+
self.cubeA.set_pose(Pose.create_from_pq(p=xyz.clone(), q=qs))
|
105
|
+
|
106
|
+
# Cube B
|
107
|
+
xyz[:, :2] = cubeB_xy
|
108
|
+
qs = randomization.random_quaternions(
|
109
|
+
b,
|
110
|
+
lock_x=True,
|
111
|
+
lock_y=True,
|
112
|
+
lock_z=False,
|
113
|
+
)
|
114
|
+
self.cubeB.set_pose(Pose.create_from_pq(p=xyz.clone(), q=qs))
|
115
|
+
|
116
|
+
# Cube C
|
117
|
+
xyz[:, :2] = cubeC_xy
|
118
|
+
qs = randomization.random_quaternions(
|
119
|
+
b,
|
120
|
+
lock_x=True,
|
121
|
+
lock_y=True,
|
122
|
+
lock_z=False,
|
123
|
+
)
|
124
|
+
self.cubeC.set_pose(Pose.create_from_pq(p=xyz, q=qs))
|
125
|
+
|
126
|
+
def evaluate(self):
|
127
|
+
pos_A = self.cubeA.pose.p
|
128
|
+
pos_B = self.cubeB.pose.p
|
129
|
+
pos_C = self.cubeC.pose.p
|
130
|
+
|
131
|
+
offset_AB = pos_A - pos_B
|
132
|
+
offset_BC = pos_B - pos_C
|
133
|
+
offset_AC = pos_A - pos_C
|
134
|
+
|
135
|
+
def evaluate_cube_distance(offset, cube_a, cube_b, top_or_next):
|
136
|
+
xy_flag = (torch.linalg.norm(offset[..., :2], axis=1)
|
137
|
+
<= torch.linalg.norm(2*self.cube_half_size[:2])
|
138
|
+
+ 0.005
|
139
|
+
)
|
140
|
+
z_flag = torch.abs(offset[..., 2]) > 0.02
|
141
|
+
if top_or_next == "top":
|
142
|
+
is_cubeA_on_cubeB = torch.logical_and(xy_flag, z_flag)
|
143
|
+
elif top_or_next == "next_to":
|
144
|
+
is_cubeA_on_cubeB = xy_flag
|
145
|
+
else:
|
146
|
+
return NotImplementedError(f"Expect top_or_next to be either 'top' or 'next_to', got {top_or_next}")
|
147
|
+
|
148
|
+
is_cubeA_static = cube_a.is_static(lin_thresh=1e-2, ang_thresh=0.5)
|
149
|
+
is_cubeA_grasped = self.agent.is_grasping(cube_a)
|
150
|
+
|
151
|
+
success = is_cubeA_on_cubeB & is_cubeA_static & (~is_cubeA_grasped)
|
152
|
+
return success.bool()
|
153
|
+
|
154
|
+
success_A_B = evaluate_cube_distance(offset_AB, self.cubeA, self.cubeB, "next_to")
|
155
|
+
success_C_B = evaluate_cube_distance(offset_BC, self.cubeC, self.cubeB, "top")
|
156
|
+
success_C_A = evaluate_cube_distance(offset_AC, self.cubeC, self.cubeA, "top")
|
157
|
+
success = torch.logical_and(success_A_B, torch.logical_and(success_C_B, success_C_A))
|
158
|
+
return {
|
159
|
+
"success": success,
|
160
|
+
}
|
161
|
+
|
162
|
+
def _get_obs_extra(self, info: Dict):
|
163
|
+
obs = dict(tcp_pose=self.agent.tcp.pose.raw_pose)
|
164
|
+
if "state" in self.obs_mode:
|
165
|
+
obs.update(
|
166
|
+
cubeA_pose=self.cubeA.pose.raw_pose,
|
167
|
+
cubeB_pose=self.cubeB.pose.raw_pose,
|
168
|
+
cubeC_pose=self.cubeC.pose.raw_pose,
|
169
|
+
tcp_to_cubeA_pos=self.cubeA.pose.p - self.agent.tcp.pose.p,
|
170
|
+
tcp_to_cubeB_pos=self.cubeB.pose.p - self.agent.tcp.pose.p,
|
171
|
+
tcp_to_cubeC_pos=self.cubeC.pose.p - self.agent.tcp.pose.p,
|
172
|
+
cubeA_to_cubeB_pos=self.cubeB.pose.p - self.cubeA.pose.p,
|
173
|
+
cubeB_to_cubeC_pos=self.cubeC.pose.p - self.cubeB.pose.p,
|
174
|
+
cubeA_to_cubeC_pos=self.cubeC.pose.p - self.cubeA.pose.p,
|
175
|
+
)
|
176
|
+
return obs
|
177
|
+
|
@@ -9,7 +9,7 @@ from tqdm import tqdm
|
|
9
9
|
import os.path as osp
|
10
10
|
from mani_skill.utils.wrappers.record import RecordEpisode
|
11
11
|
from mani_skill.trajectory.merge_trajectory import merge_trajectories
|
12
|
-
from mani_skill.examples.motionplanning.panda.solutions import solvePushCube, solvePickCube, solveStackCube, solvePegInsertionSide, solvePlugCharger, solvePullCubeTool, solveLiftPegUpright, solvePullCube, solveDrawTriangle, solveDrawSVG, solvePlaceSphere
|
12
|
+
from mani_skill.examples.motionplanning.panda.solutions import solvePushCube, solvePickCube, solveStackCube, solvePegInsertionSide, solvePlugCharger, solvePullCubeTool, solveLiftPegUpright, solvePullCube, solveDrawTriangle, solveDrawSVG, solvePlaceSphere, solveStackPyramid
|
13
13
|
MP_SOLUTIONS = {
|
14
14
|
"DrawTriangle-v1": solveDrawTriangle,
|
15
15
|
"PickCube-v1": solvePickCube,
|
@@ -21,7 +21,8 @@ MP_SOLUTIONS = {
|
|
21
21
|
"PullCubeTool-v1": solvePullCubeTool,
|
22
22
|
"LiftPegUpright-v1": solveLiftPegUpright,
|
23
23
|
"PullCube-v1": solvePullCube,
|
24
|
-
"DrawSVG-v1" : solveDrawSVG
|
24
|
+
"DrawSVG-v1" : solveDrawSVG,
|
25
|
+
"StackPyramid-v1": solveStackPyramid,
|
25
26
|
}
|
26
27
|
def parse_args(args=None):
|
27
28
|
parser = argparse.ArgumentParser()
|
@@ -8,4 +8,5 @@ from .pull_cube_tool import solve as solvePullCubeTool
|
|
8
8
|
from .lift_peg_upright import solve as solveLiftPegUpright
|
9
9
|
from .pull_cube import solve as solvePullCube
|
10
10
|
from .draw_svg import solve as solveDrawSVG
|
11
|
-
from .draw_triangle import solve as solveDrawTriangle
|
11
|
+
from .draw_triangle import solve as solveDrawTriangle
|
12
|
+
from .stack_pyramid import solve as solveStackPyramid
|
@@ -0,0 +1,135 @@
|
|
1
|
+
import argparse
|
2
|
+
import gymnasium as gym
|
3
|
+
import numpy as np
|
4
|
+
import sapien
|
5
|
+
from transforms3d.euler import euler2quat
|
6
|
+
|
7
|
+
from mani_skill.envs.tasks import StackPyramidEnv
|
8
|
+
from mani_skill.examples.motionplanning.panda.motionplanner import \
|
9
|
+
PandaArmMotionPlanningSolver
|
10
|
+
from mani_skill.examples.motionplanning.panda.utils import (
|
11
|
+
compute_grasp_info_by_obb, get_actor_obb)
|
12
|
+
from mani_skill.utils.wrappers.record import RecordEpisode
|
13
|
+
from mani_skill.utils.structs import Pose
|
14
|
+
|
15
|
+
def solve(env: StackPyramidEnv, seed=None, debug=False, vis=False):
|
16
|
+
env.reset(seed=seed)
|
17
|
+
assert env.unwrapped.control_mode in [
|
18
|
+
"pd_joint_pos",
|
19
|
+
"pd_joint_pos_vel",
|
20
|
+
], env.unwrapped.control_mode
|
21
|
+
planner = PandaArmMotionPlanningSolver(
|
22
|
+
env,
|
23
|
+
debug=debug,
|
24
|
+
vis=vis,
|
25
|
+
base_pose=env.unwrapped.agent.robot.pose,
|
26
|
+
visualize_target_grasp_pose=vis,
|
27
|
+
print_env_info=False,
|
28
|
+
)
|
29
|
+
FINGER_LENGTH = 0.025
|
30
|
+
env = env.unwrapped
|
31
|
+
|
32
|
+
moving_cube = env.cubeA
|
33
|
+
target_cube = env.cubeB
|
34
|
+
|
35
|
+
|
36
|
+
# -------------------------------------------------------------------------- #
|
37
|
+
# Move the specified cube to be next to the other cube
|
38
|
+
# -------------------------------------------------------------------------- #
|
39
|
+
# Move Gripper to the specified cube
|
40
|
+
obb = get_actor_obb(moving_cube)
|
41
|
+
approaching = np.array([0, 0, -1])
|
42
|
+
target_closing = env.agent.tcp.pose.to_transformation_matrix()[0, :3, 1].cpu().numpy()
|
43
|
+
grasp_info = compute_grasp_info_by_obb(
|
44
|
+
obb,
|
45
|
+
approaching=approaching,
|
46
|
+
target_closing=target_closing,
|
47
|
+
depth=FINGER_LENGTH,
|
48
|
+
)
|
49
|
+
closing, center = grasp_info["closing"], grasp_info["center"]
|
50
|
+
distance = np.linalg.norm(moving_cube.pose.sp.p - target_cube.pose.sp.p)
|
51
|
+
|
52
|
+
need_move_a_b = (distance > 0.07)
|
53
|
+
if need_move_a_b:
|
54
|
+
planner.close_gripper()
|
55
|
+
grasp_pose = env.agent.build_grasp_pose(approaching, closing, moving_cube.pose.sp.p)
|
56
|
+
|
57
|
+
# Reach
|
58
|
+
reach_pose = grasp_pose * sapien.Pose([0, 0, -0.05])
|
59
|
+
planner.move_to_pose_with_screw(reach_pose)
|
60
|
+
|
61
|
+
# Grasp
|
62
|
+
planner.move_to_pose_with_screw(grasp_pose)
|
63
|
+
planner.close_gripper()
|
64
|
+
|
65
|
+
# Move to Goal Pose
|
66
|
+
goal_pose = sapien.Pose(target_cube.pose.sp.p * 0.8, grasp_pose.q)
|
67
|
+
planner.move_to_pose_with_screw(goal_pose)
|
68
|
+
|
69
|
+
# -------------------------------------------------------------------------- #
|
70
|
+
# Stack Cube C onto Cube A and B
|
71
|
+
# -------------------------------------------------------------------------- #
|
72
|
+
|
73
|
+
obb = get_actor_obb(env.cubeC)
|
74
|
+
target_closing = env.agent.tcp.pose.to_transformation_matrix()[0, :3, 1].cpu().numpy()
|
75
|
+
grasp_info = compute_grasp_info_by_obb(
|
76
|
+
obb,
|
77
|
+
approaching=approaching,
|
78
|
+
target_closing=target_closing,
|
79
|
+
depth=FINGER_LENGTH,
|
80
|
+
)
|
81
|
+
closing, center = grasp_info["closing"], grasp_info["center"]
|
82
|
+
grasp_pose = env.agent.build_grasp_pose(approaching, closing, center)
|
83
|
+
|
84
|
+
# Search a valid pose
|
85
|
+
angles = np.arange(0, np.pi * 2 / 3, np.pi / 2)
|
86
|
+
angles = np.repeat(angles, 2)
|
87
|
+
angles[1::2] *= -1
|
88
|
+
for angle in angles:
|
89
|
+
delta_pose = sapien.Pose(q=euler2quat(0, 0, angle))
|
90
|
+
grasp_pose2 = grasp_pose * delta_pose
|
91
|
+
res = planner.move_to_pose_with_screw(grasp_pose2, dry_run=True)
|
92
|
+
if res == -1:
|
93
|
+
continue
|
94
|
+
grasp_pose = grasp_pose2
|
95
|
+
break
|
96
|
+
else:
|
97
|
+
print("Fail to find a valid grasp pose")
|
98
|
+
|
99
|
+
# -------------------------------------------------------------------------- #
|
100
|
+
# Reach
|
101
|
+
# -------------------------------------------------------------------------- #
|
102
|
+
|
103
|
+
# planner.planner.update_attached_box([0.04, 0.04, 0.04], Pose.create(env.cubeB.pose).raw_pose.numpy().astype(np.float64).reshape(7,1))
|
104
|
+
|
105
|
+
reach_pose = grasp_pose * sapien.Pose([0, 0, -0.05])
|
106
|
+
planner.move_to_pose_with_screw(reach_pose)
|
107
|
+
if need_move_a_b:
|
108
|
+
planner.open_gripper()
|
109
|
+
|
110
|
+
# -------------------------------------------------------------------------- #
|
111
|
+
# Grasp
|
112
|
+
# -------------------------------------------------------------------------- #
|
113
|
+
planner.move_to_pose_with_screw(grasp_pose)
|
114
|
+
planner.close_gripper()
|
115
|
+
|
116
|
+
# -------------------------------------------------------------------------- #
|
117
|
+
# Lift
|
118
|
+
# -------------------------------------------------------------------------- #
|
119
|
+
lift_pose = sapien.Pose([0, 0, 0.1]) * grasp_pose
|
120
|
+
planner.move_to_pose_with_screw(lift_pose)
|
121
|
+
|
122
|
+
# -------------------------------------------------------------------------- #
|
123
|
+
# Stack
|
124
|
+
# -------------------------------------------------------------------------- #
|
125
|
+
goal_pose_A = env.cubeA.pose * sapien.Pose([0, 0, env.cube_half_size[2] * 2])
|
126
|
+
goal_pose_B = env.cubeB.pose * sapien.Pose([0, 0, env.cube_half_size[2] * 2])
|
127
|
+
goal_pose_p = (goal_pose_A.p + goal_pose_B.p)/2
|
128
|
+
offset = (goal_pose_p - env.cubeC.pose.p).cpu().numpy()[0] # remember that all data in ManiSkill is batched and a torch tensor
|
129
|
+
align_pose = sapien.Pose(lift_pose.p + offset, lift_pose.q)
|
130
|
+
planner.move_to_pose_with_screw(align_pose)
|
131
|
+
|
132
|
+
res = planner.open_gripper()
|
133
|
+
planner.close()
|
134
|
+
return res
|
135
|
+
|
{mani_skill_nightly-2025.6.28.2200.dist-info → mani_skill_nightly-2025.7.8.44.dist-info}/RECORD
RENAMED
@@ -604,7 +604,7 @@ mani_skill/envs/tasks/mobile_manipulation/robocasa/kitchen.py,sha256=fXLoTIDgk-0
|
|
604
604
|
mani_skill/envs/tasks/quadruped/__init__.py,sha256=_AHS3H9Cj2XT7--5jwW1NMmVWbZxRpdGDNXudT6OrZM,92
|
605
605
|
mani_skill/envs/tasks/quadruped/quadruped_reach.py,sha256=IggZpOlncVy-runqcX9PmD6a04JKj13tzpft63mWdQE,7355
|
606
606
|
mani_skill/envs/tasks/quadruped/quadruped_spin.py,sha256=F9HmJtZeLNpuFg3-VyO7Qdz8dBsJmCfiH0076npq4is,5205
|
607
|
-
mani_skill/envs/tasks/tabletop/__init__.py,sha256=
|
607
|
+
mani_skill/envs/tasks/tabletop/__init__.py,sha256=DJmoG6Z19yXPuLUv2mZ8UqgsMVethY_pzYspc4veRMw,791
|
608
608
|
mani_skill/envs/tasks/tabletop/assembling_kits.py,sha256=piXxTybVKrRr92VqIFIQsbra4Q3njRxBTmOGvsribHI,11933
|
609
609
|
mani_skill/envs/tasks/tabletop/lift_peg_upright.py,sha256=o6AmHyjyoT5U6IYn0tXz3MJ7PNCEqHPZf2jnFOFuW-Y,5857
|
610
610
|
mani_skill/envs/tasks/tabletop/peg_insertion_side.py,sha256=3tf9eOI4PmNGKXooZUR81AXUPuUUTgG-V4DuYxtd5dg,14033
|
@@ -621,6 +621,7 @@ mani_skill/envs/tasks/tabletop/push_cube.py,sha256=WZ4k89f8inbwbomYtJAxodQDcGUYh
|
|
621
621
|
mani_skill/envs/tasks/tabletop/push_t.py,sha256=MpANhMe6ay5Qhsipe2G1Wy-LSJqrgeOyH3M8fZW_L2c,23522
|
622
622
|
mani_skill/envs/tasks/tabletop/roll_ball.py,sha256=OujblvDphjdQBzQiCUnm_gXFwGLubpr40VT7daCWlDo,6760
|
623
623
|
mani_skill/envs/tasks/tabletop/stack_cube.py,sha256=_3auYI95uj6hMzTmHMty8pFmD5RhiVxw48MPg5BpREA,7459
|
624
|
+
mani_skill/envs/tasks/tabletop/stack_pyramid.py,sha256=erfYC1fOMYW18kP44PHt0-L6ysb63r7IALb-qCmAu7w,7224
|
624
625
|
mani_skill/envs/tasks/tabletop/turn_faucet.py,sha256=g4UQ0DQGVxEdan2jW5vX-QSsTDhoKpdQMhXP7WqVMJo,9275
|
625
626
|
mani_skill/envs/tasks/tabletop/two_robot_pick_cube.py,sha256=osuA6BFne2UkgIp8sw7JMh_83y_Ray7e30iNNJDHib0,10101
|
626
627
|
mani_skill/envs/tasks/tabletop/two_robot_stack_cube.py,sha256=lXkdS4zRE9KA4jzr9mN_Tytq24pg5WD2YlYcsvDlr4I,11973
|
@@ -668,9 +669,9 @@ mani_skill/examples/motionplanning/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQe
|
|
668
669
|
mani_skill/examples/motionplanning/panda/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
|
669
670
|
mani_skill/examples/motionplanning/panda/motionplanner.py,sha256=2GT2K2tXI9QVyhE1hOapr34vyCPRtBdOVm_MFH_OnGE,10314
|
670
671
|
mani_skill/examples/motionplanning/panda/motionplanner_stick.py,sha256=o4qwJLL7rLFsPAu856UtbtBOu8nlKJo3SLI_bFcGzUM,6148
|
671
|
-
mani_skill/examples/motionplanning/panda/run.py,sha256=
|
672
|
+
mani_skill/examples/motionplanning/panda/run.py,sha256=PM0p424MfA-wVcvXJWKlnITKGYNI_FC3CBZjIiCX37U,7438
|
672
673
|
mani_skill/examples/motionplanning/panda/utils.py,sha256=ueS0b4-gX9lnsvqet361tEi8S5cv4Liq71BWN-feEZU,3058
|
673
|
-
mani_skill/examples/motionplanning/panda/solutions/__init__.py,sha256=
|
674
|
+
mani_skill/examples/motionplanning/panda/solutions/__init__.py,sha256=a3Pglv99wemA-TjqHGMV2FBEJnhJMEt8OTniwzeAO5c,618
|
674
675
|
mani_skill/examples/motionplanning/panda/solutions/draw_svg.py,sha256=MF-THj9aAXefc6wpRJ44nk5Y_sF2P0PdWXKQhlR_pOE,1049
|
675
676
|
mani_skill/examples/motionplanning/panda/solutions/draw_triangle.py,sha256=CeRhTdPep6vgVix6SfOEBx8DRDS9Kmpo3zALEg7sK7Q,1937
|
676
677
|
mani_skill/examples/motionplanning/panda/solutions/lift_peg_upright.py,sha256=-wQ5DpT7dMffOgOkpboUNYg4odq-NuQgGUzJ0LWNIUg,3616
|
@@ -682,6 +683,7 @@ mani_skill/examples/motionplanning/panda/solutions/pull_cube.py,sha256=rQkvCRYjV
|
|
682
683
|
mani_skill/examples/motionplanning/panda/solutions/pull_cube_tool.py,sha256=g6adx921V2SOVYYFlh_gLwV5I0tnz70qCLm81oA6YhA,3609
|
683
684
|
mani_skill/examples/motionplanning/panda/solutions/push_cube.py,sha256=EynyseBJ_njMP74o9gVxqWOOqoC5j1rBc4XQzFug9EQ,1113
|
684
685
|
mani_skill/examples/motionplanning/panda/solutions/stack_cube.py,sha256=QIa280jNOJfJqqgbb5WWEBxErFPE7Mv4-_ZL9TCsRos,3280
|
686
|
+
mani_skill/examples/motionplanning/panda/solutions/stack_pyramid.py,sha256=s7IWytihZv4IvT2cuhLM0RAWoV1NEEoPKq5-E6ArA6s,5190
|
685
687
|
mani_skill/examples/motionplanning/xarm6/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
|
686
688
|
mani_skill/examples/motionplanning/xarm6/motionplanner.py,sha256=OcJ2OgY09j3kKl7tFa8GcuGGknF999I_bWZGHZF8lps,4751
|
687
689
|
mani_skill/examples/motionplanning/xarm6/run.py,sha256=yejnUUasyllXZYWpWD9ksvdjgM8o9TwGVfY24kXQxSI,7053
|
@@ -711,7 +713,7 @@ mani_skill/utils/README.md,sha256=A2UG1u5-4LLi-Fkc4lCcEBjSHwxY0xst2Xtvyw4q-0c,15
|
|
711
713
|
mani_skill/utils/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
|
712
714
|
mani_skill/utils/common.py,sha256=PYzgQRpTFnqKj2brD0mfGuOICLPsruEDXqs9D7u8Trg,13118
|
713
715
|
mani_skill/utils/download_asset.py,sha256=vP7dsho4Fc-b-Ydm9vj6opFmORa-2Svd69w1izuk5go,8060
|
714
|
-
mani_skill/utils/download_demo.py,sha256=
|
716
|
+
mani_skill/utils/download_demo.py,sha256=ndnnc1TfyuLVb-odrA50HvuZemXZf-zZlqyFTinx-mA,4467
|
715
717
|
mani_skill/utils/gym_utils.py,sha256=rAYNyxJtF1bSghi_EDPlqgnYZQwG0RklobgaPztSEvw,5922
|
716
718
|
mani_skill/utils/io_utils.py,sha256=VJ93qoHxzFWIljAp9043pJqETmEGmxzt_DoYtE5Hd_I,1615
|
717
719
|
mani_skill/utils/logging_utils.py,sha256=Iomnw2VrJ56A6kvyIm9Zhgp94Qf-WOf9WuMAGNB-2fc,1765
|
@@ -825,8 +827,8 @@ mani_skill/vector/wrappers/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJ
|
|
825
827
|
mani_skill/vector/wrappers/gymnasium.py,sha256=aNPB-2oGDLep8qzdsuTSIlwGGO0OGQAQ193LefOGoTk,7434
|
826
828
|
mani_skill/vector/wrappers/sb3.py,sha256=SlXdiEPqcNHYMhJCzA29kBU6zK7DKTe1nc0L6Z3QQtY,4722
|
827
829
|
mani_skill/viewer/__init__.py,sha256=srvDBsk4LQU75K2VIttrhiQ68p_ro7PSDqQRls2PY5c,1722
|
828
|
-
mani_skill_nightly-2025.
|
829
|
-
mani_skill_nightly-2025.
|
830
|
-
mani_skill_nightly-2025.
|
831
|
-
mani_skill_nightly-2025.
|
832
|
-
mani_skill_nightly-2025.
|
830
|
+
mani_skill_nightly-2025.7.8.44.dist-info/LICENSE,sha256=xx0jnfkXJvxRnG63LTGOxlggYnIysveWIZ6H3PNdCrQ,11357
|
831
|
+
mani_skill_nightly-2025.7.8.44.dist-info/METADATA,sha256=Ka9GaBgZrLhZD_YhqrEHuf7aGCrmHRMjf1BPffm9Xug,9269
|
832
|
+
mani_skill_nightly-2025.7.8.44.dist-info/WHEEL,sha256=tZoeGjtWxWRfdplE7E3d45VPlLNQnvbKiYnx7gwAy8A,92
|
833
|
+
mani_skill_nightly-2025.7.8.44.dist-info/top_level.txt,sha256=bkBgOVl_MZMoQx2aRFsSFEYlZLxjWlip5vtJ39FB3jA,11
|
834
|
+
mani_skill_nightly-2025.7.8.44.dist-info/RECORD,,
|
{mani_skill_nightly-2025.6.28.2200.dist-info → mani_skill_nightly-2025.7.8.44.dist-info}/LICENSE
RENAMED
File without changes
|
{mani_skill_nightly-2025.6.28.2200.dist-info → mani_skill_nightly-2025.7.8.44.dist-info}/WHEEL
RENAMED
File without changes
|
File without changes
|