mani-skill-nightly 2025.8.19.1758__py3-none-any.whl → 2025.8.28.2229__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.

Potentially problematic release.


This version of mani-skill-nightly might be problematic. Click here for more details.

@@ -1,4 +1,4 @@
1
- from dataclasses import dataclass
1
+ from dataclasses import dataclass, field
2
2
  from typing import Literal, Optional, Sequence, Union
3
3
 
4
4
  import numpy as np
@@ -9,9 +9,11 @@ from mani_skill.agents.controllers.utils.kinematics import Kinematics
9
9
  from mani_skill.utils import gym_utils, sapien_utils
10
10
  from mani_skill.utils.geometry.rotation_conversions import (
11
11
  euler_angles_to_matrix,
12
+ matrix_to_euler_angles,
12
13
  matrix_to_quaternion,
13
14
  quaternion_apply,
14
15
  quaternion_multiply,
16
+ quaternion_to_matrix,
15
17
  )
16
18
  from mani_skill.utils.structs import Pose
17
19
  from mani_skill.utils.structs.types import Array, DriveMode
@@ -72,13 +74,14 @@ class PDEEPosController(PDJointPosController):
72
74
 
73
75
  def reset(self):
74
76
  super().reset()
75
- if self._target_pose is None:
76
- self._target_pose = self.ee_pose_at_base
77
- else:
78
- # TODO (stao): this is a strange way to mask setting individual batched pose parts
79
- self._target_pose.raw_pose[self.scene._reset_mask] = (
80
- self.ee_pose_at_base.raw_pose[self.scene._reset_mask]
81
- )
77
+ if self.config.use_target:
78
+ if self._target_pose is None:
79
+ self._target_pose = self.ee_pose_at_base
80
+ else:
81
+ # TODO (stao): this is a strange way to mask setting individual batched pose parts
82
+ self._target_pose.raw_pose[
83
+ self.scene._reset_mask
84
+ ] = self.ee_pose_at_base.raw_pose[self.scene._reset_mask]
82
85
 
83
86
  def compute_target_pose(self, prev_ee_pose_at_base, action):
84
87
  # Keep the current rotation and change the position
@@ -105,14 +108,22 @@ class PDEEPosController(PDJointPosController):
105
108
  else:
106
109
  prev_ee_pose_at_base = self.ee_pose_at_base
107
110
 
108
- self._target_pose = self.compute_target_pose(prev_ee_pose_at_base, action)
111
+ # we only need to use the target pose for CPU sim or if a virtual target is enabled
112
+ # if we have no virtual target and using the gpu sim we can directly use the given action without
113
+ # having to recompute the new target pose based on the action delta.
114
+ ik_via_target_pose = self.config.use_target or not self.scene.gpu_sim_enabled
115
+ if ik_via_target_pose:
116
+ self._target_pose = self.compute_target_pose(prev_ee_pose_at_base, action)
109
117
  pos_only = type(self.config) == PDEEPosControllerConfig
118
+ if pos_only:
119
+ action = torch.hstack([action, torch.zeros(action.shape[0], 3, device=self.device)])
120
+
110
121
  self._target_qpos = self.kinematics.compute_ik(
111
- self._target_pose,
112
- self.articulation.get_qpos(),
113
- pos_only=pos_only,
114
- action=action,
115
- use_delta_ik_solver=self.config.use_delta and not self.config.use_target,
122
+ pose=self._target_pose if ik_via_target_pose else action,
123
+ q0=self.articulation.get_qpos(),
124
+ is_delta_pose=not ik_via_target_pose and self.config.use_delta,
125
+ current_pose=self.ee_pose_at_base,
126
+ solver_config=self.config.delta_solver_config,
116
127
  )
117
128
  if self._target_qpos is None:
118
129
  self._target_qpos = self._start_qpos
@@ -175,6 +186,10 @@ class PDEEPosControllerConfig(ControllerConfig):
175
186
  interpolate: bool = False
