From 4eb7873324c5d622e48181e5e8f37e56b0fb2272 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen?= <1408354+cgokmen@users.noreply.github.com> Date: Thu, 20 Feb 2025 15:35:27 -0800 Subject: [PATCH 1/4] Fix meta link path issues --- omnigibson/object_states/particle_modifier.py | 14 ++- omnigibson/object_states/toggle.py | 13 +- omnigibson/utils/python_utils.py | 19 +++ omnigibson/utils/transform_utils.py | 113 +++++++++--------- 4 files changed, 99 insertions(+), 60 deletions(-) diff --git a/omnigibson/object_states/particle_modifier.py b/omnigibson/object_states/particle_modifier.py index d85c527bc..c4f650d2e 100644 --- a/omnigibson/object_states/particle_modifier.py +++ b/omnigibson/object_states/particle_modifier.py @@ -348,11 +348,21 @@ def overlap_callback(hit): "height": 1.0, "size": 1.0, } - mesh_prim_path = f"{self.link.prim_path}/mesh_0" - # Create a primitive shape if it doesn't already exist + # See if the mesh exists at the latest dataset's target location + mesh_prim_path = f"{self.link.prim_path}/visuals/mesh_0" pre_existing_mesh = lazy.omni.isaac.core.utils.prims.get_prim_at_path(mesh_prim_path) + + # If not, see if it exists in the legacy format's location + # TODO: Remove this after new dataset release + if pre_existing_mesh is None: + mesh_prim_path = f"{self.link.prim_path}/mesh_0" + pre_existing_mesh = lazy.omni.isaac.core.utils.prims.get_prim_at_path(mesh_prim_path) + + # Create a primitive mesh neither option exists if not pre_existing_mesh: + mesh_prim_path = f"{self.link.prim_path}/visuals/mesh_0" + # Projection mesh params must be specified in order to determine scalings assert self._projection_mesh_params is not None, ( f"Must specify projection_mesh_params for {self.obj.name}'s {self.__class__.__name__} " diff --git a/omnigibson/object_states/toggle.py b/omnigibson/object_states/toggle.py index 881c1c88b..33925c4b2 100644 --- a/omnigibson/object_states/toggle.py +++ b/omnigibson/object_states/toggle.py @@ -99,10 +99,19 @@ def _initialize(self): # Make sure this object is not cloth assert self.obj.prim_type != PrimType.CLOTH, f"Cannot create ToggledOn state for cloth object {self.obj.name}!" - mesh_prim_path = f"{self.link.prim_path}/mesh_0" + # See if the mesh exists at the latest dataset's target location + mesh_prim_path = f"{self.link.prim_path}/visuals/mesh_0" pre_existing_mesh = lazy.omni.isaac.core.utils.prims.get_prim_at_path(mesh_prim_path) - # Create a primitive mesh if it doesn't already exist + + # If not, see if it exists in the legacy format's location + # TODO: Remove this after new dataset release + if pre_existing_mesh is None: + mesh_prim_path = f"{self.link.prim_path}/mesh_0" + pre_existing_mesh = lazy.omni.isaac.core.utils.prims.get_prim_at_path(mesh_prim_path) + + # Create a primitive mesh neither option exists if not pre_existing_mesh: + mesh_prim_path = f"{self.link.prim_path}/visuals/mesh_0" self.scale = m.DEFAULT_SCALE if self.scale is None else self.scale # Note: We have to create a mesh (instead of a sphere shape) because physx complains about non-uniform # scaling for non-meshes diff --git a/omnigibson/utils/python_utils.py b/omnigibson/utils/python_utils.py index b5aac7e9e..5245cf9ac 100644 --- a/omnigibson/utils/python_utils.py +++ b/omnigibson/utils/python_utils.py @@ -9,6 +9,7 @@ from functools import wraps from hashlib import md5 from importlib import import_module +import sys import h5py import torch as th @@ -711,6 +712,24 @@ def __setattr__(self, key, value): super().__setattr__(key, value) +def torch_compile(func): + """ + Decorator to compile a function with torch.compile on Linux and torch.jit.script on Windows. This is because of poor support for torch.compile on Windows. + + Args: + func (function): Function to compile + + Returns: + function: Compiled function + """ + # If we're on Windows, return a jitscript option + if sys.platform == "win32": + return th.jit.script(func) + # Otherwise, return a torch.compile option + else: + return th.compile(func) + + def nums2array(nums, dim, dtype=th.float32): """ Converts input @nums into numpy array of length @dim. If @nums is a single number, broadcasts input to diff --git a/omnigibson/utils/transform_utils.py b/omnigibson/utils/transform_utils.py index 81415d746..5f94da696 100644 --- a/omnigibson/utils/transform_utils.py +++ b/omnigibson/utils/transform_utils.py @@ -9,6 +9,7 @@ import math from typing import Optional, Tuple +from omnigibson.utils.python_utils import torch_compile import torch PI = math.pi @@ -43,27 +44,27 @@ } -@torch.jit.script +@torch_compile def copysign(a, b): # type: (float, torch.Tensor) -> torch.Tensor a = torch.tensor(a, device=b.device, dtype=torch.float).repeat(b.shape[0]) return torch.abs(a) * torch.sign(b) -@torch.jit.script +@torch_compile def anorm(x: torch.Tensor, dim: Optional[int] = None, keepdim: bool = False) -> torch.Tensor: """Compute L2 norms along specified axes.""" return torch.norm(x, dim=dim, keepdim=keepdim) -@torch.jit.script +@torch_compile def normalize(v: torch.Tensor, dim: Optional[int] = None, eps: float = 1e-10) -> torch.Tensor: """L2 Normalize along specified axes.""" norm = anorm(v, dim=dim, keepdim=True) return v / torch.where(norm < eps, torch.full_like(norm, eps), norm) -@torch.jit.script +@torch_compile def dot(v1, v2, dim=-1, keepdim=False): """ Computes dot product between two vectors along the provided dim, optionally keeping the dimension @@ -81,7 +82,7 @@ def dot(v1, v2, dim=-1, keepdim=False): return torch.sum(v1 * v2, dim=dim, keepdim=keepdim) -@torch.jit.script +@torch_compile def unit_vector(data: torch.Tensor, dim: Optional[int] = None, out: Optional[torch.Tensor] = None) -> torch.Tensor: """ Returns tensor normalized by length, i.e. Euclidean norm, along axis. @@ -116,7 +117,7 @@ def unit_vector(data: torch.Tensor, dim: Optional[int] = None, out: Optional[tor return data -@torch.jit.script +@torch_compile def quat_apply(quat: torch.Tensor, vec: torch.Tensor) -> torch.Tensor: """ Apply a quaternion rotation to a vector (equivalent to R.from_quat(x).apply(y)) @@ -161,7 +162,7 @@ def quat_apply(quat: torch.Tensor, vec: torch.Tensor) -> torch.Tensor: return result.squeeze() -@torch.jit.script +@torch_compile def convert_quat(q: torch.Tensor, to: str = "xyzw") -> torch.Tensor: """ Converts quaternion from one convention to another. @@ -183,7 +184,7 @@ def convert_quat(q: torch.Tensor, to: str = "xyzw") -> torch.Tensor: raise ValueError("convert_quat: choose a valid `to` argument (xyzw or wxyz)") -@torch.jit.script +@torch_compile def quat_multiply(quaternion1: torch.Tensor, quaternion0: torch.Tensor) -> torch.Tensor: """ Return multiplication of two quaternions (q1 * q0). @@ -209,7 +210,7 @@ def quat_multiply(quaternion1: torch.Tensor, quaternion0: torch.Tensor) -> torch ) -@torch.jit.script +@torch_compile def quat_conjugate(quaternion: torch.Tensor) -> torch.Tensor: """ Return conjugate of quaternion. @@ -223,7 +224,7 @@ def quat_conjugate(quaternion: torch.Tensor) -> torch.Tensor: return torch.cat([-quaternion[:3], quaternion[3:]]) -@torch.jit.script +@torch_compile def quat_inverse(quaternion: torch.Tensor) -> torch.Tensor: """ Return inverse of quaternion. @@ -243,7 +244,7 @@ def quat_inverse(quaternion: torch.Tensor) -> torch.Tensor: return quat_conjugate(quaternion) / torch.dot(quaternion, quaternion) -@torch.jit.script +@torch_compile def quat_distance(quaternion1, quaternion0): """ Returns distance between two quaternions, such that distance * quaternion0 = quaternion1 @@ -258,7 +259,7 @@ def quat_distance(quaternion1, quaternion0): return quat_multiply(quaternion1, quat_inverse(quaternion0)) -@torch.jit.script +@torch_compile def quat_slerp(quat0, quat1, frac, shortestpath=True, eps=1.0e-15): """ Return spherical linear interpolation between two quaternions. @@ -310,7 +311,7 @@ def quat_slerp(quat0, quat1, frac, shortestpath=True, eps=1.0e-15): return val.reshape(list(quat_shape)) -@torch.jit.script +@torch_compile def random_quaternion(num_quaternions: int = 1) -> torch.Tensor: """ Generate random rotation quaternions, uniformly distributed over SO(3). @@ -335,7 +336,7 @@ def random_quaternion(num_quaternions: int = 1) -> torch.Tensor: return quaternions -@torch.jit.script +@torch_compile def random_axis_angle(angle_limit: float = 2.0 * math.pi): """ Samples an axis-angle rotation by first sampling a random axis @@ -357,7 +358,7 @@ def random_axis_angle(angle_limit: float = 2.0 * math.pi): return random_axis, random_angle.item() -@torch.jit.script +@torch_compile def quat2mat(quaternion): """ Convert quaternions into rotation matrices. @@ -400,7 +401,7 @@ def quat2mat(quaternion): return rmat -@torch.jit.script +@torch_compile def mat2quat(rmat: torch.Tensor) -> torch.Tensor: """ Converts given rotation matrix to quaternion. @@ -485,7 +486,7 @@ def mat2quat_batch(rmat: torch.Tensor) -> torch.Tensor: return mat2quat(rmat) -@torch.jit.script +@torch_compile def mat2pose(hmat): """ Converts a homogeneous 4x4 matrix into pose. @@ -507,7 +508,7 @@ def mat2pose(hmat): return pos, orn -@torch.jit.script +@torch_compile def vec2quat(vec: torch.Tensor, up: torch.Tensor = torch.tensor([0.0, 0.0, 1.0])) -> torch.Tensor: """ Converts given 3d-direction vector @vec to quaternion orientation with respect to another direction vector @up @@ -536,7 +537,7 @@ def vec2quat(vec: torch.Tensor, up: torch.Tensor = torch.tensor([0.0, 0.0, 1.0]) return mat2quat(rmat) -@torch.jit.script +@torch_compile def euler2quat(euler: torch.Tensor) -> torch.Tensor: """ Converts euler angles into quaternion form @@ -574,7 +575,7 @@ def euler2quat(euler: torch.Tensor) -> torch.Tensor: return torch.stack([qx, qy, qz, qw], dim=-1) -@torch.jit.script +@torch_compile def quat2euler(q): single_dim = q.dim() == 1 @@ -603,7 +604,7 @@ def quat2euler(q): return euler -@torch.jit.script +@torch_compile def euler2mat(euler): """ Converts euler angles into rotation matrix form @@ -627,7 +628,7 @@ def euler2mat(euler): return quat2mat(quat) -@torch.jit.script +@torch_compile def mat2euler(rmat): """ Converts given rotation matrix to euler angles in radian. @@ -653,7 +654,7 @@ def mat2euler(rmat): return torch.stack([roll, pitch, yaw], dim=-1) -@torch.jit.script +@torch_compile def pose2mat(pose: Tuple[torch.Tensor, torch.Tensor]) -> torch.Tensor: pos, orn = pose @@ -672,7 +673,7 @@ def pose2mat(pose: Tuple[torch.Tensor, torch.Tensor]) -> torch.Tensor: return homo_pose_mat -@torch.jit.script +@torch_compile def quat2axisangle(quat): """ Converts quaternion to axis-angle format. @@ -706,7 +707,7 @@ def quat2axisangle(quat): return ret -@torch.jit.script +@torch_compile def axisangle2quat(vec, eps=1e-6): """ Converts scaled axis-angle to quat. @@ -745,7 +746,7 @@ def axisangle2quat(vec, eps=1e-6): return quat -@torch.jit.script +@torch_compile def pose_in_A_to_pose_in_B(pose_A, pose_A_in_B): """ Converts a homogenous matrix corresponding to a point C in frame A @@ -767,7 +768,7 @@ def pose_in_A_to_pose_in_B(pose_A, pose_A_in_B): return torch.matmul(pose_A_in_B, pose_A) -@torch.jit.script +@torch_compile def pose_inv(pose_mat): """ Computes the inverse of a homogeneous matrix corresponding to the pose of some @@ -800,7 +801,7 @@ def pose_inv(pose_mat): return pose_inv -@torch.jit.script +@torch_compile def pose_transform(pos1, quat1, pos0, quat0): """ Conducts forward transform from pose (pos0, quat0) to pose (pos1, quat1): @@ -826,7 +827,7 @@ def pose_transform(pos1, quat1, pos0, quat0): return mat2pose(mat1 @ mat0) -@torch.jit.script +@torch_compile def invert_pose_transform(pos, quat): """ Inverts a pose transform @@ -847,7 +848,7 @@ def invert_pose_transform(pos, quat): return mat2pose(pose_inv(mat)) -@torch.jit.script +@torch_compile def relative_pose_transform(pos1, quat1, pos0, quat0): """ Computes relative forward transform from pose (pos0, quat0) to pose (pos1, quat1), i.e.: solves: @@ -873,7 +874,7 @@ def relative_pose_transform(pos1, quat1, pos0, quat0): return mat2pose(pose_inv(mat0) @ mat1) -@torch.jit.script +@torch_compile def _skew_symmetric_translation(pos_A_in_B): """ Helper function to get a skew symmetric translation matrix for converting quantities @@ -896,7 +897,7 @@ def _skew_symmetric_translation(pos_A_in_B): ) -@torch.jit.script +@torch_compile def vel_in_A_to_vel_in_B(vel_A, ang_vel_A, pose_A_in_B): """ Converts linear and angular velocity of a point in frame A to the equivalent in frame B. @@ -920,7 +921,7 @@ def vel_in_A_to_vel_in_B(vel_A, ang_vel_A, pose_A_in_B): return vel_B, ang_vel_B -@torch.jit.script +@torch_compile def force_in_A_to_force_in_B(force_A, torque_A, pose_A_in_B): """ Converts linear and rotational force at a point in frame A to the equivalent in frame B. @@ -944,7 +945,7 @@ def force_in_A_to_force_in_B(force_A, torque_A, pose_A_in_B): return force_B, torque_B -@torch.jit.script +@torch_compile def rotation_matrix(angle: float, direction: torch.Tensor) -> torch.Tensor: """ Returns a 3x3 rotation matrix to rotate about the given axis. @@ -981,7 +982,7 @@ def rotation_matrix(angle: float, direction: torch.Tensor) -> torch.Tensor: return R -@torch.jit.script +@torch_compile def transformation_matrix(angle: float, direction: torch.Tensor, point: Optional[torch.Tensor] = None) -> torch.Tensor: """ Returns a 4x4 homogeneous transformation matrix to rotate about axis defined by point and direction. @@ -1004,7 +1005,7 @@ def transformation_matrix(angle: float, direction: torch.Tensor, point: Optional return M -@torch.jit.script +@torch_compile def clip_translation(dpos, limit): """ Limits a translation (delta position) to a specified limit @@ -1025,7 +1026,7 @@ def clip_translation(dpos, limit): return (dpos * limit / input_norm, True) if input_norm > limit else (dpos, False) -@torch.jit.script +@torch_compile def clip_rotation(quat, limit): """ Limits a (delta) rotation to a specified limit @@ -1069,7 +1070,7 @@ def clip_rotation(quat, limit): return quat, clipped -@torch.jit.script +@torch_compile def make_pose(translation, rotation): """ Makes a homogeneous pose matrix from a translation vector and a rotation matrix. @@ -1088,7 +1089,7 @@ def make_pose(translation, rotation): return pose -@torch.jit.script +@torch_compile def get_orientation_error(desired, current): """ This function calculates a 3-dimensional orientation error vector, where inputs are quaternions @@ -1109,7 +1110,7 @@ def get_orientation_error(desired, current): return (q_r[:, 0:3] * torch.sign(q_r[:, 3]).unsqueeze(-1)).reshape(list(input_shape) + [3]) -@torch.jit.script +@torch_compile def get_orientation_diff_in_radian(orn0: torch.Tensor, orn1: torch.Tensor) -> torch.Tensor: """ Returns the difference between two quaternion orientations in radians. @@ -1131,7 +1132,7 @@ def get_orientation_diff_in_radian(orn0: torch.Tensor, orn1: torch.Tensor) -> to return torch.norm(axis_angle) -@torch.jit.script +@torch_compile def get_pose_error(target_pose, current_pose): """ Computes the error corresponding to target pose - current pose as a 6-dim vector. @@ -1166,7 +1167,7 @@ def get_pose_error(target_pose, current_pose): return error -@torch.jit.script +@torch_compile def matrix_inverse(matrix): """ Helper function to have an efficient matrix inversion function. @@ -1180,7 +1181,7 @@ def matrix_inverse(matrix): return torch.linalg.inv_ex(matrix).inverse -@torch.jit.script +@torch_compile def vecs2axisangle(vec0, vec1): """ Converts the angle from unnormalized 3D vectors @vec0 to @vec1 into an axis-angle representation of the angle @@ -1197,7 +1198,7 @@ def vecs2axisangle(vec0, vec1): return torch.linalg.cross(vec0, vec1) * torch.arccos((vec0 * vec1).sum(-1, keepdim=True)) -@torch.jit.script +@torch_compile def vecs2quat(vec0: torch.Tensor, vec1: torch.Tensor, normalized: bool = False) -> torch.Tensor: """ Converts the angle from unnormalized 3D vectors @vec0 to @vec1 into a quaternion representation of the angle @@ -1233,7 +1234,7 @@ def vecs2quat(vec0: torch.Tensor, vec1: torch.Tensor, normalized: bool = False) # Ref: https://github.com/scipy/scipy/blob/9974222eb58ec3eafe5d12f25ee960f3170c277a/scipy/spatial/transform/_rotation.pyx#L3249 -@torch.jit.script +@torch_compile def align_vector_sets(vec_set1: torch.Tensor, vec_set2: torch.Tensor) -> torch.Tensor: """ Computes a single quaternion representing the rotation that best aligns vec_set1 to vec_set2. @@ -1262,13 +1263,13 @@ def align_vector_sets(vec_set1: torch.Tensor, vec_set2: torch.Tensor) -> torch.T return mat2quat(C) -@torch.jit.script +@torch_compile def l2_distance(v1: torch.Tensor, v2: torch.Tensor) -> torch.Tensor: """Returns the L2 distance between vector v1 and v2.""" return torch.norm(v1 - v2) -@torch.jit.script +@torch_compile def cartesian_to_polar(x, y): """Convert cartesian coordinate to polar coordinate""" rho = torch.sqrt(x**2 + y**2) @@ -1284,7 +1285,7 @@ def rad2deg(rad): return rad * 180.0 / math.pi -@torch.jit.script +@torch_compile def check_quat_right_angle(quat: torch.Tensor, atol: float = 5e-2) -> torch.Tensor: """ Check by making sure the quaternion is some permutation of +/- (1, 0, 0, 0), @@ -1304,14 +1305,14 @@ def check_quat_right_angle(quat: torch.Tensor, atol: float = 5e-2) -> torch.Tens return torch.any(torch.abs(l1_norm.unsqueeze(-1) - reference_norms) < atol, dim=-1) -@torch.jit.script +@torch_compile def z_angle_from_quat(quat): """Get the angle around the Z axis produced by the quaternion.""" rotated_X_axis = quat_apply(quat, torch.tensor([1, 0, 0], dtype=torch.float32)) return torch.arctan2(rotated_X_axis[1], rotated_X_axis[0]) -@torch.jit.script +@torch_compile def integer_spiral_coordinates(n: int) -> Tuple[int, int]: """A function to map integers to 2D coordinates in a spiral pattern around the origin.""" # Map integers from Z to Z^2 in a spiral pattern around the origin. @@ -1324,7 +1325,7 @@ def integer_spiral_coordinates(n: int) -> Tuple[int, int]: return int(x), int(y) -@torch.jit.script +@torch_compile def transform_points(points: torch.Tensor, matrix: torch.Tensor, translate: bool = True) -> torch.Tensor: """ Returns points rotated by a homogeneous @@ -1360,7 +1361,7 @@ def transform_points(points: torch.Tensor, matrix: torch.Tensor, translate: bool return torch.mm(matrix[:dim, :dim], points.t()).t() -@torch.jit.script +@torch_compile def quaternions_close(q1: torch.Tensor, q2: torch.Tensor, atol: float = 1e-3) -> bool: """ Whether two quaternions represent the same rotation, @@ -1381,7 +1382,7 @@ def quaternions_close(q1: torch.Tensor, q2: torch.Tensor, atol: float = 1e-3) -> return torch.allclose(q1, q2, atol=atol) or torch.allclose(q1, -q2, atol=atol) -@torch.jit.script +@torch_compile def orientation_error(desired, current): """ This function calculates a 3-dimensional orientation error vector for use in the @@ -1411,7 +1412,7 @@ def orientation_error(desired, current): return error.reshape(desired.shape[:-2] + (3,)) -@torch.jit.script +@torch_compile def delta_rotation_matrix(omega, delta_t): """ Compute the delta rotation matrix given angular velocity and time elapsed. @@ -1452,7 +1453,7 @@ def delta_rotation_matrix(omega, delta_t): return R -@torch.jit.script +@torch_compile def mat2euler_intrinsic(rmat): """ Converts given rotation matrix to intrinsic euler angles in radian. @@ -1478,7 +1479,7 @@ def mat2euler_intrinsic(rmat): return torch.stack([roll, pitch, yaw]) -@torch.jit.script +@torch_compile def euler_intrinsic2mat(euler): """ Converts intrinsic euler angles into rotation matrix form From 9c4cd88939d0ab8d99fd1383dd4a8a003b24c9d6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen?= <1408354+cgokmen@users.noreply.github.com> Date: Thu, 20 Feb 2025 15:37:36 -0800 Subject: [PATCH 2/4] Fully unify torch compile calls --- omnigibson/controllers/joint_controller.py | 4 ++-- omnigibson/utils/usd_utils.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/omnigibson/controllers/joint_controller.py b/omnigibson/controllers/joint_controller.py index d418af4ef..6f952e3ce 100644 --- a/omnigibson/controllers/joint_controller.py +++ b/omnigibson/controllers/joint_controller.py @@ -14,7 +14,7 @@ from omnigibson.macros import create_module_macros from omnigibson.utils.backend_utils import _compute_backend as cb from omnigibson.utils.backend_utils import add_compute_function -from omnigibson.utils.python_utils import assert_valid_key +from omnigibson.utils.python_utils import assert_valid_key, torch_compile from omnigibson.utils.ui_utils import create_module_logger # Create module logger @@ -307,7 +307,7 @@ def command_dim(self): return len(self.dof_idx) -@th.compile +@torch_compile def _compute_joint_torques_torch( u: th.Tensor, mm: th.Tensor, diff --git a/omnigibson/utils/usd_utils.py b/omnigibson/utils/usd_utils.py index f9d9a84d3..5cb2d784b 100644 --- a/omnigibson/utils/usd_utils.py +++ b/omnigibson/utils/usd_utils.py @@ -20,7 +20,7 @@ from omnigibson.utils.backend_utils import add_compute_function from omnigibson.utils.constants import PRIMITIVE_MESH_TYPES, JointType, PrimType from omnigibson.utils.numpy_utils import vtarray_to_torch -from omnigibson.utils.python_utils import assert_valid_key +from omnigibson.utils.python_utils import assert_valid_key, torch_compile from omnigibson.utils.ui_utils import create_module_logger, suppress_omni_log # Create module logger @@ -1996,7 +1996,7 @@ def delete_or_deactivate_prim(prim_path): return True -@th.compile +@torch_compile def _compute_relative_poses_torch( idx: int, n_links: int, From 59135f91cfc15f559cca470d39cabeb24ddf2aba Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen?= <1408354+cgokmen@users.noreply.github.com> Date: Thu, 20 Feb 2025 16:36:11 -0800 Subject: [PATCH 3/4] Fix how we check for bad prim --- omnigibson/object_states/particle_modifier.py | 2 +- omnigibson/object_states/toggle.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/omnigibson/object_states/particle_modifier.py b/omnigibson/object_states/particle_modifier.py index c4f650d2e..c6c162908 100644 --- a/omnigibson/object_states/particle_modifier.py +++ b/omnigibson/object_states/particle_modifier.py @@ -355,7 +355,7 @@ def overlap_callback(hit): # If not, see if it exists in the legacy format's location # TODO: Remove this after new dataset release - if pre_existing_mesh is None: + if not pre_existing_mesh: mesh_prim_path = f"{self.link.prim_path}/mesh_0" pre_existing_mesh = lazy.omni.isaac.core.utils.prims.get_prim_at_path(mesh_prim_path) diff --git a/omnigibson/object_states/toggle.py b/omnigibson/object_states/toggle.py index 33925c4b2..2ead470e8 100644 --- a/omnigibson/object_states/toggle.py +++ b/omnigibson/object_states/toggle.py @@ -105,7 +105,7 @@ def _initialize(self): # If not, see if it exists in the legacy format's location # TODO: Remove this after new dataset release - if pre_existing_mesh is None: + if not pre_existing_mesh: mesh_prim_path = f"{self.link.prim_path}/mesh_0" pre_existing_mesh = lazy.omni.isaac.core.utils.prims.get_prim_at_path(mesh_prim_path) From 51d44ab4d580be918d0b97b9c77140ea71f620d6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Cem=20G=C3=B6kmen?= Date: Fri, 21 Feb 2025 10:37:21 -0800 Subject: [PATCH 4/4] Make cloth prim compatible with meta link API, temporarily allow multi mesh cloth --- omnigibson/prims/cloth_prim.py | 32 +++++++++++++++++++++++++++++++- 1 file changed, 31 insertions(+), 1 deletion(-) diff --git a/omnigibson/prims/cloth_prim.py b/omnigibson/prims/cloth_prim.py index b9112c14c..f2aeb3b0b 100644 --- a/omnigibson/prims/cloth_prim.py +++ b/omnigibson/prims/cloth_prim.py @@ -39,7 +39,7 @@ CLOTH_CONFIGURATIONS = ["default", "settled", "folded", "crumpled"] # Subsample cloth particle points to boost performance -m.ALLOW_MULTIPLE_CLOTH_MESH_COMPONENTS = False +m.ALLOW_MULTIPLE_CLOTH_MESH_COMPONENTS = True # TODO: Disable after new dataset release m.N_CLOTH_KEYPOINTS = 1000 m.FOLDING_INCREMENTS = 100 m.CRUMPLING_INCREMENTS = 100 @@ -1023,3 +1023,33 @@ def reset(self): if self.initialized: points_configuration = self._load_config.get("default_point_configuration", "default") self.reset_points_to_configuration(points_configuration) + + @cached_property + def is_meta_link(self): + return False + + @cached_property + def meta_link_type(self): + raise ValueError(f"{self.name} is not a meta link") + + @cached_property + def meta_link_id(self): + """The meta link id of this link, if the link is a meta link. + + The meta link ID is a semantic identifier for the meta link within the meta link type. It is + used when an object has multiple meta links of the same type. It can be just a numerical index, + or for some objects, it will be a string that can be matched to other meta links. For example, + a stove might have toggle buttons named "left" and "right", and heat sources named "left" and + "right". The meta link ID can be used to match the toggle button to the heat source. + """ + raise ValueError(f"{self.name} is not a meta link") + + @cached_property + def meta_link_sub_id(self): + """The integer meta link sub id of this link, if the link is a meta link. + + The meta link sub ID identifies this link as one of the parts of a meta link. For example, an + attachment meta link's ID will be the attachment pair name, and each attachment point that + works with that pair will show up as a separate link with a unique sub ID. + """ + raise ValueError(f"{self.name} is not a meta link")