From c79d5c40092880635d10ed1fc485cf0776d65f31 Mon Sep 17 00:00:00 2001 From: hapatel-bdai Date: Fri, 4 Apr 2025 14:15:42 -0400 Subject: [PATCH 1/8] collision mesh schema changes --- .../isaaclab/sim/converters/mesh_converter.py | 122 +++++------ .../sim/converters/mesh_converter_cfg.py | 28 +-- .../isaaclab/isaaclab/sim/schemas/__init__.py | 53 +++++ .../isaaclab/isaaclab/sim/schemas/schemas.py | 200 ++++++++++++++---- .../isaaclab/sim/schemas/schemas_cfg.py | 199 +++++++++++++++++ source/isaaclab/isaaclab/utils/configclass.py | 10 +- 6 files changed, 479 insertions(+), 133 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py index fb6adbaef3d..62c04d072f5 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py @@ -64,13 +64,12 @@ def __init__(self, cfg: MeshConverterCfg): def _convert_asset(self, cfg: MeshConverterCfg): """Generate USD from OBJ, STL or FBX. - The USD file has Y-up axis and is scaled to meters. - The asset hierarchy is arranged as follows: + It stores the asset in the following format: - .. code-block:: none - mesh_file_basename (default prim) - |- /geometry/Looks - |- /geometry/mesh + /file_name (default prim) + |- /geometry <- Made instanceable if requested + |- /Looks + |- /mesh Args: cfg: The configuration for conversion of mesh to USD. @@ -82,37 +81,17 @@ def _convert_asset(self, cfg: MeshConverterCfg): mesh_file_basename, mesh_file_format = os.path.basename(cfg.asset_path).split(".") mesh_file_format = mesh_file_format.lower() - # Check if mesh_file_basename is a valid USD identifier - if not Tf.IsValidIdentifier(mesh_file_basename): - # Correct the name to a valid identifier and update the basename - mesh_file_basename_original = mesh_file_basename - mesh_file_basename = Tf.MakeValidIdentifier(mesh_file_basename) - omni.log.warn( - f"Input file name '{mesh_file_basename_original}' is an invalid identifier for the mesh prim path." - f" Renaming it to '{mesh_file_basename}' for the conversion." - ) - # Convert USD asyncio.get_event_loop().run_until_complete( - self._convert_mesh_to_usd(in_file=cfg.asset_path, out_file=self.usd_path) + self._convert_mesh_to_usd( + in_file=cfg.asset_path, out_file=self.usd_path, prim_path=f"/{mesh_file_basename}" + ) ) - # Create a new stage, set Z up and meters per unit - temp_stage = Usd.Stage.CreateInMemory() - UsdGeom.SetStageUpAxis(temp_stage, UsdGeom.Tokens.z) - UsdGeom.SetStageMetersPerUnit(temp_stage, 1.0) - UsdPhysics.SetStageKilogramsPerUnit(temp_stage, 1.0) - # Add mesh to stage - base_prim = temp_stage.DefinePrim(f"/{mesh_file_basename}", "Xform") - prim = temp_stage.DefinePrim(f"/{mesh_file_basename}/geometry", "Xform") - prim.GetReferences().AddReference(self.usd_path) - temp_stage.SetDefaultPrim(base_prim) - temp_stage.Export(self.usd_path) - # Open converted USD stage + # note: This opens a new stage and does not use the stage created earlier by the user + # create a new stage stage = Usd.Stage.Open(self.usd_path) - # Need to reload the stage to get the new prim structure, otherwise it can be taken from the cache - stage.Reload() - # Add USD to stage cache + # add USD to stage cache stage_id = UsdUtils.StageCache.Get().Insert(stage) # Get the default prim (which is the root prim) -- "/{mesh_file_basename}" xform_prim = stage.GetDefaultPrim() @@ -122,42 +101,17 @@ def _convert_asset(self, cfg: MeshConverterCfg): if child_mesh_prim.GetTypeName() == "Mesh": # Apply collider properties to mesh if cfg.collision_props is not None: - # -- Collision approximation to mesh - # TODO: Move this to a new Schema: https://github.com/isaac-orbit/IsaacLab/issues/163 - mesh_collision_api = UsdPhysics.MeshCollisionAPI.Apply(child_mesh_prim) - mesh_collision_api.GetApproximationAttr().Set(cfg.collision_approximation) # -- Collider properties such as offset, scale, etc. schemas.define_collision_properties( prim_path=child_mesh_prim.GetPath(), cfg=cfg.collision_props, stage=stage ) + # Add collision mesh + if cfg.mesh_collision_props is not None: + schemas.define_mesh_collision_properties( + prim_path=child_mesh_prim.GetPath(), cfg=cfg.mesh_collision_props, stage=stage + ) # Delete the old Xform and make the new Xform the default prim stage.SetDefaultPrim(xform_prim) - # Apply default Xform rotation to mesh -> enable to set rotation and scale - omni.kit.commands.execute( - "CreateDefaultXformOnPrimCommand", - prim_path=xform_prim.GetPath(), - **{"stage": stage}, - ) - - # Apply translation, rotation, and scale to the Xform - geom_xform = UsdGeom.Xform(geom_prim) - geom_xform.ClearXformOpOrder() - - # Remove any existing rotation attributes - rotate_attr = geom_prim.GetAttribute("xformOp:rotateXYZ") - if rotate_attr: - geom_prim.RemoveProperty(rotate_attr.GetName()) - - # translation - translate_op = geom_xform.AddTranslateOp(UsdGeom.XformOp.PrecisionDouble) - translate_op.Set(Gf.Vec3d(*cfg.translation)) - # rotation - orient_op = geom_xform.AddOrientOp(UsdGeom.XformOp.PrecisionDouble) - orient_op.Set(Gf.Quatd(*cfg.rotation)) - # scale - scale_op = geom_xform.AddScaleOp(UsdGeom.XformOp.PrecisionDouble) - scale_op.Set(Gf.Vec3d(*cfg.scale)) - # Handle instanceable # Create a new Xform prim that will be the prototype prim if cfg.make_instanceable: @@ -195,18 +149,28 @@ def _convert_asset(self, cfg: MeshConverterCfg): """ @staticmethod - async def _convert_mesh_to_usd(in_file: str, out_file: str, load_materials: bool = True) -> bool: + async def _convert_mesh_to_usd( + in_file: str, out_file: str, prim_path: str = "/World", load_materials: bool = True + ) -> bool: """Convert mesh from supported file types to USD. This function uses the Omniverse Asset Converter extension to convert a mesh file to USD. It is an asynchronous function and should be called using `asyncio.get_event_loop().run_until_complete()`. The converted asset is stored in the USD format in the specified output file. - The USD file has Y-up axis and is scaled to cm. + The USD file has Y-up axis and is scaled to meters. + + The asset hierarchy is arranged as follows: + + .. code-block:: none + prim_path (default prim) + |- /geometry/Looks + |- /geometry/mesh Args: in_file: The file to convert. out_file: The path to store the output file. + prim_path: The prim path of the mesh. load_materials: Set to True to enable attaching materials defined in the input file to the generated USD mesh. Defaults to True. @@ -214,9 +178,11 @@ async def _convert_mesh_to_usd(in_file: str, out_file: str, load_materials: bool True if the conversion succeeds. """ enable_extension("omni.kit.asset_converter") + enable_extension("omni.usd.metrics.assembler") import omni.kit.asset_converter import omni.usd + from omni.metrics.assembler.core import get_metrics_assembler_interface # Create converter context converter_context = omni.kit.asset_converter.AssetConverterContext() @@ -237,9 +203,29 @@ async def _convert_mesh_to_usd(in_file: str, out_file: str, load_materials: bool # Create converter task instance = omni.kit.asset_converter.get_instance() - task = instance.create_converter_task(in_file, out_file, None, converter_context) + out_file_non_metric = out_file.replace(".usd", "_non_metric.usd") + task = instance.create_converter_task(in_file, out_file_non_metric, None, converter_context) # Start conversion task and wait for it to finish - success = await task.wait_until_finished() - if not success: - raise RuntimeError(f"Failed to convert {in_file} to USD. Error: {task.get_error_message()}") + success = True + while True: + success = await task.wait_until_finished() + if not success: + await asyncio.sleep(0.1) + else: + break + + temp_stage = Usd.Stage.CreateInMemory() + UsdGeom.SetStageUpAxis(temp_stage, UsdGeom.Tokens.z) + UsdGeom.SetStageMetersPerUnit(temp_stage, 1.0) + UsdPhysics.SetStageKilogramsPerUnit(temp_stage, 1.0) + + base_prim = temp_stage.DefinePrim(prim_path, "Xform") + prim = temp_stage.DefinePrim(f"{prim_path}/geometry", "Xform") + prim.GetReferences().AddReference(out_file_non_metric) + cache = UsdUtils.StageCache.Get() + cache.Insert(temp_stage) + stage_id = cache.GetId(temp_stage).ToLongInt() + get_metrics_assembler_interface().resolve_stage(stage_id) + temp_stage.SetDefaultPrim(base_prim) + temp_stage.Export(out_file) return success diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py index c7f603e309f..fd6f9aedf44 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py @@ -12,42 +12,28 @@ class MeshConverterCfg(AssetConverterBaseCfg): """The configuration class for MeshConverter.""" - mass_props: schemas_cfg.MassPropertiesCfg | None = None + mass_props: schemas_cfg.MassPropertiesCfg = None """Mass properties to apply to the USD. Defaults to None. Note: If None, then no mass properties will be added. """ - rigid_props: schemas_cfg.RigidBodyPropertiesCfg | None = None + rigid_props: schemas_cfg.RigidBodyPropertiesCfg = None """Rigid body properties to apply to the USD. Defaults to None. Note: If None, then no rigid body properties will be added. """ - collision_props: schemas_cfg.CollisionPropertiesCfg | None = None + collision_props: schemas_cfg.CollisionPropertiesCfg = None """Collision properties to apply to the USD. Defaults to None. Note: If None, then no collision properties will be added. """ - - collision_approximation: str = "convexDecomposition" - """Collision approximation method to use. Defaults to "convexDecomposition". - - Valid options are: - "convexDecomposition", "convexHull", "boundingCube", - "boundingSphere", "meshSimplification", or "none" - - "none" causes no collision mesh to be added. + mesh_collision_props: schemas_cfg.MeshCollisionPropertiesCfg = None + """Mesh approximation properties to apply to all collision meshes in the USD. + Note: + If None, then no mesh approximation properties will be added. """ - - translation: tuple[float, float, float] = (0.0, 0.0, 0.0) - """The translation of the mesh to the origin. Defaults to (0.0, 0.0, 0.0).""" - - rotation: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0) - """The rotation of the mesh in quaternion format (w, x, y, z). Defaults to (1.0, 0.0, 0.0, 0.0).""" - - scale: tuple[float, float, float] = (1.0, 1.0, 1.0) - """The scale of the mesh. Defaults to (1.0, 1.0, 1.0).""" diff --git a/source/isaaclab/isaaclab/sim/schemas/__init__.py b/source/isaaclab/isaaclab/sim/schemas/__init__.py index 20f02aa9e69..0772915cae7 100644 --- a/source/isaaclab/isaaclab/sim/schemas/__init__.py +++ b/source/isaaclab/isaaclab/sim/schemas/__init__.py @@ -33,11 +33,14 @@ """ from .schemas import ( + PHYSX_MESH_COLLISION_CFGS, + USD_MESH_COLLISION_CFGS, activate_contact_sensors, define_articulation_root_properties, define_collision_properties, define_deformable_body_properties, define_mass_properties, + define_mesh_collision_properties, define_rigid_body_properties, modify_articulation_root_properties, modify_collision_properties, @@ -45,14 +48,64 @@ modify_fixed_tendon_properties, modify_joint_drive_properties, modify_mass_properties, + modify_mesh_collision_properties, modify_rigid_body_properties, ) from .schemas_cfg import ( ArticulationRootPropertiesCfg, + BoundingCubePropertiesCfg, + BoundingSpherePropertiesCfg, CollisionPropertiesCfg, + ConvexDecompositionPropertiesCfg, + ConvexHullPropertiesCfg, DeformableBodyPropertiesCfg, FixedTendonPropertiesCfg, JointDrivePropertiesCfg, MassPropertiesCfg, + MeshCollisionPropertiesCfg, RigidBodyPropertiesCfg, + SDFMeshPropertiesCfg, + TriangleMeshPropertiesCfg, + TriangleMeshSimplificationPropertiesCfg, ) + +__all__ = [ + # articulation root + "ArticulationRootPropertiesCfg", + "define_articulation_root_properties", + "modify_articulation_root_properties", + # rigid bodies + "RigidBodyPropertiesCfg", + "define_rigid_body_properties", + "modify_rigid_body_properties", + "activate_contact_sensors", + # colliders + "CollisionPropertiesCfg", + "define_collision_properties", + "modify_collision_properties", + # mass + "MassPropertiesCfg", + "define_mass_properties", + "modify_mass_properties", + # mesh colliders + "MeshCollisionPropertiesCfg", + "define_mesh_collision_properties", + "modify_mesh_collision_properties", + # bounding cube + "BoundingCubePropertiesCfg", + # bounding sphere + "BoundingSpherePropertiesCfg", + # convex decomposition + "ConvexDecompositionPropertiesCfg", + # convex hull + "ConvexHullPropertiesCfg", + # sdf mesh + "SDFMeshPropertiesCfg", + # triangle mesh + "TriangleMeshPropertiesCfg", + # triangle mesh simplification + "TriangleMeshSimplificationPropertiesCfg", + # Constants for configs that use PhysX vs USD API + "PHYSX_MESH_COLLISION_CFGS", + "USD_MESH_COLLISION_CFGS", +] \ No newline at end of file diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas.py b/source/isaaclab/isaaclab/sim/schemas/schemas.py index fe8ced7e79e..03c21a28532 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas.py @@ -26,6 +26,22 @@ Articulation root properties. """ +PHYSX_MESH_COLLISION_CFGS = [ + schemas_cfg.ConvexDecompositionPropertiesCfg, + schemas_cfg.ConvexHullPropertiesCfg, + schemas_cfg.TriangleMeshPropertiesCfg, + schemas_cfg.TriangleMeshSimplificationPropertiesCfg, + schemas_cfg.SDFMeshPropertiesCfg, +] + +USD_MESH_COLLISION_CFGS = [ + schemas_cfg.BoundingCubePropertiesCfg, + schemas_cfg.BoundingSpherePropertiesCfg, + schemas_cfg.ConvexDecompositionPropertiesCfg, + schemas_cfg.ConvexHullPropertiesCfg, + schemas_cfg.TriangleMeshSimplificationPropertiesCfg, +] + def define_articulation_root_properties( prim_path: str, cfg: schemas_cfg.ArticulationRootPropertiesCfg, stage: Usd.Stage | None = None @@ -133,12 +149,12 @@ def modify_articulation_root_properties( # if we found a fixed joint, enable/disable it based on the input # otherwise, create a fixed joint between the world and the root link if existing_fixed_joint_prim is not None: - omni.log.info( + carb.log_info( f"Found an existing fixed joint for the articulation: '{prim_path}'. Setting it to: {fix_root_link}." ) existing_fixed_joint_prim.GetJointEnabledAttr().Set(fix_root_link) elif fix_root_link: - omni.log.info(f"Creating a fixed joint for the articulation: '{prim_path}'.") + carb.log_info(f"Creating a fixed joint for the articulation: '{prim_path}'.") # note: we have to assume that the root prim is a rigid body, # i.e. we don't handle the case where the root prim is not a rigid body but has articulation api on it @@ -502,10 +518,10 @@ def activate_contact_sensors(prim_path: str, threshold: float = 0.0, stage: Usd. rb.CreateSleepThresholdAttr().Set(0.0) # add contact report API with threshold of zero if not child_prim.HasAPI(PhysxSchema.PhysxContactReportAPI): - omni.log.verbose(f"Adding contact report API to prim: '{child_prim.GetPrimPath()}'") + carb.log_verbose(f"Adding contact report API to prim: '{child_prim.GetPrimPath()}'") cr_api = PhysxSchema.PhysxContactReportAPI.Apply(child_prim) else: - omni.log.verbose(f"Contact report API already exists on prim: '{child_prim.GetPrimPath()}'") + carb.log_verbose(f"Contact report API already exists on prim: '{child_prim.GetPrimPath()}'") cr_api = PhysxSchema.PhysxContactReportAPI.Get(stage, child_prim.GetPrimPath()) # set threshold to zero cr_api.CreateThresholdAttr().Set(threshold) @@ -531,7 +547,7 @@ def activate_contact_sensors(prim_path: str, threshold: float = 0.0, stage: Usd. @apply_nested def modify_joint_drive_properties( - prim_path: str, cfg: schemas_cfg.JointDrivePropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, drive_props: schemas_cfg.JointDrivePropertiesCfg, stage: Usd.Stage | None = None ) -> bool: """Modify PhysX parameters for a joint prim. @@ -546,7 +562,7 @@ def modify_joint_drive_properties( .. caution:: We highly recommend modifying joint properties of articulations through the functionalities in the - :mod:`isaaclab.actuators` module. The methods here are for setting simulation low-level + :mod:`omni.isaac.lab.actuators` module. The methods here are for setting simulation low-level properties only. .. _UsdPhysics.DriveAPI: https://openusd.org/dev/api/class_usd_physics_drive_a_p_i.html @@ -554,7 +570,7 @@ def modify_joint_drive_properties( Args: prim_path: The prim path where to apply the joint drive schema. - cfg: The configuration for the joint drive. + drive_props: The configuration for the joint drive. stage: The stage where to find the prim. Defaults to None, in which case the current stage is used. @@ -589,43 +605,10 @@ def modify_joint_drive_properties( usd_drive_api = UsdPhysics.DriveAPI(prim, drive_api_name) if not usd_drive_api: usd_drive_api = UsdPhysics.DriveAPI.Apply(prim, drive_api_name) - # check if prim has Physx joint drive applied on it - physx_joint_api = PhysxSchema.PhysxJointAPI(prim) - if not physx_joint_api: - physx_joint_api = PhysxSchema.PhysxJointAPI.Apply(prim) - - # mapping from configuration name to USD attribute name - cfg_to_usd_map = { - "max_velocity": "max_joint_velocity", - "max_effort": "max_force", - "drive_type": "type", - } - # convert to dict - cfg = cfg.to_dict() - # check if linear drive - is_linear_drive = prim.IsA(UsdPhysics.PrismaticJoint) - # convert values for angular drives from radians to degrees units - if not is_linear_drive: - if cfg["max_velocity"] is not None: - # rad / s --> deg / s - cfg["max_velocity"] = cfg["max_velocity"] * 180.0 / math.pi - if cfg["stiffness"] is not None: - # N-m/rad --> N-m/deg - cfg["stiffness"] = cfg["stiffness"] * math.pi / 180.0 - if cfg["damping"] is not None: - # N-m-s/rad --> N-m-s/deg - cfg["damping"] = cfg["damping"] * math.pi / 180.0 - - # set into PhysX API - for attr_name in ["max_velocity"]: - value = cfg.pop(attr_name, None) - attr_name = cfg_to_usd_map[attr_name] - safe_set_attribute_on_usd_schema(physx_joint_api, attr_name, value, camel_case=True) - # set into USD API - for attr_name, attr_value in cfg.items(): - attr_name = cfg_to_usd_map.get(attr_name, attr_name) - safe_set_attribute_on_usd_schema(usd_drive_api, attr_name, attr_value, camel_case=True) + # change the drive type to input + if drive_props.drive_type is not None: + usd_drive_api.CreateTypeAttr().Set(drive_props.drive_type) return True @@ -851,3 +834,134 @@ def modify_deformable_body_properties( # success return True + + +""" +Collision mesh properties. + +""" + + +def extract_mesh_collision_api_and_attrs(cfg): + # We use the number of user set attributes outside of the API function + # to determine which API to use in ambiguous cases, so collect them here + custom_attrs = { + key: value + for key, value in cfg.to_dict().items() + if value is not None and key not in ["usd_func", "physx_func"] + } + + use_usd_api = False + use_phsyx_api = False + + # We have some custom attributes and allow them + if len(custom_attrs) > 0 and type(cfg) in PHYSX_MESH_COLLISION_CFGS: + use_phsyx_api = True + # We have no custom attributes + elif len(custom_attrs) == 0: + if type(cfg) in USD_MESH_COLLISION_CFGS: + # Use the USD API + use_usd_api = True + else: + # Use the PhysX API + use_phsyx_api = True + + elif len(custom_attrs > 0) and type(cfg) in USD_MESH_COLLISION_CFGS: + raise ValueError("Args are specified but the USD Mesh API doesn't support them!") + + mesh_collision_appx_type = type(cfg).__name__.partition("PropertiesCfg")[0] + + if use_usd_api: + # Add approximation to the attributes as this is how USD collision mesh API is configured + api_func = cfg.usd_func + # Approximation needs to be formatted with camelCase + custom_attrs["Approximation"] = mesh_collision_appx_type[0].lower() + mesh_collision_appx_type[1:] + elif use_phsyx_api: + api_func = cfg.physx_func + else: + raise ValueError("Either USD or PhysX API should be used for mesh collision approximation!") + + return api_func, custom_attrs + + +def define_mesh_collision_properties( + prim_path: str, cfg: schemas_cfg.MeshCollisionPropertiesCfg, stage: Usd.Stage | None = None +): + """Apply the mesh collision schema on the input prim and set its properties. + + See :func:`modify_collision_mesh_properties` for more details on how the properties are set. + + Args: + prim_path : The prim path where to apply the mesh collision schema. + cfg : The configuration for the mesh collision properties. + stage : The stage where to find the prim. Defaults to None, in which case the + current stage is used. + + Raises: + ValueError: When the prim path is not valid. + """ + # obtain stage + if stage is None: + stage = stage_utils.get_current_stage() + # get USD prim + prim = stage.GetPrimAtPath(prim_path) + # check if prim path is valid + if not prim.IsValid(): + raise ValueError(f"Prim path '{prim_path}' is not valid.") + + api_func, _ = extract_mesh_collision_api_and_attrs(cfg=cfg) + + # Only enable if not already enabled + if not api_func(prim): + api_func.Apply(prim) + + modify_mesh_collision_properties(prim_path=prim_path, cfg=cfg, stage=stage) + + +@apply_nested +def modify_mesh_collision_properties( + prim_path: str, cfg: schemas_cfg.MeshCollisionPropertiesCfg, stage: Usd.Stage | None = None +): + """Set properties for the mesh collision of a prim. + + These properties are based on either the `Phsyx the `UsdPhysics.MeshCollisionAPI` schema. + + .. note:: + This function is decorated with :func:`apply_nested` that sets the properties to all the prims + (that have the schema applied on them) under the input prim path. + + .. UsdPhysics.MeshCollisionAPI: https://openusd.org/release/api/class_usd_physics_mesh_collision_a_p_i.html + + Args: + prim_path : The prim path of the rigid body. This prim should be a Mesh prim. + cfg : The configuration for the mesh collision properties. + stage : The stage where to find the prim. Defaults to None, in which case the + current stage is used. + """ + # obtain stage + if stage is None: + stage = stage_utils.get_current_stage() + # get USD prim + prim = stage.GetPrimAtPath(prim_path) + + api_func, custom_attrs = extract_mesh_collision_api_and_attrs(cfg=cfg) + + # check if prim has mesh collision api applied on it + if not api_func(prim): + print("****") + # return False + + # retrieve the mesh collision API + mesh_collision_api = api_func(prim) + + # set custom attributes into mesh collision API + for attr_name, value in custom_attrs.items(): + # Only "Attribute" attr should be in format "boundingSphere", so set camel_case to be False + if attr_name == "Attribute": + camel_case = False + else: + camel_case = True + safe_set_attribute_on_usd_schema(mesh_collision_api, attr_name, value, camel_case=camel_case) + + # success + return True \ No newline at end of file diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py index fed680f183b..e900d70d04d 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py @@ -3,8 +3,11 @@ # # SPDX-License-Identifier: BSD-3-Clause +from dataclasses import MISSING from typing import Literal +from pxr import PhysxSchema, UsdPhysics + from isaaclab.utils import configclass @@ -395,3 +398,199 @@ class DeformableBodyPropertiesCfg: max_depenetration_velocity: float | None = None """Maximum depenetration velocity permitted to be introduced by the solver (in m/s).""" + + +@configclass +class MeshCollisionPropertiesCfg: + """Properties to apply to a mesh in regards to collision. + See :meth:`set_mesh_collision_properties` for more information. + + .. note:: + If the values are None, they are not modified. This is useful when you want to set only a subset of + the properties and leave the rest as-is. + """ + + usd_func: callable = MISSING + + physx_func: callable = MISSING + + +@configclass +class BoundingCubePropertiesCfg(MeshCollisionPropertiesCfg): + usd_func: callable = UsdPhysics.MeshCollisionAPI + """Original USD Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html + """ + + +@configclass +class BoundingSpherePropertiesCfg(MeshCollisionPropertiesCfg): + usd_func: callable = UsdPhysics.MeshCollisionAPI + """Original USD Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html + """ + + +@configclass +class ConvexDecompositionPropertiesCfg(MeshCollisionPropertiesCfg): + usd_func: callable = UsdPhysics.MeshCollisionAPI + """Original USD Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html + """ + + physx_func: callable = PhysxSchema.PhysxConvexDecompositionCollisionAPI + """Original PhysX Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_convex_decomposition_collision_a_p_i.html + """ + + hull_vertex_limit: int | None = None + """Convex hull vertex limit used for convex hull cooking. + + Defaults to 64. + """ + max_convex_hulls: int | None = None + """Maximum of convex hulls created during convex decomposition. + Default value is 32. + """ + min_thickness: float | None = None + """Convex hull min thickness. + + Range: [0, inf). Units are distance. Default value is 0.001. + """ + voxel_resolution: int | None = None + """Voxel resolution used for convex decomposition. + + Defaults to 500,000 voxels. + """ + error_percentage: float | None = None + """Convex decomposition error percentage parameter. + + Defaults to 10 percent. Units are percent. + """ + shrink_wrap: bool | None = None + """Attempts to adjust the convex hull points so that they are projected onto the surface of the original graphics + mesh. + + Defaults to False. + """ + + +@configclass +class ConvexHullPropertiesCfg(MeshCollisionPropertiesCfg): + usd_func: callable = UsdPhysics.MeshCollisionAPI + """Original USD Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html + """ + + physx_func: callable = PhysxSchema.PhysxConvexHullCollisionAPI + """Original PhysX Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_convex_hull_collision_a_p_i.html + """ + + hull_vertex_limit: int | None = None + """Convex hull vertex limit used for convex hull cooking. + + Defaults to 64. + """ + min_thickness: float | None = None + """Convex hull min thickness. + + Range: [0, inf). Units are distance. Default value is 0.001. + """ + + +@configclass +class TriangleMeshPropertiesCfg(MeshCollisionPropertiesCfg): + physx_func: callable = PhysxSchema.PhysxTriangleMeshCollisionAPI + """Triangle mesh is only supported by PhysX API. + + Original PhysX Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_triangle_mesh_collision_a_p_i.html + """ + + weld_tolerance: float | None = None + """Mesh weld tolerance, controls the distance at which vertices are welded. + + Default -inf will autocompute the welding tolerance based on the mesh size. Zero value will disable welding. + Range: [0, inf) Units: distance + """ + + +@configclass +class TriangleMeshSimplificationPropertiesCfg(MeshCollisionPropertiesCfg): + usd_func: callable = UsdPhysics.MeshCollisionAPI + """Original USD Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_usd_physics_mesh_collision_a_p_i.html + """ + + physx_func: callable = PhysxSchema.PhysxTriangleMeshSimplificationCollisionAPI + """Original PhysX Documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_triangle_mesh_simplification_collision_a_p_i.html + """ + + simplification_metric: float | None = None + """Mesh simplification accuracy. + + Defaults to 0.55. + """ + weld_tolerance: float | None = None + """Mesh weld tolerance, controls the distance at which vertices are welded. + + Default -inf will autocompute the welding tolerance based on the mesh size. Zero value will disable welding. + Range: [0, inf) Units: distance + """ + + +@configclass +class SDFMeshPropertiesCfg(MeshCollisionPropertiesCfg): + physx_func: callable = PhysxSchema.PhysxSDFMeshCollisionAPI + """SDF mesh is only supported by PhysX API. + + Original PhysX documentation: + https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/latest/class_physx_schema_physx_s_d_f_mesh_collision_a_p_i.html + + More details and steps for optimizing SDF results can be found here: + https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/RigidBodyCollision.html#dynamic-triangle-meshes-with-sdfs + """ + sdf_margin: float | None = None + """Margin to increase the size of the SDF relative to the bounding box diagonal length of the mesh. + + + A sdf margin value of 0.01 means the sdf boundary will be enlarged in any direction by 1% of the mesh's bounding + box diagonal length. Representing the margin relative to the bounding box diagonal length ensures that it is scale + independent. Margins allow for precise distance queries in a region slightly outside of the mesh's bounding box. + + Default value is 0.01. + Range: [0, inf) Units: dimensionless + """ + sdf_narrow_band_thickness: float | None = None + """Size of the narrow band around the mesh surface where high resolution SDF samples are available. + + Outside of the narrow band, only low resolution samples are stored. Representing the narrow band thickness as a + fraction of the mesh's bounding box diagonal length ensures that it is scale independent. A value of 0.01 is + usually large enough. The smaller the narrow band thickness, the smaller the memory consumption of the sparse SDF. + + Default value is 0.01. + Range: [0, 1] Units: dimensionless + """ + sdf_resolution: int | None = None + """The spacing of the uniformly sampled SDF is equal to the largest AABB extent of the mesh, divided by the resolution. + + Choose the lowest possible resolution that provides acceptable performance; very high resolution results in large + memory consumption, and slower cooking and simulation performance. + + Default value is 256. + Range: (1, inf) + """ + sdf_subgrid_resolution: int | None = None + """A positive subgrid resolution enables sparsity on signed-distance-fields (SDF) while a value of 0 leads to the + usage of a dense SDF. + + A value in the range of 4 to 8 is a reasonable compromise between block size and the overhead introduced by block + addressing. The smaller a block, the more memory is spent on the address table. The bigger a block, the less + precisely the sparse SDF can adapt to the mesh's surface. In most cases sparsity reduces the memory consumption of + a SDF significantly. + + Default value is 6. + Range: [0, inf) + """ \ No newline at end of file diff --git a/source/isaaclab/isaaclab/utils/configclass.py b/source/isaaclab/isaaclab/utils/configclass.py index 4bdecffb78d..1ffc7e52587 100644 --- a/source/isaaclab/isaaclab/utils/configclass.py +++ b/source/isaaclab/isaaclab/utils/configclass.py @@ -47,7 +47,7 @@ def configclass(cls, **kwargs): from dataclasses import MISSING - from isaaclab.utils.configclass import configclass + from isaaclabz.utils.configclass import configclass @configclass @@ -259,6 +259,9 @@ def _validate(obj: object, prefix: str = "") -> list[str]: """ missing_fields = [] + if type(obj).__name__ == "MeshConverterCfg": + return missing_fields + if type(obj) is type(MISSING): missing_fields.append(prefix) return missing_fields @@ -451,10 +454,15 @@ def _skippable_class_member(key: str, value: Any, hints: dict | None = None) -> # check for class methods if isinstance(value, types.MethodType): return True + + if "CollisionAPI" in value.__name__: + return False + # check for instance methods signature = inspect.signature(value) if "self" in signature.parameters or "cls" in signature.parameters: return True + # skip property methods if isinstance(value, property): return True From 2b0617f8c9094cfceeac8eb8dfdff6c13c110031 Mon Sep 17 00:00:00 2001 From: hapatel-bdai Date: Fri, 4 Apr 2025 14:29:37 -0400 Subject: [PATCH 2/8] minor fixes ot acciently removed code --- .../isaaclab/sim/converters/mesh_converter.py | 113 ++++++++++-------- .../sim/converters/mesh_converter_cfg.py | 9 ++ 2 files changed, 73 insertions(+), 49 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py index 62c04d072f5..a74ab8bb389 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py @@ -64,12 +64,13 @@ def __init__(self, cfg: MeshConverterCfg): def _convert_asset(self, cfg: MeshConverterCfg): """Generate USD from OBJ, STL or FBX. - It stores the asset in the following format: + The USD file has Y-up axis and is scaled to meters. + The asset hierarchy is arranged as follows: - /file_name (default prim) - |- /geometry <- Made instanceable if requested - |- /Looks - |- /mesh + .. code-block:: none + mesh_file_basename (default prim) + |- /geometry/Looks + |- /geometry/mesh Args: cfg: The configuration for conversion of mesh to USD. @@ -81,17 +82,37 @@ def _convert_asset(self, cfg: MeshConverterCfg): mesh_file_basename, mesh_file_format = os.path.basename(cfg.asset_path).split(".") mesh_file_format = mesh_file_format.lower() + # Check if mesh_file_basename is a valid USD identifier + if not Tf.IsValidIdentifier(mesh_file_basename): + # Correct the name to a valid identifier and update the basename + mesh_file_basename_original = mesh_file_basename + mesh_file_basename = Tf.MakeValidIdentifier(mesh_file_basename) + omni.log.warn( + f"Input file name '{mesh_file_basename_original}' is an invalid identifier for the mesh prim path." + f" Renaming it to '{mesh_file_basename}' for the conversion." + ) + # Convert USD asyncio.get_event_loop().run_until_complete( - self._convert_mesh_to_usd( - in_file=cfg.asset_path, out_file=self.usd_path, prim_path=f"/{mesh_file_basename}" - ) + self._convert_mesh_to_usd(in_file=cfg.asset_path, out_file=self.usd_path) ) + # Create a new stage, set Z up and meters per unit + temp_stage = Usd.Stage.CreateInMemory() + UsdGeom.SetStageUpAxis(temp_stage, UsdGeom.Tokens.z) + UsdGeom.SetStageMetersPerUnit(temp_stage, 1.0) + UsdPhysics.SetStageKilogramsPerUnit(temp_stage, 1.0) + # Add mesh to stage + base_prim = temp_stage.DefinePrim(f"/{mesh_file_basename}", "Xform") + prim = temp_stage.DefinePrim(f"/{mesh_file_basename}/geometry", "Xform") + prim.GetReferences().AddReference(self.usd_path) + temp_stage.SetDefaultPrim(base_prim) + temp_stage.Export(self.usd_path) + # Open converted USD stage - # note: This opens a new stage and does not use the stage created earlier by the user - # create a new stage stage = Usd.Stage.Open(self.usd_path) - # add USD to stage cache + # Need to reload the stage to get the new prim structure, otherwise it can be taken from the cache + stage.Reload() + # Add USD to stage cache stage_id = UsdUtils.StageCache.Get().Insert(stage) # Get the default prim (which is the root prim) -- "/{mesh_file_basename}" xform_prim = stage.GetDefaultPrim() @@ -112,6 +133,32 @@ def _convert_asset(self, cfg: MeshConverterCfg): ) # Delete the old Xform and make the new Xform the default prim stage.SetDefaultPrim(xform_prim) + # Apply default Xform rotation to mesh -> enable to set rotation and scale + omni.kit.commands.execute( + "CreateDefaultXformOnPrimCommand", + prim_path=xform_prim.GetPath(), + **{"stage": stage}, + ) + + # Apply translation, rotation, and scale to the Xform + geom_xform = UsdGeom.Xform(geom_prim) + geom_xform.ClearXformOpOrder() + + # Remove any existing rotation attributes + rotate_attr = geom_prim.GetAttribute("xformOp:rotateXYZ") + if rotate_attr: + geom_prim.RemoveProperty(rotate_attr.GetName()) + + # translation + translate_op = geom_xform.AddTranslateOp(UsdGeom.XformOp.PrecisionDouble) + translate_op.Set(Gf.Vec3d(*cfg.translation)) + # rotation + orient_op = geom_xform.AddOrientOp(UsdGeom.XformOp.PrecisionDouble) + orient_op.Set(Gf.Quatd(*cfg.rotation)) + # scale + scale_op = geom_xform.AddScaleOp(UsdGeom.XformOp.PrecisionDouble) + scale_op.Set(Gf.Vec3d(*cfg.scale)) + # Handle instanceable # Create a new Xform prim that will be the prototype prim if cfg.make_instanceable: @@ -149,28 +196,18 @@ def _convert_asset(self, cfg: MeshConverterCfg): """ @staticmethod - async def _convert_mesh_to_usd( - in_file: str, out_file: str, prim_path: str = "/World", load_materials: bool = True - ) -> bool: + async def _convert_mesh_to_usd(in_file: str, out_file: str, load_materials: bool = True) -> bool: """Convert mesh from supported file types to USD. This function uses the Omniverse Asset Converter extension to convert a mesh file to USD. It is an asynchronous function and should be called using `asyncio.get_event_loop().run_until_complete()`. The converted asset is stored in the USD format in the specified output file. - The USD file has Y-up axis and is scaled to meters. - - The asset hierarchy is arranged as follows: - - .. code-block:: none - prim_path (default prim) - |- /geometry/Looks - |- /geometry/mesh + The USD file has Y-up axis and is scaled to cm. Args: in_file: The file to convert. out_file: The path to store the output file. - prim_path: The prim path of the mesh. load_materials: Set to True to enable attaching materials defined in the input file to the generated USD mesh. Defaults to True. @@ -178,11 +215,9 @@ async def _convert_mesh_to_usd( True if the conversion succeeds. """ enable_extension("omni.kit.asset_converter") - enable_extension("omni.usd.metrics.assembler") import omni.kit.asset_converter import omni.usd - from omni.metrics.assembler.core import get_metrics_assembler_interface # Create converter context converter_context = omni.kit.asset_converter.AssetConverterContext() @@ -203,29 +238,9 @@ async def _convert_mesh_to_usd( # Create converter task instance = omni.kit.asset_converter.get_instance() - out_file_non_metric = out_file.replace(".usd", "_non_metric.usd") - task = instance.create_converter_task(in_file, out_file_non_metric, None, converter_context) + task = instance.create_converter_task(in_file, out_file, None, converter_context) # Start conversion task and wait for it to finish - success = True - while True: - success = await task.wait_until_finished() - if not success: - await asyncio.sleep(0.1) - else: - break - - temp_stage = Usd.Stage.CreateInMemory() - UsdGeom.SetStageUpAxis(temp_stage, UsdGeom.Tokens.z) - UsdGeom.SetStageMetersPerUnit(temp_stage, 1.0) - UsdPhysics.SetStageKilogramsPerUnit(temp_stage, 1.0) - - base_prim = temp_stage.DefinePrim(prim_path, "Xform") - prim = temp_stage.DefinePrim(f"{prim_path}/geometry", "Xform") - prim.GetReferences().AddReference(out_file_non_metric) - cache = UsdUtils.StageCache.Get() - cache.Insert(temp_stage) - stage_id = cache.GetId(temp_stage).ToLongInt() - get_metrics_assembler_interface().resolve_stage(stage_id) - temp_stage.SetDefaultPrim(base_prim) - temp_stage.Export(out_file) + success = await task.wait_until_finished() + if not success: + raise RuntimeError(f"Failed to convert {in_file} to USD. Error: {task.get_error_message()}") return success diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py index fd6f9aedf44..2257424812c 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py @@ -37,3 +37,12 @@ class MeshConverterCfg(AssetConverterBaseCfg): Note: If None, then no mesh approximation properties will be added. """ + + translation: tuple[float, float, float] = (0.0, 0.0, 0.0) + """The translation of the mesh to the origin. Defaults to (0.0, 0.0, 0.0).""" + + rotation: tuple[float, float, float, float] = (1.0, 0.0, 0.0, 0.0) + """The rotation of the mesh in quaternion format (w, x, y, z). Defaults to (1.0, 0.0, 0.0, 0.0).""" + + scale: tuple[float, float, float] = (1.0, 1.0, 1.0) + """The scale of the mesh. Defaults to (1.0, 1.0, 1.0).""" \ No newline at end of file From e11cc39ac5337b667b0c27d88bcc16b79944c1a1 Mon Sep 17 00:00:00 2001 From: hapatel-bdai Date: Fri, 4 Apr 2025 14:37:22 -0400 Subject: [PATCH 3/8] additional code fixes --- .../isaaclab/isaaclab/sim/schemas/schemas.py | 62 +++++++++++++------ 1 file changed, 43 insertions(+), 19 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas.py b/source/isaaclab/isaaclab/sim/schemas/schemas.py index 03c21a28532..a38c06d5076 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas.py @@ -149,12 +149,12 @@ def modify_articulation_root_properties( # if we found a fixed joint, enable/disable it based on the input # otherwise, create a fixed joint between the world and the root link if existing_fixed_joint_prim is not None: - carb.log_info( + omni.log.info( f"Found an existing fixed joint for the articulation: '{prim_path}'. Setting it to: {fix_root_link}." ) existing_fixed_joint_prim.GetJointEnabledAttr().Set(fix_root_link) elif fix_root_link: - carb.log_info(f"Creating a fixed joint for the articulation: '{prim_path}'.") + omni.log.info(f"Creating a fixed joint for the articulation: '{prim_path}'.") # note: we have to assume that the root prim is a rigid body, # i.e. we don't handle the case where the root prim is not a rigid body but has articulation api on it @@ -518,10 +518,10 @@ def activate_contact_sensors(prim_path: str, threshold: float = 0.0, stage: Usd. rb.CreateSleepThresholdAttr().Set(0.0) # add contact report API with threshold of zero if not child_prim.HasAPI(PhysxSchema.PhysxContactReportAPI): - carb.log_verbose(f"Adding contact report API to prim: '{child_prim.GetPrimPath()}'") + omni.log.verbose(f"Adding contact report API to prim: '{child_prim.GetPrimPath()}'") cr_api = PhysxSchema.PhysxContactReportAPI.Apply(child_prim) else: - carb.log_verbose(f"Contact report API already exists on prim: '{child_prim.GetPrimPath()}'") + omni.log.verbose(f"Contact report API already exists on prim: '{child_prim.GetPrimPath()}'") cr_api = PhysxSchema.PhysxContactReportAPI.Get(stage, child_prim.GetPrimPath()) # set threshold to zero cr_api.CreateThresholdAttr().Set(threshold) @@ -547,7 +547,7 @@ def activate_contact_sensors(prim_path: str, threshold: float = 0.0, stage: Usd. @apply_nested def modify_joint_drive_properties( - prim_path: str, drive_props: schemas_cfg.JointDrivePropertiesCfg, stage: Usd.Stage | None = None + prim_path: str, cfg: schemas_cfg.JointDrivePropertiesCfg, stage: Usd.Stage | None = None ) -> bool: """Modify PhysX parameters for a joint prim. @@ -562,7 +562,7 @@ def modify_joint_drive_properties( .. caution:: We highly recommend modifying joint properties of articulations through the functionalities in the - :mod:`omni.isaac.lab.actuators` module. The methods here are for setting simulation low-level + :mod:`isaaclab.actuators` module. The methods here are for setting simulation low-level properties only. .. _UsdPhysics.DriveAPI: https://openusd.org/dev/api/class_usd_physics_drive_a_p_i.html @@ -570,7 +570,7 @@ def modify_joint_drive_properties( Args: prim_path: The prim path where to apply the joint drive schema. - drive_props: The configuration for the joint drive. + cfg: The configuration for the joint drive. stage: The stage where to find the prim. Defaults to None, in which case the current stage is used. @@ -605,10 +605,43 @@ def modify_joint_drive_properties( usd_drive_api = UsdPhysics.DriveAPI(prim, drive_api_name) if not usd_drive_api: usd_drive_api = UsdPhysics.DriveAPI.Apply(prim, drive_api_name) + # check if prim has Physx joint drive applied on it + physx_joint_api = PhysxSchema.PhysxJointAPI(prim) + if not physx_joint_api: + physx_joint_api = PhysxSchema.PhysxJointAPI.Apply(prim) + + # mapping from configuration name to USD attribute name + cfg_to_usd_map = { + "max_velocity": "max_joint_velocity", + "max_effort": "max_force", + "drive_type": "type", + } + # convert to dict + cfg = cfg.to_dict() + + # check if linear drive + is_linear_drive = prim.IsA(UsdPhysics.PrismaticJoint) + # convert values for angular drives from radians to degrees units + if not is_linear_drive: + if cfg["max_velocity"] is not None: + # rad / s --> deg / s + cfg["max_velocity"] = cfg["max_velocity"] * 180.0 / math.pi + if cfg["stiffness"] is not None: + # N-m/rad --> N-m/deg + cfg["stiffness"] = cfg["stiffness"] * math.pi / 180.0 + if cfg["damping"] is not None: + # N-m-s/rad --> N-m-s/deg + cfg["damping"] = cfg["damping"] * math.pi / 180.0 - # change the drive type to input - if drive_props.drive_type is not None: - usd_drive_api.CreateTypeAttr().Set(drive_props.drive_type) + # set into PhysX API + for attr_name in ["max_velocity"]: + value = cfg.pop(attr_name, None) + attr_name = cfg_to_usd_map[attr_name] + safe_set_attribute_on_usd_schema(physx_joint_api, attr_name, value, camel_case=True) + # set into USD API + for attr_name, attr_value in cfg.items(): + attr_name = cfg_to_usd_map.get(attr_name, attr_name) + safe_set_attribute_on_usd_schema(usd_drive_api, attr_name, attr_value, camel_case=True) return True @@ -835,10 +868,8 @@ def modify_deformable_body_properties( # success return True - """ Collision mesh properties. - """ @@ -888,15 +919,12 @@ def define_mesh_collision_properties( prim_path: str, cfg: schemas_cfg.MeshCollisionPropertiesCfg, stage: Usd.Stage | None = None ): """Apply the mesh collision schema on the input prim and set its properties. - See :func:`modify_collision_mesh_properties` for more details on how the properties are set. - Args: prim_path : The prim path where to apply the mesh collision schema. cfg : The configuration for the mesh collision properties. stage : The stage where to find the prim. Defaults to None, in which case the current stage is used. - Raises: ValueError: When the prim path is not valid. """ @@ -923,15 +951,11 @@ def modify_mesh_collision_properties( prim_path: str, cfg: schemas_cfg.MeshCollisionPropertiesCfg, stage: Usd.Stage | None = None ): """Set properties for the mesh collision of a prim. - These properties are based on either the `Phsyx the `UsdPhysics.MeshCollisionAPI` schema. - .. note:: This function is decorated with :func:`apply_nested` that sets the properties to all the prims (that have the schema applied on them) under the input prim path. - .. UsdPhysics.MeshCollisionAPI: https://openusd.org/release/api/class_usd_physics_mesh_collision_a_p_i.html - Args: prim_path : The prim path of the rigid body. This prim should be a Mesh prim. cfg : The configuration for the mesh collision properties. From 53091cca730c4514b4ff0da7f72f6827d3dfd014 Mon Sep 17 00:00:00 2001 From: hapatel-bdai Date: Fri, 4 Apr 2025 14:41:50 -0400 Subject: [PATCH 4/8] formatting --- .../isaaclab/sim/converters/mesh_converter_cfg.py | 2 +- source/isaaclab/isaaclab/sim/schemas/schemas.py | 8 ++------ source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py | 2 +- 3 files changed, 4 insertions(+), 8 deletions(-) diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py index 2257424812c..80e8d20b143 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter_cfg.py @@ -45,4 +45,4 @@ class MeshConverterCfg(AssetConverterBaseCfg): """The rotation of the mesh in quaternion format (w, x, y, z). Defaults to (1.0, 0.0, 0.0, 0.0).""" scale: tuple[float, float, float] = (1.0, 1.0, 1.0) - """The scale of the mesh. Defaults to (1.0, 1.0, 1.0).""" \ No newline at end of file + """The scale of the mesh. Defaults to (1.0, 1.0, 1.0).""" diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas.py b/source/isaaclab/isaaclab/sim/schemas/schemas.py index a38c06d5076..35253c893db 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas.py @@ -868,6 +868,7 @@ def modify_deformable_body_properties( # success return True + """ Collision mesh properties. """ @@ -970,11 +971,6 @@ def modify_mesh_collision_properties( api_func, custom_attrs = extract_mesh_collision_api_and_attrs(cfg=cfg) - # check if prim has mesh collision api applied on it - if not api_func(prim): - print("****") - # return False - # retrieve the mesh collision API mesh_collision_api = api_func(prim) @@ -988,4 +984,4 @@ def modify_mesh_collision_properties( safe_set_attribute_on_usd_schema(mesh_collision_api, attr_name, value, camel_case=camel_case) # success - return True \ No newline at end of file + return True diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py index e900d70d04d..e74b576c24a 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py @@ -593,4 +593,4 @@ class SDFMeshPropertiesCfg(MeshCollisionPropertiesCfg): Default value is 6. Range: [0, inf) - """ \ No newline at end of file + """ From e8b0640b72df108c334d7fbf905bf5a57feb6151 Mon Sep 17 00:00:00 2001 From: hapatel-bdai Date: Fri, 4 Apr 2025 14:43:21 -0400 Subject: [PATCH 5/8] more formatting --- source/isaaclab/isaaclab/sim/schemas/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/isaaclab/isaaclab/sim/schemas/__init__.py b/source/isaaclab/isaaclab/sim/schemas/__init__.py index 0772915cae7..b517be3d732 100644 --- a/source/isaaclab/isaaclab/sim/schemas/__init__.py +++ b/source/isaaclab/isaaclab/sim/schemas/__init__.py @@ -108,4 +108,4 @@ # Constants for configs that use PhysX vs USD API "PHYSX_MESH_COLLISION_CFGS", "USD_MESH_COLLISION_CFGS", -] \ No newline at end of file +] From dd49dd3698786e819bde511f02fa1a62c3b4ad3b Mon Sep 17 00:00:00 2001 From: Harsh Patel Date: Mon, 7 Apr 2025 15:47:23 -0400 Subject: [PATCH 6/8] Update CONTRIBUTORS.md Added to contributors list Signed-off-by: Harsh Patel --- CONTRIBUTORS.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index deca7c88f9b..6a45ffc9fd6 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -53,6 +53,7 @@ Guidelines for modifications: * Gary Lvov * Giulio Romualdi * Haoran Zhou +* Harsh Patel * HoJin Jeon * Hongwei Xiong * Hongyu Li From c1c5b44e909a11d1669647bc9ca817a6c4263e32 Mon Sep 17 00:00:00 2001 From: Harsh Patel Date: Fri, 18 Apr 2025 09:43:40 -0400 Subject: [PATCH 7/8] Update schemas_cfg.py Signed-off-by: Harsh Patel --- source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py index e74b576c24a..08cf9538ab9 100644 --- a/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py +++ b/source/isaaclab/isaaclab/sim/schemas/schemas_cfg.py @@ -406,7 +406,7 @@ class MeshCollisionPropertiesCfg: See :meth:`set_mesh_collision_properties` for more information. .. note:: - If the values are None, they are not modified. This is useful when you want to set only a subset of + If the values are MISSING, they are not modified. This is useful when you want to set only a subset of the properties and leave the rest as-is. """ From 14f0665b12d2b5e7ab53080986b5381a5ff050f3 Mon Sep 17 00:00:00 2001 From: Harsh Patel Date: Fri, 18 Apr 2025 09:44:08 -0400 Subject: [PATCH 8/8] Update configclass.py Signed-off-by: Harsh Patel --- source/isaaclab/isaaclab/utils/configclass.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/isaaclab/isaaclab/utils/configclass.py b/source/isaaclab/isaaclab/utils/configclass.py index 1ffc7e52587..b3942ffda0f 100644 --- a/source/isaaclab/isaaclab/utils/configclass.py +++ b/source/isaaclab/isaaclab/utils/configclass.py @@ -47,7 +47,7 @@ def configclass(cls, **kwargs): from dataclasses import MISSING - from isaaclabz.utils.configclass import configclass + from isaaclab.utils.configclass import configclass @configclass