176
187
  normalize_action: bool = True
177
188
  """Whether to normalize each action dimension into a range of [-1, 1]. Normally for most machine learning workflows this is recommended to be kept true."""
189
+ delta_solver_config: dict = field(
190
+ default_factory=lambda: dict(type="levenberg_marquardt", alpha=1.0)
191
+ )
192
+ """Configuration for the delta IK solver. Default is `dict(type="levenberg_marquardt", alpha=1.0)`. type can be one of "levenberg_marquardt" or "pseudo_inverse". alpha is a scaling term applied to the delta joint positions generated by the solver. Generally levenberg_marquardt is faster and more accurate than pseudo_inverse and is the recommended option, see https://github.com/haosulab/ManiSkill/issues/955#issuecomment-2742253342 for some analysis on performance."""
178
193
  drive_mode: Union[Sequence[DriveMode], DriveMode] = "force"
179
194
  controller_cls = PDEEPosController
180
195
 
@@ -4,7 +4,9 @@ Code for kinematics utilities on CPU/GPU
4
4
 
5
5
  from contextlib import contextmanager, redirect_stderr, redirect_stdout
6
6
  from os import devnull
7
- from typing import List
7
+ from typing import List, Optional, Union
8
+
9
+ from mani_skill.utils.geometry import rotation_conversions
8
10
 
9
11
  try:
10
12
  import pytorch_kinematics as pk
@@ -182,62 +184,69 @@ class Kinematics:
182
184
 
183
185
  def compute_ik(
184
186
  self,
185
- target_pose: Pose,
187
+ pose: Union[Pose, torch.Tensor],
186
188
  q0: torch.Tensor,
187
- pos_only: bool = False,
188
- action=None,
189
- use_delta_ik_solver: bool = False,
189
+ is_delta_pose: bool = False,
190
+ current_pose: Optional[Pose] = None,
191
+ solver_config: dict = dict(type="levenberg_marquardt", solver_iterations=1, alpha=1.0),
190
192
  ):
191
- """Given a target pose, via inverse kinematics compute the target joint positions that will achieve the target pose
193
+ """Given a target pose, initial joint positions, this computes the target joint positions that will achieve the target pose.
194
+ For optimization you can also provide the delta pose instead and specify is_delta_pose=True.
192
195
 
193
196
  Args:
194
- target_pose (Pose): target pose of the end effector in the world frame. note this is not relative to the robot base frame!
195
- q0 (torch.Tensor): initial joint positions of every active joint in the articulation
196
- pos_only (bool): if True, only the position of the end link is considered in the IK computation
197
- action (torch.Tensor): delta action to be applied to the articulation. Used for fast delta IK solutions on the GPU.
198
- use_delta_ik_solver (bool): If true, returns the target joint positions that correspond with a delta IK solution. This is specifically
199
- used for GPU simulation to determine which GPU IK algorithm to use.
197
+ pose (Pose): target pose in the world frame. Note this is not relative to the robot base frame!
198
+ q0 (torch.Tensor): initial joint positions of each active joint in the articulation. Note that this function will mask out the joints that are not kinematically relevant.
199
+ is_delta_pose (bool): if True, the `pose` parameter should be a delta pose. It can also be a tensor of shape (N, 6) with the first 3 channels for translation and the last 3 channels for rotation in the euler angle format.
200
+ current_pose (Optional[Pose]): current pose of the controlled link in the world frame. This is used to optimize the function by avoiding computing the current pose from q0 to compute the delta pose. If is_delta_pose is False, this is not used.
201
+ solver_config (dict): configuration for the IK solver. Default is `dict(type="levenberg_marquardt", alpha=1.0)`. type can be one of "levenberg_marquardt" or "pseudo_inverse". alpha is a scaling term applied to the delta joint positions generated by the solver.
200
202
  """
203
+ assert isinstance(pose, Pose) or pose.shape[1] == 6, "pose must be a Pose or a tensor with shape (N, 6)"
201
204
  if self.use_gpu_ik:
205
+ B = pose.shape[0]
202
206
  q0 = q0[:, self.active_ancestor_joint_idxs]
203
- if not use_delta_ik_solver:
204
- tf = pk.Transform3d(
205
- pos=target_pose.p,
206
- rot=target_pose.q,
207
- device=self.device,
208
- )
209
- self.pik.initial_config = q0 # shape (num_retries, active_ancestor_dof)
210
- result = self.pik.solve(
211
- tf
212
- ) # produce solutions in shape (B, num_retries/initial_configs, active_ancestor_dof)
213
- # TODO return mask for invalid solutions. CPU returns None at the moment
214
- return result.solutions[:, 0, :]
207
+ if not is_delta_pose:
208
+ if current_pose is None:
209
+ current_pose = self.pk_chain.forward_kinematics(q0).get_matrix()
210
+ current_pose = Pose.create_from_pq(current_pose[:, :3, 3], rotation_conversions.matrix_to_quaternion(current_pose[:, :3, :3]))
211
+ if isinstance(pose, torch.Tensor):
212
+ target_pos, target_rot = pose[:, 0:3], pose[:, 3:6]
213
+ target_quat = rotation_conversions.matrix_to_quaternion(
214
+ rotation_conversions.euler_angles_to_matrix(target_rot, "XYZ")
215
+ )
216
+ pose = Pose.create_from_pq(target_pos, target_quat)
217
+ if isinstance(pose, Pose):
218
+ # the following assumes root_translation:root_aligned_body_rotation control frame
219
+ translation = pose.p - current_pose.p
220
+ quaternion = rotation_conversions.quaternion_multiply(pose.q, rotation_conversions.quaternion_invert(current_pose.q))
221
+ pose = Pose.create_from_pq(translation, quaternion)
222
+ if isinstance(pose, Pose):
223
+ delta_pose = torch.zeros((B, 6), device=self.device, dtype=torch.float32)
224
+ delta_pose[:, 0:3] = pose.p
225
+ delta_pose[:, 3:6] = rotation_conversions.matrix_to_euler_angles(rotation_conversions.quaternion_to_matrix(pose.q), "XYZ")
215
226
  else:
216
- jacobian = self.pk_chain.jacobian(q0)
217
- # code commented out below is the fast kinematics method
218
- # jacobian = (
219
- # self.fast_kinematics_model.jacobian_mixed_frame_pytorch(
220
- # self.articulation.get_qpos()[:, self.active_ancestor_joint_idxs]
221
- # )
222
- # .view(-1, len(self.active_ancestor_joints), 6)
223
- # .permute(0, 2, 1)
224
- # )
225
- # jacobian = jacobian[:, :, self.qmask]
226
- if pos_only:
227
- jacobian = jacobian[:, 0:3]
228
-
229
- # NOTE (arth): use only the parts of the jacobian that correspond to the active joints
230
- jacobian = jacobian[:, :, self.qmask]
227
+ delta_pose = pose
228
+ jacobian = self.pk_chain.jacobian(q0)[:, :, self.qmask]
229
+ if solver_config["type"] == "levenberg_marquardt":
230
+ lambd = 0.0001 # Regularization parameter to ensure J^T * J is non-singular.
231
+ J_T = jacobian.transpose(1, 2)
232
+ lfs_A = torch.bmm(J_T, jacobian) + lambd * torch.eye(
233
+ len(self.qmask), device=self.device
234
+ )
235
+ rhs_B = torch.bmm(J_T, delta_pose.unsqueeze(-1))
236
+ delta_joint_pos = torch.linalg.solve(lfs_A, rhs_B)
231
237
 
238
+ elif solver_config["type"] == "pseudo_inverse":
232
239
  # NOTE (stao): this method of IK is from https://mathweb.ucsd.edu/~sbuss/ResearchWeb/ikmethods/iksurvey.pdf by Samuel R. Buss
233
- delta_joint_pos = torch.linalg.pinv(jacobian) @ action.unsqueeze(-1)
240
+ delta_joint_pos = torch.linalg.pinv(jacobian) @ delta_pose.unsqueeze(-1)
234
241
 
235
- return q0[:, self.qmask] + delta_joint_pos.squeeze(-1)
242
+ return q0[:, self.qmask] + solver_config[
243
+ "alpha"
244
+ ] * delta_joint_pos.squeeze(-1)
236
245
  else:
237
246
  q0 = q0[:, self.pmodel_active_joint_indices]
238
247
  result, success, error = self.pmodel.compute_inverse_kinematics(
239
248
  self.end_link_idx,
240
- target_pose.sp,
249
+ pose.sp,
241
250
  initial_qpos=q0.cpu().numpy()[0],
242
251
  active_qmask=self.qmask,
243
252
  max_iterations=100,
@@ -102,49 +102,13 @@ class SO100(BaseAgent):
102
102
  def tcp_pose(self):
103
103
  return Pose.create_from_pq(self.tcp_pos, self.finger1_link.pose.q)
104
104
 
105
- def is_grasping(self, object: Actor, min_force=0.5, max_angle=110):
106
- """Check if the robot is grasping an object
107
-
108
- Args:
109
- object (Actor): The object to check if the robot is grasping
110
- min_force (float, optional): Minimum force before the robot is considered to be grasping the object in Newtons. Defaults to 0.5.
111
- max_angle (int, optional): Maximum angle of contact to consider grasping. Defaults to 85.
112
- """
113
- l_contact_forces = self.scene.get_pairwise_contact_forces(
114
- self.finger1_link, object
115
- )
116
- r_contact_forces = self.scene.get_pairwise_contact_forces(
117
- self.finger2_link, object
118
- )
119
- lforce = torch.linalg.norm(l_contact_forces, axis=1)
120
- rforce = torch.linalg.norm(r_contact_forces, axis=1)
121
-
122
- # direction to open the gripper
123
- ldirection = self.finger1_link.pose.to_transformation_matrix()[..., :3, 1]
124
- rdirection = -self.finger2_link.pose.to_transformation_matrix()[..., :3, 1]
125
- langle = common.compute_angle_between(ldirection, l_contact_forces)
126
- rangle = common.compute_angle_between(rdirection, r_contact_forces)
127
- lflag = torch.logical_and(
128
- lforce >= min_force, torch.rad2deg(langle) <= max_angle
129
- )
130
- rflag = torch.logical_and(
131
- rforce >= min_force, torch.rad2deg(rangle) <= max_angle
132
- )
133
- return torch.logical_and(lflag, rflag)
134
-
135
105
  def _after_loading_articulation(self):
136
106
  super()._after_loading_articulation()
137
- # self.set_colors()
138
107
  self.finger1_link = self.robot.links_map["Fixed_Jaw"]
139
108
  self.finger2_link = self.robot.links_map["Moving_Jaw"]
140
109
  self.finger1_tip = self.robot.links_map["Fixed_Jaw_tip"]
141
110
  self.finger2_tip = self.robot.links_map["Moving_Jaw_tip"]
142
111
 
143
- @property
144
- def tcp_pos(self):
145
- # computes the tool center point as the mid point between the the fixed and moving jaw's tips
146
- return (self.finger1_tip.pose.p + self.finger2_tip.pose.p) / 2
147
-
148
112
  def is_grasping(self, object: Actor, min_force=0.5, max_angle=110):
149
113
  """Check if the robot is grasping an object
150
114
 
@@ -178,3 +142,15 @@ class SO100(BaseAgent):
178
142
  def is_static(self, threshold=0.2):
179
143
  qvel = self.robot.get_qvel()[:, :-1] # exclude the gripper joint
180
144
  return torch.max(torch.abs(qvel), 1)[0] <= threshold
145
+
146
+ @staticmethod
147
+ def build_grasp_pose(approaching, closing, center):
148
+ """Build a grasp pose (panda_hand_tcp)."""
149
+ assert np.abs(1 - np.linalg.norm(approaching)) < 1e-3
150
+ assert np.abs(1 - np.linalg.norm(closing)) < 1e-3
151
+ assert np.abs(approaching @ closing) <= 1e-3
152
+ ortho = np.cross(closing, approaching)
153
+ T = np.eye(4)
154
+ T[:3, :3] = np.stack([ortho, closing, approaching], axis=1)
155
+ T[:3, 3] = center
156
+ return sapien.Pose(T)
@@ -33,7 +33,7 @@ def register_scene_builder(uid: str, override=False):
33
33
  logger.warn(
34
34
  f"Scene Builder {uid} is already registered. Skip registration."
35
35
  )
36
- return scene_builder_cls
36
+ return scene_builder_cls
37
37
 
38
38
  REGISTERED_SCENE_BUILDERS[uid] = SceneBuilderSpec(
39
39
  scene_builder_cls=scene_builder_cls
@@ -281,7 +281,7 @@ class TableSceneBuilder(SceneBuilder):
281
281
  qpos = self.env.agent.keyframes["ready_to_grasp"].qpos
282
282
  self.env.agent.reset(qpos)
283
283
  elif self.env.robot_uids == "so100":
284
- qpos = np.array([0, np.pi / 2, np.pi / 2, np.pi / 2, -np.pi / 2, 1.0])
284
+ qpos = np.array([0, 0, 0, np.pi / 2, np.pi / 2, 0])
285
285
  qpos = (
286
286
  self.env._episode_rng.normal(
287
287
  0, self.robot_init_qpos_noise, (b, len(qpos))
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: mani-skill-nightly
3
- Version: 2025.8.19.1758
3
+ Version: 2025.8.28.2229
4
4
  Summary: ManiSkill3: A Unified Benchmark for Generalizable Manipulation Skills
5
5
  Home-page: https://github.com/haosulab/ManiSkill
6
6
  Author: ManiSkill contributors
@@ -9,12 +9,12 @@ mani_skill/agents/controllers/__init__.py,sha256=tsd27dW6brQBm563CddUGtFMBNAxe_M
9
9
  mani_skill/agents/controllers/base_controller.py,sha256=JcKdQF7VN5YWzFOPwdYKShptfHVnxts78L9yPh4-Kto,13337
10
10
  mani_skill/agents/controllers/passive_controller.py,sha256=1cZp758AVuABvgWOzCeguBbbB8wJ6hF_cqN-k_vx5Kw,1322
11
11
  mani_skill/agents/controllers/pd_base_vel.py,sha256=-3ZzLZ9nRDMGHWnFE7c4reEbC3jHtQJCOx3LmArz95g,2868
12
- mani_skill/agents/controllers/pd_ee_pose.py,sha256=iCqK8q1ds7VTH4tkQleyryiBTIts70yS4SEQ0jzpMYI,12134
12
+ mani_skill/agents/controllers/pd_ee_pose.py,sha256=alYkN02OVYDbj7i1OqC6hC87o_FZ85SxHXNmBFXR-lw,13447
13
13
  mani_skill/agents/controllers/pd_joint_pos.py,sha256=dSdOu1Q-sGyG3rJnWYNNmzXW8U6_zU3zcIY4wgHRvI8,11108
14
14
  mani_skill/agents/controllers/pd_joint_pos_vel.py,sha256=wgiXmenTVIao1Tm1vtdJWTZRFJMB_yQBNd5vQaP8WXw,2489
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
- mani_skill/agents/controllers/utils/kinematics.py,sha256=FiSE1nfZejShEqvua9buzA_SCBuEP9OiAd7LpLbSp44,10415
17
+ mani_skill/agents/controllers/utils/kinematics.py,sha256=FxREZaBRjUfc7S-jf0cLhN3HivTPxhq3AnO5zHE2nyI,11920
18
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
@@ -46,7 +46,7 @@ mani_skill/agents/robots/panda/panda.py,sha256=aufC9et7TK5Ojms03ITT3cb7jsVClcbqL
46
46
  mani_skill/agents/robots/panda/panda_stick.py,sha256=YEGYLPGZFKkCTTAry4F82_fNZqrso3LdMWgBfT_RRbY,6131
47
47
  mani_skill/agents/robots/panda/panda_wristcam.py,sha256=eSw652CaA82YfetCqasHGAcUkaJ_aXJijJm6tHZmKyQ,875
48
48
  mani_skill/agents/robots/so100/__init__.py,sha256=54RRpI3ue89zbNtSKOK8JxvSaKrHt6PXQrriTN6X01c,26
49
- mani_skill/agents/robots/so100/so_100.py,sha256=WohuT8mw0fm2-mSPPZNDeZfKjuL_QaibnvkIfLZpIrA,7096
49
+ mani_skill/agents/robots/so100/so_100.py,sha256=JWfDM6f-QP-WTv-KGcHiZoaZkMWr-c4Dd9vHuU2-IpI,5896
50
50
  mani_skill/agents/robots/so100/so_100_real.py,sha256=-M1iRAe81AQgnM8XE32Q2jsFBmE87MGXgQwA138BVis,125
51
51
  mani_skill/agents/robots/stompy/__init__.py,sha256=fNuqeJqKneHPnzvjDYtzbpV3MIGGll8-CMok89hf0zo,27
52
52
  mani_skill/agents/robots/stompy/stompy.py,sha256=doBI0c4QCbjCiaHAxdngI73Ux_ISBy6N5JTgPovrX34,4052
@@ -743,7 +743,7 @@ mani_skill/utils/geometry/geometry.py,sha256=6hvxNDVLNBV5yBzHxam7hjEI2PVGvp67gFr
743
743
  mani_skill/utils/geometry/rotation_conversions.py,sha256=GmivoJ3pmXCVRDPvZRxel-RP1G_rsLLRbFYa2VTHfu8,20673
744
744
  mani_skill/utils/geometry/trimesh_utils.py,sha256=JruFftu0YPMut4Ig3ucv7lq_29dhKf1FH8Brc2nYY08,4558
745
745
  mani_skill/utils/scene_builder/__init__.py,sha256=9jJXXQYBuYPabZ_GTIskD41_JX33R5ZT8jiaQOEEf0c,40
746
- mani_skill/utils/scene_builder/registration.py,sha256=jz0CODY0myH0t1PHKwUuuGoed9dngq0l_8QPcs5Mp1Q,1508
746
+ mani_skill/utils/scene_builder/registration.py,sha256=O76fnn3XkDidXTxEhrVwWbDDJWpUZua9ge4-IGu4fEs,1512
747
747
  mani_skill/utils/scene_builder/scene_builder.py,sha256=7cmP_Em1Xi3hhltrqvtLdSvk8eHkMEgjkEfqEuqecpY,4295
748
748
  mani_skill/utils/scene_builder/ai2thor/__init__.py,sha256=kyHl6QlUDKvFJHzuPjYVnAMVKtMq0fICWLsLcBHy-v0,131
749
749
  mani_skill/utils/scene_builder/ai2thor/constants.py,sha256=Yiv7awe7MSc0CpsH5UG2rYaSuo30w4NKtcVYt7oY4KY,4027
@@ -794,7 +794,7 @@ mani_skill/utils/scene_builder/robocasa/utils/placement_samplers.py,sha256=ZUbue
794
794
  mani_skill/utils/scene_builder/robocasa/utils/scene_registry.py,sha256=16ZHhI1mgDGy3373aMVRliN8pcvrVigNJIMExyTxE1c,3770
795
795
  mani_skill/utils/scene_builder/robocasa/utils/scene_utils.py,sha256=a8HnoRtbwmqQyvLQCHUXKj951G2_wlzodW_eD_CBvsc,6293
796
796
  mani_skill/utils/scene_builder/table/__init__.py,sha256=g5qmrh4wZ7V_PuKv-ZU9RVwNQUbQhCshAFInAyRLuZc,45
797
- mani_skill/utils/scene_builder/table/scene_builder.py,sha256=fxs_Z-s9dj-CQMgrhdQReH6hzUAdvIgfat-BwYcjjIg,10364
797
+ mani_skill/utils/scene_builder/table/scene_builder.py,sha256=zSjZGjvFiu_e-P0QT6ylhV7lPwaks-neS2ZGtOHZcJw,10345
798
798
  mani_skill/utils/scene_builder/table/assets/Dining_Table_204_1.glb,sha256=IleHi35xfR8O9atKehqjWiuC9McjEFRCBKHRF85w_Tg,150524
799
799
  mani_skill/utils/scene_builder/table/assets/table.glb,sha256=yw69itZDjBFg8JXZAr9VQV-dZD-MaZChhqBSJR_nlRo,3891588
800
800
  mani_skill/utils/structs/README.md,sha256=qnYKimp_ZkgNcduURrYQxVTimNmq_usDMKoQ8VtMdCs,286
@@ -826,8 +826,8 @@ mani_skill/vector/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU
826
826
  mani_skill/vector/wrappers/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
827
827
  mani_skill/vector/wrappers/gymnasium.py,sha256=voHNmYg5Jyy-laMSC2Fd8VggQvhXw3NnfYLbD9QDXAc,7305
828
828
  mani_skill/vector/wrappers/sb3.py,sha256=SlXdiEPqcNHYMhJCzA29kBU6zK7DKTe1nc0L6Z3QQtY,4722
829
- mani_skill_nightly-2025.8.19.1758.dist-info/LICENSE,sha256=xx0jnfkXJvxRnG63LTGOxlggYnIysveWIZ6H3PNdCrQ,11357
830
- mani_skill_nightly-2025.8.19.1758.dist-info/METADATA,sha256=Ewkt0h5OQrqfFT7bTTCIMC-8adHb1eP5i0KF0giZxPU,9316
831
- mani_skill_nightly-2025.8.19.1758.dist-info/WHEEL,sha256=tZoeGjtWxWRfdplE7E3d45VPlLNQnvbKiYnx7gwAy8A,92
832
- mani_skill_nightly-2025.8.19.1758.dist-info/top_level.txt,sha256=bkBgOVl_MZMoQx2aRFsSFEYlZLxjWlip5vtJ39FB3jA,11
833
- mani_skill_nightly-2025.8.19.1758.dist-info/RECORD,,
829
+ mani_skill_nightly-2025.8.28.2229.dist-info/LICENSE,sha256=xx0jnfkXJvxRnG63LTGOxlggYnIysveWIZ6H3PNdCrQ,11357
830
+ mani_skill_nightly-2025.8.28.2229.dist-info/METADATA,sha256=4syinioe9vhNbp_fsYSOAcNa4Ap-y63218Wfyp4nOCk,9316
831
+ mani_skill_nightly-2025.8.28.2229.dist-info/WHEEL,sha256=tZoeGjtWxWRfdplE7E3d45VPlLNQnvbKiYnx7gwAy8A,92
832
+ mani_skill_nightly-2025.8.28.2229.dist-info/top_level.txt,sha256=bkBgOVl_MZMoQx2aRFsSFEYlZLxjWlip5vtJ39FB3jA,11
833
+ mani_skill_nightly-2025.8.28.2229.dist-info/RECORD,,