Unverified Commit 0a6079d2 authored by Mayank Mittal's avatar Mayank Mittal Committed by GitHub

Adds APIs for spawning deformable meshes (#613)

# Description

This MR adds schemas and spawners to create deformable bodies based on
primitive shapes. It uses the latest PhysX 5.4 support for FEM
simulation of deformable bodies. The MR adds the required demo and docs
changes.

## Type of change

- New feature (non-breaking change which adds functionality)
- This change requires a documentation update

## Screenshots

https://github.com/isaac-sim/IsaacLab/assets/12863862/9c239d6d-098d-4c70-b6fd-0a73c74c80c4

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [ ] I have added tests that prove my fix is effective or that my
feature works
- [ ] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there
parent 8cf6647a
......@@ -13,6 +13,7 @@
MassPropertiesCfg
JointDrivePropertiesCfg
FixedTendonPropertiesCfg
DeformableBodyPropertiesCfg
.. rubric:: Functions
......@@ -29,6 +30,8 @@
modify_mass_properties
modify_joint_drive_properties
modify_fixed_tendon_properties
define_deformable_body_properties
modify_deformable_body_properties
Articulation Root
-----------------
......@@ -88,3 +91,13 @@ Fixed Tendon
:exclude-members: __init__
.. autofunction:: modify_fixed_tendon_properties
Deformable Body
---------------
.. autoclass:: DeformableBodyPropertiesCfg
:members:
:exclude-members: __init__
.. autofunction:: define_deformable_body_properties
.. autofunction:: modify_deformable_body_properties
......@@ -8,6 +8,7 @@
.. autosummary::
shapes
meshes
lights
sensors
from_files
......@@ -19,6 +20,7 @@
SpawnerCfg
RigidObjectSpawnerCfg
DeformableObjectSpawnerCfg
Spawners
--------
......@@ -32,6 +34,11 @@ Spawners
:show-inheritance:
:exclude-members: __init__
.. autoclass:: DeformableObjectSpawnerCfg
:members:
:show-inheritance:
:exclude-members: __init__
Shapes
------
......@@ -87,6 +94,60 @@ Shapes
:show-inheritance:
:exclude-members: __init__, func
Meshes
------
.. automodule:: omni.isaac.lab.sim.spawners.meshes
.. rubric:: Classes
.. autosummary::
MeshCfg
MeshCapsuleCfg
MeshConeCfg
MeshCuboidCfg
MeshCylinderCfg
MeshSphereCfg
.. autoclass:: MeshCfg
:members:
:exclude-members: __init__, func
.. autofunction:: spawn_mesh_capsule
.. autoclass:: MeshCapsuleCfg
:members:
:show-inheritance:
:exclude-members: __init__, func
.. autofunction:: spawn_mesh_cone
.. autoclass:: MeshConeCfg
:members:
:show-inheritance:
:exclude-members: __init__, func
.. autofunction:: spawn_mesh_cuboid
.. autoclass:: MeshCuboidCfg
:members:
:show-inheritance:
:exclude-members: __init__, func
.. autofunction:: spawn_mesh_cylinder
.. autoclass:: MeshCylinderCfg
:members:
:show-inheritance:
:exclude-members: __init__, func
.. autofunction:: spawn_mesh_sphere
.. autoclass:: MeshSphereCfg
:members:
:show-inheritance:
:exclude-members: __init__, func
Lights
------
......@@ -198,6 +259,7 @@ Materials
GlassMdlCfg
PhysicsMaterialCfg
RigidBodyMaterialCfg
DeformableBodyMaterialCfg
Visual Materials
~~~~~~~~~~~~~~~~
......@@ -234,3 +296,9 @@ Physical Materials
.. autoclass:: RigidBodyMaterialCfg
:members:
:exclude-members: __init__, func
.. autofunction:: spawn_deformable_body_material
.. autoclass:: DeformableBodyMaterialCfg
:members:
:exclude-members: __init__, func
......@@ -35,6 +35,12 @@ A few quick showroom scripts to run and checkout:
./isaaclab.sh -p source/standalone/demos/procedural_terrain.py
- Spawn different deformable (soft) bodies and let them fall from a height:
.. code:: bash
./isaaclab.sh -p source/standalone/demos/deformables.py
- Spawn multiple markers that are useful for visualizations:
.. code:: bash
......
......@@ -22,7 +22,7 @@ Let's take a look at the Python script:
.. literalinclude:: ../../../../source/standalone/tutorials/00_sim/spawn_prims.py
:language: python
:emphasize-lines: 40-79, 91-92
:emphasize-lines: 40-88, 100-101
:linenos:
......@@ -134,8 +134,17 @@ default to the default values set by USD Physics.
.. literalinclude:: ../../../../source/standalone/tutorials/00_sim/spawn_prims.py
:language: python
:start-at: # spawn a green cone with colliders and rigid body
:end-before: # spawn a usd file of a table into the scene
:end-before: # spawn a blue cuboid with deformable body
Lastly, we spawn a cuboid ``CuboidDeformable`` which contains deformable body physics properties. Unlike the
rigid body simulation, a deformable body can have relative motion between its vertices. This is useful for simulating
soft bodies like cloth, rubber, or jello. It is important to note that deformable bodies are only supported in
GPU simulation and require a mesh object to be spawned with the deformable body physics properties.
.. literalinclude:: ../../../../source/standalone/tutorials/00_sim/spawn_prims.py
:language: python
:start-at: # spawn a blue cuboid with deformable body
:end-before: # spawn a usd file of a table into the scene
Spawning from another file
--------------------------
......
[package]
# Note: Semantic Versioning is used: https://semver.org/
version = "0.19.2"
version = "0.19.3"
# Description
title = "Isaac Lab framework for Robot Learning"
......
Changelog
---------
0.19.3 (2024-07-13)
~~~~~~~~~~~~~~~~~~~
Added
^^^^^
* Added schemas for setting and modifying deformable body properties on a USD prim.
* Added API to spawn a deformable body material in the simulation.
* Added APIs to spawn rigid and deformable meshes of primitive shapes (cone, cylinder, sphere, box, capsule)
in the simulation. This is possible through the :mod:`omni.isaac.lab.sim.spawners.meshes` module.
0.19.2 (2024-07-05)
~~~~~~~~~~~~~~~~~~~
Changed
^^^^^^^
* Modified cloning scheme based on the attribute :attr:`~omni.isaac.lab.scene.InteractiveSceneCfg.replicate_physics` to determine whether environment is homogeneous or heterogeneous.
* Modified cloning scheme based on the attribute :attr:`~omni.isaac.lab.scene.InteractiveSceneCfg.replicate_physics`
to determine whether environment is homogeneous or heterogeneous.
0.19.1 (2024-07-05)
......
......@@ -102,7 +102,7 @@ class MeshConverter(AssetConverterBase):
# Apply collider properties to mesh
if cfg.collision_props is not None:
# -- Collision approximation to mesh
# TODO: https://github.com/isaac-orbit/orbit/issues/163 Move this to a new Schema
# 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.
......
......@@ -27,8 +27,8 @@ The schemas are defined in the following links:
Locally, the schemas are defined in the following files:
* ``_isaac_sim/kit/extsPhysics/omni.usd.schema.physics/plugins/UsdPhysics/resources/UsdPhysics/schema.usda``
* ``_isaac_sim/kit/extsPhysics/omni.usd.schema.physx/plugins/PhysxSchema/resources/PhysxSchema/schema.usda``
* ``_isaac_sim/extsPhysics/omni.usd.schema.physics/plugins/UsdPhysics/resources/UsdPhysics/schema.usda``
* ``_isaac_sim/extsPhysics/omni.usd.schema.physx/plugins/PhysxSchema/resources/generatedSchema.usda``
"""
......@@ -36,10 +36,12 @@ from .schemas import (
activate_contact_sensors,
define_articulation_root_properties,
define_collision_properties,
define_deformable_body_properties,
define_mass_properties,
define_rigid_body_properties,
modify_articulation_root_properties,
modify_collision_properties,
modify_deformable_body_properties,
modify_fixed_tendon_properties,
modify_joint_drive_properties,
modify_mass_properties,
......@@ -48,6 +50,7 @@ from .schemas import (
from .schemas_cfg import (
ArticulationRootPropertiesCfg,
CollisionPropertiesCfg,
DeformableBodyPropertiesCfg,
FixedTendonPropertiesCfg,
JointDrivePropertiesCfg,
MassPropertiesCfg,
......
......@@ -9,9 +9,15 @@ from __future__ import annotations
import carb
import omni.isaac.core.utils.stage as stage_utils
import omni.physx.scripts.utils as physx_utils
from omni.physx.scripts import deformableUtils as deformable_utils
from pxr import PhysxSchema, Usd, UsdPhysics
from ..utils import apply_nested, find_global_fixed_joint_prim, safe_set_attribute_on_usd_schema
from ..utils import (
apply_nested,
find_global_fixed_joint_prim,
get_all_matching_child_prims,
safe_set_attribute_on_usd_schema,
)
from . import schemas_cfg
"""
......@@ -78,7 +84,7 @@ def modify_articulation_root_properties(
This function is decorated with :func:`apply_nested` that set the properties to all the prims
(that have the schema applied on them) under the input prim path.
.. _articulation root: https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/Articulations.html
.. _articulation root: https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/docs/Articulations.html
.. _ArticulationRootAPI: https://openusd.org/dev/api/class_usd_physics_articulation_root_a_p_i.html
.. _PhysxArticulationAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_articulation_a_p_i.html
......@@ -228,7 +234,7 @@ def modify_rigid_body_properties(
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.
.. _rigid body: https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/RigidBodyOverview.html
.. _rigid body: https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/docs/RigidBodyOverview.html
.. _kinematic body: https://openusd.org/release/wp_rigid_body_physics.html#kinematic-bodies
.. _RigidBodyAPI: https://openusd.org/dev/api/class_usd_physics_rigid_body_a_p_i.html
.. _PhysxRigidBodyAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_rigid_body_a_p_i.html
......@@ -317,7 +323,7 @@ def modify_collision_properties(
Tuning these parameters influence the contact behavior of the rigid body. For more information on
tune them and their effect on the simulation, please refer to the
`PhysX documentation <https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/AdvancedCollisionDetection.html>`__.
`PhysX documentation <https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/docs/AdvancedCollisionDetection.html>`__.
.. note::
This function is decorated with :func:`apply_nested` that sets the properties to all the prims
......@@ -651,3 +657,162 @@ def modify_fixed_tendon_properties(
safe_set_attribute_on_usd_schema(physx_tendon_axis_api, attr_name, value, camel_case=True)
# success
return True
"""
Deformable body properties.
"""
def define_deformable_body_properties(
prim_path: str, cfg: schemas_cfg.DeformableBodyPropertiesCfg, stage: Usd.Stage | None = None
):
"""Apply the deformable body schema on the input prim and set its properties.
See :func:`modify_deformable_body_properties` for more details on how the properties are set.
.. note::
If the input prim is not a mesh, this function will traverse the prim and find the first mesh
under it. If no mesh or multiple meshes are found, an error is raised. This is because the deformable
body schema can only be applied to a single mesh.
Args:
prim_path: The prim path where to apply the deformable body schema.
cfg: The configuration for the deformable body.
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.
ValueError: When the prim has no mesh or multiple meshes.
"""
# 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.")
# traverse the prim and get the mesh
matching_prims = get_all_matching_child_prims(prim_path, lambda p: p.GetTypeName() == "Mesh")
# check if the mesh is valid
if len(matching_prims) == 0:
raise ValueError(f"Could not find any mesh in '{prim_path}'. Please check asset.")
if len(matching_prims) > 1:
# get list of all meshes found
mesh_paths = [p.GetPrimPath() for p in matching_prims]
raise ValueError(
f"Found multiple meshes in '{prim_path}': {mesh_paths}."
" Deformable body schema can only be applied to one mesh."
)
# get deformable-body USD prim
mesh_prim = matching_prims[0]
# check if prim has deformable-body applied on it
if not PhysxSchema.PhysxDeformableBodyAPI(mesh_prim):
PhysxSchema.PhysxDeformableBodyAPI.Apply(mesh_prim)
# set deformable body properties
modify_deformable_body_properties(mesh_prim.GetPrimPath(), cfg, stage)
@apply_nested
def modify_deformable_body_properties(
prim_path: str, cfg: schemas_cfg.DeformableBodyPropertiesCfg, stage: Usd.Stage | None = None
):
"""Modify PhysX parameters for a deformable body prim.
A `deformable body`_ is a single body that can be simulated by PhysX. Unlike rigid bodies, deformable bodies
support relative motion of the nodes in the mesh. Consequently, they can be used to simulate deformations
under applied forces.
PhysX soft body simulation employs Finite Element Analysis (FEA) to simulate the deformations of the mesh.
It uses two tetrahedral meshes to represent the deformable body:
1. **Simulation mesh**: This mesh is used for the simulation and is the one that is deformed by the solver.
2. **Collision mesh**: This mesh only needs to match the surface of the simulation mesh and is used for
collision detection.
For most applications, we assume that the above two meshes are computed from the "render mesh" of the deformable
body. The render mesh is the mesh that is visible in the scene and is used for rendering purposes. It is composed
of triangles and is the one that is used to compute the above meshes based on PhysX cookings.
The schema comprises of attributes that belong to the `PhysxDeformableBodyAPI`_. schemas containing the PhysX
parameters for the deformable body.
.. caution::
The deformable body schema is still under development by the Omniverse team. The current implementation
works with the PhysX schemas shipped with Isaac Sim 4.0.0. It may change in future releases.
.. 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.
.. _deformable body: https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/docs/SoftBodies.html
.. _PhysxDeformableBodyAPI: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_deformable_a_p_i.html
Args:
prim_path: The prim path to the deformable body.
cfg: The configuration for the deformable body.
stage: The stage where to find the prim. Defaults to None, in which case the
current stage is used.
Returns:
True if the properties were successfully set, False otherwise.
"""
# obtain stage
if stage is None:
stage = stage_utils.get_current_stage()
# get deformable-body USD prim
deformable_body_prim = stage.GetPrimAtPath(prim_path)
# check if the prim is valid and has the deformable-body API
if not deformable_body_prim.IsValid() or not PhysxSchema.PhysxDeformableBodyAPI(deformable_body_prim):
return False
# retrieve the physx deformable-body api
physx_deformable_body_api = PhysxSchema.PhysxDeformableBodyAPI(deformable_body_prim)
# retrieve the physx deformable api
physx_deformable_api = PhysxSchema.PhysxDeformableAPI(physx_deformable_body_api)
# convert to dict
cfg = cfg.to_dict()
# set into deformable body API
attr_kwargs = {
attr_name: cfg.pop(attr_name)
for attr_name in [
"kinematic_enabled",
"collision_simplification",
"collision_simplification_remeshing",
"collision_simplification_remeshing_resolution",
"collision_simplification_target_triangle_count",
"collision_simplification_force_conforming",
"simulation_hexahedral_resolution",
"solver_position_iteration_count",
"vertex_velocity_damping",
"sleep_damping",
"sleep_threshold",
"settling_threshold",
"self_collision",
"self_collision_filter_distance",
]
}
status = deformable_utils.add_physx_deformable_body(stage, prim_path=prim_path, **attr_kwargs)
# check if the deformable body was successfully added
if not status:
return False
# obtain the PhysX collision API (this is set when the deformable body is added)
physx_collision_api = PhysxSchema.PhysxCollisionAPI(deformable_body_prim)
# set into PhysX API
for attr_name, value in cfg.items():
if attr_name in ["rest_offset", "collision_offset"]:
safe_set_attribute_on_usd_schema(physx_collision_api, attr_name, value, camel_case=True)
else:
safe_set_attribute_on_usd_schema(physx_deformable_api, attr_name, value, camel_case=True)
# success
return True
......@@ -21,16 +21,22 @@ class ArticulationRootPropertiesCfg:
articulation_enabled: bool | None = None
"""Whether to enable or disable articulation."""
enabled_self_collisions: bool | None = None
"""Whether to enable or disable self-collisions."""
solver_position_iteration_count: int | None = None
"""Solver position iteration counts for the body."""
solver_velocity_iteration_count: int | None = None
"""Solver position iteration counts for the body."""
sleep_threshold: float | None = None
"""Mass-normalized kinetic energy threshold below which an actor may go to sleep."""
stabilization_threshold: float | None = None
"""The mass-normalized kinetic energy threshold below which an articulation may participate in stabilization."""
fix_root_link: bool | None = None
"""Whether to fix the root link of the articulation.
......@@ -58,6 +64,7 @@ class RigidBodyPropertiesCfg:
rigid_body_enabled: bool | None = None
"""Whether to enable or disable the rigid body."""
kinematic_enabled: bool | None = None
"""Determines whether the body is kinematic or not.
......@@ -66,30 +73,43 @@ class RigidBodyPropertiesCfg:
For more information on kinematic bodies, please refer to the `documentation <https://openusd.org/release/wp_rigid_body_physics.html#kinematic-bodies>`_.
"""
disable_gravity: bool | None = None
"""Disable gravity for the actor."""
linear_damping: float | None = None
"""Linear damping for the body."""
angular_damping: float | None = None
"""Angular damping for the body."""
max_linear_velocity: float | None = None
"""Maximum linear velocity for rigid bodies (in m/s)."""
max_angular_velocity: float | None = None
"""Maximum angular velocity for rigid bodies (in deg/s)."""
max_depenetration_velocity: float | None = None
"""Maximum depenetration velocity permitted to be introduced by the solver (in m/s)."""
max_contact_impulse: float | None = None
"""The limit on the impulse that may be applied at a contact."""
enable_gyroscopic_forces: bool | None = None
"""Enables computation of gyroscopic forces on the rigid body."""
retain_accelerations: bool | None = None
"""Carries over forces/accelerations over sub-steps."""
solver_position_iteration_count: int | None = None
"""Solver position iteration counts for the body."""
solver_velocity_iteration_count: int | None = None
"""Solver position iteration counts for the body."""
sleep_threshold: float | None = None
"""Mass-normalized kinetic energy threshold below which an actor may go to sleep."""
stabilization_threshold: float | None = None
"""The mass-normalized kinetic energy threshold below which an actor may participate in stabilization."""
......@@ -107,6 +127,7 @@ class CollisionPropertiesCfg:
collision_enabled: bool | None = None
"""Whether to enable or disable collisions."""
contact_offset: float | None = None
"""Contact offset for the collision shape (in m).
......@@ -114,6 +135,7 @@ class CollisionPropertiesCfg:
contact offsets. This quantity should be non-negative which means that contact generation can potentially start
before the shapes actually penetrate.
"""
rest_offset: float | None = None
"""Rest offset for the collision shape (in m).
......@@ -121,12 +143,14 @@ class CollisionPropertiesCfg:
vertically stacked objects is the sum of their rest offsets. If a pair of shapes have a positive rest
offset, the shapes will be separated at rest by an air gap.
"""
torsional_patch_radius: float | None = None
"""Radius of the contact patch for applying torsional friction (in m).
It is used to approximate rotational friction introduced by the compression of contacting surfaces.
If the radius is zero, no torsional friction is applied.
"""
min_torsional_patch_radius: float | None = None
"""Minimum radius of the contact patch for applying torsional friction (in m)."""
......@@ -148,6 +172,7 @@ class MassPropertiesCfg:
Note:
If non-zero, the mass is ignored and the density is used to compute the mass.
"""
density: float | None = None
"""The density of the rigid body (in kg/m^3).
......@@ -188,17 +213,155 @@ class FixedTendonPropertiesCfg:
tendon_enabled: bool | None = None
"""Whether to enable or disable the tendon."""
stiffness: float | None = None
"""Spring stiffness term acting on the tendon's length."""
damping: float | None = None
"""The damping term acting on both the tendon length and the tendon-length limits."""
limit_stiffness: float | None = None
"""Limit stiffness term acting on the tendon's length limits."""
offset: float | None = None
"""Length offset term for the tendon.
It defines an amount to be added to the accumulated length computed for the tendon. This allows the application
to actuate the tendon by shortening or lengthening it.
"""
rest_length: float | None = None
"""Spring rest length of the tendon."""
@configclass
class DeformableBodyPropertiesCfg:
"""Properties to apply to a deformable body.
A deformable body is a body that can deform under forces. The configuration allows users to specify
the properties of the deformable body, such as the solver iteration counts, damping, and self-collision.
An FEM-based deformable body is created by providing a collision mesh and simulation mesh. The collision mesh
is used for collision detection and the simulation mesh is used for simulation. The collision mesh is usually
a simplified version of the simulation mesh.
Based on the above, the PhysX team provides APIs to either set the simulation and collision mesh directly
(by specifying the points) or to simplify the collision mesh based on the simulation mesh. The simplification
process involves remeshing the collision mesh and simplifying it based on the target triangle count.
Since specifying the collision mesh points directly is not a common use case, we only expose the parameters
to simplify the collision mesh based on the simulation mesh. If you want to provide the collision mesh points,
please open an issue on the repository and we can add support for it.
See :meth:`modify_deformable_body_properties` for more information.
.. note::
If the values are :obj:`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.
"""
deformable_enabled: bool | None = None
"""Enables deformable body."""
kinematic_enabled: bool = False
"""Enables kinematic body. Defaults to False, which means that the body is not kinematic.
Similar to rigid bodies, this allows setting user-driven motion for the deformable body. For more information,
please refer to the `documentation <https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/docs/SoftBodies.html#kinematic-soft-bodies>`__.
"""
self_collision: bool | None = None
"""Whether to enable or disable self-collisions for the deformable body based on the rest position distances."""
self_collision_filter_distance: float | None = None
"""Penetration value that needs to get exceeded before contacts for self collision are generated.
This parameter must be greater than of equal to twice the :attr:`rest_offset` value.
This value has an effect only if :attr:`self_collision` is enabled.
"""
settling_threshold: float | None = None
"""Threshold vertex velocity (in m/s) under which sleep damping is applied in addition to velocity damping."""
sleep_damping: float | None = None
"""Coefficient for the additional damping term if fertex velocity drops below setting threshold."""
sleep_threshold: float | None = None
"""The velocity threshold (in m/s) under which the vertex becomes a candidate for sleeping in the next step."""
solver_position_iteration_count: int | None = None
"""Number of the solver positional iterations per step. Range is [1,255]"""
vertex_velocity_damping: float | None = None
"""Coefficient for artificial damping on the vertex velocity.
This parameter can be used to approximate the effect of air drag on the deformable body.
"""
simulation_hexahedral_resolution: int = 10
"""The target resolution for the hexahedral mesh used for simulation. Defaults to 10.
Note:
This value is ignored if the user provides the simulation mesh points directly. However, we assume that
most users will not provide the simulation mesh points directly. If you want to provide the simulation mesh
directly, please set this value to :obj:`None`.
"""
collision_simplification: bool = True
"""Whether or not to simplify the collision mesh before creating a soft body out of it. Defaults to True.
Note:
This flag is ignored if the user provides the simulation mesh points directly. However, we assume that
most users will not provide the simulation mesh points directly. Hence, this flag is enabled by default.
If you want to provide the simulation mesh points directly, please set this flag to False.
"""
collision_simplification_remeshing: bool = True
"""Whether or not the collision mesh should be remeshed before simplification. Defaults to True.
This parameter is ignored if :attr:`collision_simplification` is False.
"""
collision_simplification_remeshing_resolution: int = 0
"""The resolution used for remeshing. Defaults to 0, which means that a heuristic is used to determine the
resolution.
This parameter is ignored if :attr:`collision_simplification_remeshing` is False.
"""
collision_simplification_target_triangle_count: int = 0
"""The target triangle count used for the simplification. Defaults to 0, which means that a heuristic based on
the :attr:`simulation_hexahedral_resolution` is used to determine the target count.
This parameter is ignored if :attr:`collision_simplification` is False.
"""
collision_simplification_force_conforming: bool = True
"""Whether or not the simplification should force the output mesh to conform to the input mesh. Defaults to True.
The flag indicates that the tretrahedralizer used to generate the collision mesh should produce tetrahedra
that conform to the triangle mesh. If False, the simplifier uses the output from the tretrahedralizer used.
This parameter is ignored if :attr:`collision_simplification` is False.
"""
contact_offset: float | None = None
"""Contact offset for the collision shape (in m).
The collision detector generates contact points as soon as two shapes get closer than the sum of their
contact offsets. This quantity should be non-negative which means that contact generation can potentially start
before the shapes actually penetrate.
"""
rest_offset: float | None = None
"""Rest offset for the collision shape (in m).
The rest offset quantifies how close a shape gets to others at rest, At rest, the distance between two
vertically stacked objects is the sum of their rest offsets. If a pair of shapes have a positive rest
offset, the shapes will be separated at rest by an air gap.
"""
max_depenetration_velocity: float | None = None
"""Maximum depenetration velocity permitted to be introduced by the solver (in m/s)."""
......@@ -133,7 +133,7 @@ class SimulationContext(_SimulationContext):
carb_settings_iface.set_bool("/physics/disableContactProcessing", True)
# enable custom geometry for cylinder and cone collision shapes to allow contact reporting for them
# reason: cylinders and cones aren't natively supported by PhysX so we need to use custom geometry flags
# reference: https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/Geometry.html?highlight=capsule#geometry
# reference: https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/docs/Geometry.html?highlight=capsule#geometry
carb_settings_iface.set_bool("/physics/collisionConeCustomGeometry", False)
carb_settings_iface.set_bool("/physics/collisionCylinderCustomGeometry", False)
# note: we read this once since it is not expected to change during runtime
......@@ -522,7 +522,7 @@ class SimulationContext(_SimulationContext):
raise RuntimeError("Physics scene API is None! Please create the scene first.")
# set parameters not directly supported by the constructor
# -- Continuous Collision Detection (CCD)
# ref: https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/docs/AdvancedCollisionDetection.html?highlight=ccd#continuous-collision-detection
# ref: https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/docs/AdvancedCollisionDetection.html?highlight=ccd#continuous-collision-detection
self._physics_context.enable_ccd(self.cfg.physx.enable_ccd)
# -- GPU collision stack size
physx_scene_api.CreateGpuCollisionStackSizeAttr(self.cfg.physx.gpu_collision_stack_size)
......
......@@ -57,6 +57,7 @@ For example:
from .from_files import * # noqa: F401, F403
from .lights import * # noqa: F401, F403
from .materials import * # noqa: F401, F403
from .meshes import * # noqa: F401, F403
from .sensors import * # noqa: F401, F403
from .shapes import * # noqa: F401, F403
from .spawner_cfg import * # noqa: F401, F403
......@@ -246,19 +246,23 @@ def _spawn_from_usd_file(
# modify mass properties
if cfg.mass_props is not None:
schemas.modify_mass_properties(prim_path, cfg.mass_props)
# modify articulation root properties
if cfg.articulation_props is not None:
schemas.modify_articulation_root_properties(prim_path, cfg.articulation_props)
# modify tendon properties
if cfg.fixed_tendons_props is not None:
schemas.modify_fixed_tendon_properties(prim_path, cfg.fixed_tendons_props)
# define drive API on the joints
# note: these are only for setting low-level simulation properties. all others should be set or are
# and overridden by the articulation/actuator properties.
if cfg.joint_drive_props is not None:
schemas.modify_joint_drive_properties(prim_path, cfg.joint_drive_props)
# modify deformable body properties
if cfg.deformable_props is not None:
schemas.modify_deformable_body_properties(prim_path, cfg.deformable_props)
# apply visual material
if cfg.visual_material is not None:
if not cfg.visual_material_path.startswith("/"):
......
......@@ -10,7 +10,7 @@ from dataclasses import MISSING
from omni.isaac.lab.sim import converters, schemas
from omni.isaac.lab.sim.spawners import materials
from omni.isaac.lab.sim.spawners.spawner_cfg import RigidObjectSpawnerCfg, SpawnerCfg
from omni.isaac.lab.sim.spawners.spawner_cfg import DeformableObjectSpawnerCfg, RigidObjectSpawnerCfg, SpawnerCfg
from omni.isaac.lab.utils import configclass
from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR
......@@ -18,12 +18,19 @@ from . import from_files
@configclass
class FileCfg(RigidObjectSpawnerCfg):
class FileCfg(RigidObjectSpawnerCfg, DeformableObjectSpawnerCfg):
"""Configuration parameters for spawning an asset from a file.
This class is a base class for spawning assets from files. It includes the common parameters
for spawning assets from files, such as the path to the file and the function to use for spawning
the asset.
Note:
By default, all properties are set to None. This means that no properties will be added or modified
to the prim outside of the properties available by default when spawning the prim.
If they are set to a value, then the properties are modified on the spawned prim in a nested manner.
This is done by calling the respective function with the specified properties.
"""
scale: tuple[float, float, float] | None = None
......@@ -57,11 +64,27 @@ class FileCfg(RigidObjectSpawnerCfg):
class UsdFileCfg(FileCfg):
"""USD file to spawn asset from.
USD files are imported directly into the scene. However, given their complexity, there are various different
operations that can be performed on them. For example, selecting variants, applying materials, or modifying
existing properties.
To prevent the explosion of configuration parameters, the available operations are limited to the most common
ones. These include:
- **Selecting variants**: This is done by specifying the :attr:`variants` parameter.
- **Creating and applying materials**: This is done by specifying the :attr:`visual_material` and
:attr:`physics_material` parameters.
- **Modifying existing properties**: This is done by specifying the respective properties in the configuration
class. For instance, to modify the scale of the imported prim, set the :attr:`scale` parameter.
See :meth:`spawn_from_usd` for more information.
.. note::
The configuration parameters include various properties. If not `None`, these properties
are modified on the spawned prim in a nested manner.
If they are set to a value, then the properties are modified on the spawned prim in a nested manner.
This is done by calling the respective function with the specified properties.
"""
func: Callable = from_files.spawn_from_usd
......@@ -83,11 +106,18 @@ class UrdfFileCfg(FileCfg, converters.UrdfConverterCfg):
"""URDF file to spawn asset from.
It uses the :class:`UrdfConverter` class to create a USD file from URDF and spawns the imported
USD file. See :meth:`spawn_from_urdf` for more information.
USD file. Similar to the :class:`UsdFileCfg`, the generated USD file can be modified by specifying
the respective properties in the configuration class.
See :meth:`spawn_from_urdf` for more information.
.. note::
The configuration parameters include various properties. If not `None`, these properties
are modified on the spawned prim in a nested manner.
If they are set to a value, then the properties are modified on the spawned prim in a nested manner.
This is done by calling the respective function with the specified properties.
"""
func: Callable = from_files.spawn_from_urdf
......
......@@ -54,7 +54,7 @@ Usage:
.. _Physics Scene: https://openusd.org/dev/api/usd_physics_page_front.html
"""
from .physics_materials import spawn_rigid_body_material
from .physics_materials_cfg import PhysicsMaterialCfg, RigidBodyMaterialCfg
from .physics_materials import spawn_deformable_body_material, spawn_rigid_body_material
from .physics_materials_cfg import DeformableBodyMaterialCfg, PhysicsMaterialCfg, RigidBodyMaterialCfg
from .visual_materials import spawn_from_mdl_file, spawn_preview_surface
from .visual_materials_cfg import GlassMdlCfg, MdlFileCfg, PreviewSurfaceCfg, VisualMaterialCfg
......@@ -23,7 +23,7 @@ def spawn_rigid_body_material(prim_path: str, cfg: physics_materials_cfg.RigidBo
Rigid body materials are used to define the physical properties to meshes of a rigid body. These
include the friction, restitution, and their respective combination modes. For more information on
rigid body material, please refer to the `documentation on PxMaterial <https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/_build/physx/latest/class_px_material.html>`_.
rigid body material, please refer to the `documentation on PxMaterial <https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/_build/physx/latest/class_px_material.html>`_.
.. note::
This function is decorated with :func:`clone` that resolves prim path into list of paths
......@@ -71,3 +71,53 @@ def spawn_rigid_body_material(prim_path: str, cfg: physics_materials_cfg.RigidBo
safe_set_attribute_on_usd_schema(physx_material_api, attr_name, value, camel_case=True)
# return the prim
return prim
@clone
def spawn_deformable_body_material(prim_path: str, cfg: physics_materials_cfg.DeformableBodyMaterialCfg) -> Usd.Prim:
"""Create material with deformable-body physics properties.
Deformable body materials are used to define the physical properties to meshes of a deformable body. These
include the friction and deformable body properties. For more information on deformable body material,
please refer to the documentation on `PxFEMSoftBodyMaterial`_.
.. note::
This function is decorated with :func:`clone` that resolves prim path into list of paths
if the input prim path is a regex pattern. This is done to support spawning multiple assets
from a single and cloning the USD prim at the given path expression.
Args:
prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern,
then the asset is spawned at all the matching prim paths.
cfg: The configuration for the physics material.
Returns:
The spawned deformable body material prim.
Raises:
ValueError: When a prim already exists at the specified prim path and is not a material.
.. _PxFEMSoftBodyMaterial: https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/_api_build/class_px_f_e_m_soft_body_material.html
"""
# create material prim if no prim exists
if not prim_utils.is_prim_path_valid(prim_path):
_ = UsdShade.Material.Define(stage_utils.get_current_stage(), prim_path)
# obtain prim
prim = prim_utils.get_prim_at_path(prim_path)
# check if prim is a material
if not prim.IsA(UsdShade.Material):
raise ValueError(f"A prim already exists at path: '{prim_path}' but is not a material.")
# retrieve the deformable-body api
physx_deformable_body_material_api = PhysxSchema.PhysxDeformableBodyMaterialAPI(prim)
if not physx_deformable_body_material_api:
physx_deformable_body_material_api = PhysxSchema.PhysxDeformableBodyMaterialAPI.Apply(prim)
# convert to dict
cfg = cfg.to_dict()
del cfg["func"]
# set into PhysX API
for attr_name, value in cfg.items():
safe_set_attribute_on_usd_schema(physx_deformable_body_material_api, attr_name, value, camel_case=True)
# return the prim
return prim
......@@ -19,7 +19,7 @@ class PhysicsMaterialCfg:
Physics material are PhysX schemas that can be applied to a USD material prim to define the
physical properties related to the material. For example, the friction coefficient, restitution
coefficient, etc. For more information on physics material, please refer to the
`PhysX documentation <https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/_build/physx/latest/class_px_base_material.html>`_.
`PhysX documentation <https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/_build/physx/latest/class_px_base_material.html>`__.
"""
func: Callable = MISSING
......@@ -34,7 +34,7 @@ class RigidBodyMaterialCfg(PhysicsMaterialCfg):
Note:
The default values are the `default values used by PhysX 5
<https://docs.omniverse.nvidia.com/extensions/latest/ext_physics/rigid-bodies.html#rigid-body-materials>`_.
<https://docs.omniverse.nvidia.com/extensions/latest/ext_physics/rigid-bodies.html#rigid-body-materials>`__.
"""
func: Callable = physics_materials.spawn_rigid_body_material
......@@ -58,7 +58,7 @@ class RigidBodyMaterialCfg(PhysicsMaterialCfg):
When two physics materials with different combine modes collide, the combine mode with the higher
priority will be used. The priority order is provided `here
<https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/_build/physx/latest/struct_px_combine_mode.html#pxcombinemode>`_.
<https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/_build/physx/latest/struct_px_combine_mode.html#pxcombinemode>`__.
"""
restitution_combine_mode: Literal["average", "min", "multiply", "max"] = "average"
......@@ -68,7 +68,7 @@ class RigidBodyMaterialCfg(PhysicsMaterialCfg):
When two physics materials with different combine modes collide, the combine mode with the higher
priority will be used. The priority order is provided `here
<https://nvidia-omniverse.github.io/PhysX/physx/5.2.1/_build/physx/latest/struct_px_combine_mode.html#pxcombinemode>`_.
<https://nvidia-omniverse.github.io/PhysX/physx/5.4.0/_build/physx/latest/struct_px_combine_mode.html#pxcombinemode>`__.
"""
compliant_contact_stiffness: float = 0.0
......@@ -84,3 +84,47 @@ class RigidBodyMaterialCfg(PhysicsMaterialCfg):
Irrelevant if compliant contacts are disabled when :obj:`compliant_contact_stiffness` is set to zero and
rigid contacts are active.
"""
@configclass
class DeformableBodyMaterialCfg(PhysicsMaterialCfg):
"""Physics material parameters for deformable bodies.
See :meth:`spawn_deformable_body_material` for more information.
Note:
The default values are the `default values used by PhysX 5
<https://docs.omniverse.nvidia.com/extensions/latest/ext_physics/deformable-bodies.html#deformable-body-material>`__.
"""
func: Callable = physics_materials.spawn_deformable_body_material
density: float | None = None
"""The material density. Defaults to None, in which case the simulation decides the default density."""
dynamic_friction: float = 0.25
"""The dynamic friction. Defaults to 0.25."""
youngs_modulus: float = 50000000.0
"""The Young's modulus, which defines the body's stiffness. Defaults to 50000000.0.
The Young's modulus is a measure of the material's ability to deform under stress. It is measured in Pascals (Pa).
"""
poissons_ratio: float = 0.45
"""The Poisson's ratio which defines the body's volume preservation. Defaults to 0.45.
The Poisson's ratio is a measure of the material's ability to expand in the lateral direction when compressed
in the axial direction. It is a dimensionless number between 0 and 0.5. Using a value of 0.5 will make the
material incompressible.
"""
elasticity_damping: float = 0.005
"""The elasticity damping for the deformable material. Defaults to 0.005."""
damping_scale: float = 1.0
"""The damping scale for the deformable material. Defaults to 1.0.
A scale of 1 corresponds to default damping. A value of 0 will only apply damping to certain motions leading
to special effects that look similar to water filled soft bodies.
"""
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Sub-module for spawning meshes in the simulation.
NVIDIA Omniverse deals with meshes as `USDGeomMesh`_ prims. This sub-module provides various
configurations to spawn different types of meshes. Based on the configuration, the spawned prim can be:
* a visual mesh (no physics)
* a static collider (no rigid or deformable body)
* a deformable body (with deformable properties)
.. note::
While rigid body properties can be set on a mesh, it is recommended to use the
:mod:`omni.isaac.lab.sim.spawners.shapes` module to spawn rigid bodies. This is because USD shapes
are more optimized for physics simulations.
.. _USDGeomMesh: https://openusd.org/release/api/class_usd_geom_mesh.html
"""
from .meshes import spawn_mesh_capsule, spawn_mesh_cone, spawn_mesh_cuboid, spawn_mesh_cylinder, spawn_mesh_sphere
from .meshes_cfg import MeshCapsuleCfg, MeshCfg, MeshConeCfg, MeshCuboidCfg, MeshCylinderCfg, MeshSphereCfg
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
import numpy as np
import trimesh
import trimesh.transformations
from typing import TYPE_CHECKING
import omni.isaac.core.utils.prims as prim_utils
from pxr import Usd, UsdPhysics
from omni.isaac.lab.sim import schemas
from omni.isaac.lab.sim.utils import bind_physics_material, bind_visual_material, clone
from ..materials import DeformableBodyMaterialCfg, RigidBodyMaterialCfg
if TYPE_CHECKING:
from . import meshes_cfg
@clone
def spawn_mesh_sphere(
prim_path: str,
cfg: meshes_cfg.MeshSphereCfg,
translation: tuple[float, float, float] | None = None,
orientation: tuple[float, float, float, float] | None = None,
) -> Usd.Prim:
"""Create a USD-Mesh sphere prim with the given attributes.
.. note::
This function is decorated with :func:`clone` that resolves prim path into list of paths
if the input prim path is a regex pattern. This is done to support spawning multiple assets
from a single and cloning the USD prim at the given path expression.
Args:
prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern,
then the asset is spawned at all the matching prim paths.
cfg: The configuration instance.
translation: The translation to apply to the prim w.r.t. its parent prim. Defaults to None, in which case
this is set to the origin.
orientation: The orientation in (w, x, y, z) to apply to the prim w.r.t. its parent prim. Defaults to None,
in which case this is set to identity.
Returns:
The created prim.
Raises:
ValueError: If a prim already exists at the given path.
"""
# create a trimesh sphere
sphere = trimesh.creation.uv_sphere(radius=cfg.radius)
# spawn the sphere as a mesh
_spawn_mesh_geom_from_mesh(prim_path, cfg, sphere, translation, orientation)
# return the prim
return prim_utils.get_prim_at_path(prim_path)
@clone
def spawn_mesh_cuboid(
prim_path: str,
cfg: meshes_cfg.MeshCuboidCfg,
translation: tuple[float, float, float] | None = None,
orientation: tuple[float, float, float, float] | None = None,
) -> Usd.Prim:
"""Create a USD-Mesh cuboid prim with the given attributes.
.. note::
This function is decorated with :func:`clone` that resolves prim path into list of paths
if the input prim path is a regex pattern. This is done to support spawning multiple assets
from a single and cloning the USD prim at the given path expression.
Args:
prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern,
then the asset is spawned at all the matching prim paths.
cfg: The configuration instance.
translation: The translation to apply to the prim w.r.t. its parent prim. Defaults to None, in which case
this is set to the origin.
orientation: The orientation in (w, x, y, z) to apply to the prim w.r.t. its parent prim. Defaults to None,
in which case this is set to identity.
Returns:
The created prim.
Raises:
ValueError: If a prim already exists at the given path.
""" # create a trimesh box
box = trimesh.creation.box(cfg.size)
# spawn the cuboid as a mesh
_spawn_mesh_geom_from_mesh(prim_path, cfg, box, translation, orientation, None)
# return the prim
return prim_utils.get_prim_at_path(prim_path)
@clone
def spawn_mesh_cylinder(
prim_path: str,
cfg: meshes_cfg.MeshCylinderCfg,
translation: tuple[float, float, float] | None = None,
orientation: tuple[float, float, float, float] | None = None,
) -> Usd.Prim:
"""Create a USD-Mesh cylinder prim with the given attributes.
.. note::
This function is decorated with :func:`clone` that resolves prim path into list of paths
if the input prim path is a regex pattern. This is done to support spawning multiple assets
from a single and cloning the USD prim at the given path expression.
Args:
prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern,
then the asset is spawned at all the matching prim paths.
cfg: The configuration instance.
translation: The translation to apply to the prim w.r.t. its parent prim. Defaults to None, in which case
this is set to the origin.
orientation: The orientation in (w, x, y, z) to apply to the prim w.r.t. its parent prim. Defaults to None,
in which case this is set to identity.
Returns:
The created prim.
Raises:
ValueError: If a prim already exists at the given path.
"""
# align axis from "Z" to input by rotating the cylinder
axis = cfg.axis.upper()
if axis == "X":
transform = trimesh.transformations.rotation_matrix(np.pi / 2, [0, 1, 0])
elif axis == "Y":
transform = trimesh.transformations.rotation_matrix(-np.pi / 2, [1, 0, 0])
else:
transform = None
# create a trimesh cylinder
cylinder = trimesh.creation.cylinder(radius=cfg.radius, height=cfg.height, transform=transform)
# spawn the cylinder as a mesh
_spawn_mesh_geom_from_mesh(prim_path, cfg, cylinder, translation, orientation)
# return the prim
return prim_utils.get_prim_at_path(prim_path)
@clone
def spawn_mesh_capsule(
prim_path: str,
cfg: meshes_cfg.MeshCapsuleCfg,
translation: tuple[float, float, float] | None = None,
orientation: tuple[float, float, float, float] | None = None,
) -> Usd.Prim:
"""Create a USD-Mesh capsule prim with the given attributes.
.. note::
This function is decorated with :func:`clone` that resolves prim path into list of paths
if the input prim path is a regex pattern. This is done to support spawning multiple assets
from a single and cloning the USD prim at the given path expression.
Args:
prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern,
then the asset is spawned at all the matching prim paths.
cfg: The configuration instance.
translation: The translation to apply to the prim w.r.t. its parent prim. Defaults to None, in which case
this is set to the origin.
orientation: The orientation in (w, x, y, z) to apply to the prim w.r.t. its parent prim. Defaults to None,
in which case this is set to identity.
Returns:
The created prim.
Raises:
ValueError: If a prim already exists at the given path.
"""
# align axis from "Z" to input by rotating the cylinder
axis = cfg.axis.upper()
if axis == "X":
transform = trimesh.transformations.rotation_matrix(np.pi / 2, [0, 1, 0])
elif axis == "Y":
transform = trimesh.transformations.rotation_matrix(-np.pi / 2, [1, 0, 0])
else:
transform = None
# create a trimesh capsule
capsule = trimesh.creation.capsule(radius=cfg.radius, height=cfg.height, transform=transform)
# spawn capsule if it doesn't exist.
_spawn_mesh_geom_from_mesh(prim_path, cfg, capsule, translation, orientation)
# return the prim
return prim_utils.get_prim_at_path(prim_path)
@clone
def spawn_mesh_cone(
prim_path: str,
cfg: meshes_cfg.MeshConeCfg,
translation: tuple[float, float, float] | None = None,
orientation: tuple[float, float, float, float] | None = None,
) -> Usd.Prim:
"""Create a USD-Mesh cone prim with the given attributes.
.. note::
This function is decorated with :func:`clone` that resolves prim path into list of paths
if the input prim path is a regex pattern. This is done to support spawning multiple assets
from a single and cloning the USD prim at the given path expression.
Args:
prim_path: The prim path or pattern to spawn the asset at. If the prim path is a regex pattern,
then the asset is spawned at all the matching prim paths.
cfg: The configuration instance.
translation: The translation to apply to the prim w.r.t. its parent prim. Defaults to None, in which case
this is set to the origin.
orientation: The orientation in (w, x, y, z) to apply to the prim w.r.t. its parent prim. Defaults to None,
in which case this is set to identity.
Returns:
The created prim.
Raises:
ValueError: If a prim already exists at the given path.
"""
# align axis from "Z" to input by rotating the cylinder
axis = cfg.axis.upper()
if axis == "X":
transform = trimesh.transformations.rotation_matrix(np.pi / 2, [0, 1, 0])
elif axis == "Y":
transform = trimesh.transformations.rotation_matrix(-np.pi / 2, [1, 0, 0])
else:
transform = None
# create a trimesh cone
cone = trimesh.creation.cone(radius=cfg.radius, height=cfg.height, transform=transform)
# spawn cone if it doesn't exist.
_spawn_mesh_geom_from_mesh(prim_path, cfg, cone, translation, orientation)
# return the prim
return prim_utils.get_prim_at_path(prim_path)
"""
Helper functions.
"""
def _spawn_mesh_geom_from_mesh(
prim_path: str,
cfg: meshes_cfg.MeshCfg,
mesh: trimesh.Trimesh,
translation: tuple[float, float, float] | None = None,
orientation: tuple[float, float, float, float] | None = None,
scale: tuple[float, float, float] | None = None,
):
"""Create a `USDGeomMesh`_ prim from the given mesh.
This function is similar to :func:`shapes._spawn_geom_from_prim_type` but spawns the prim from a given mesh.
In case of the mesh, it is spawned as a USDGeomMesh prim with the given vertices and faces.
There is a difference in how the properties are applied to the prim based on the type of object:
- Deformable body properties: The properties are applied to the mesh prim: ``{prim_path}/geometry/mesh``.
- Collision properties: The properties are applied to the mesh prim: ``{prim_path}/geometry/mesh``.
- Rigid body properties: The properties are applied to the parent prim: ``{prim_path}``.
Args:
prim_path: The prim path to spawn the asset at.
cfg: The config containing the properties to apply.
mesh: The mesh to spawn the prim from.
translation: The translation to apply to the prim w.r.t. its parent prim. Defaults to None, in which case
this is set to the origin.
orientation: The orientation in (w, x, y, z) to apply to the prim w.r.t. its parent prim. Defaults to None,
in which case this is set to identity.
scale: The scale to apply to the prim. Defaults to None, in which case this is set to identity.
Raises:
ValueError: If a prim already exists at the given path.
ValueError: If both deformable and rigid properties are used.
ValueError: If both deformable and collision properties are used.
ValueError: If the physics material is not of the correct type. Deformable properties require a deformable
physics material, and rigid properties require a rigid physics material.
.. _USDGeomMesh: https://openusd.org/dev/api/class_usd_geom_mesh.html
"""
# spawn geometry if it doesn't exist.
if not prim_utils.is_prim_path_valid(prim_path):
prim_utils.create_prim(prim_path, prim_type="Xform", translation=translation, orientation=orientation)
else:
raise ValueError(f"A prim already exists at path: '{prim_path}'.")
# check that invalid schema types are not used
if cfg.deformable_props is not None and cfg.rigid_props is not None:
raise ValueError("Cannot use both deformable and rigid properties at the same time.")
if cfg.deformable_props is not None and cfg.collision_props is not None:
raise ValueError("Cannot use both deformable and collision properties at the same time.")
# check material types are correct
if cfg.deformable_props is not None and cfg.physics_material is not None:
if not isinstance(cfg.physics_material, DeformableBodyMaterialCfg):
raise ValueError("Deformable properties require a deformable physics material.")
if cfg.rigid_props is not None and cfg.physics_material is not None:
if not isinstance(cfg.physics_material, RigidBodyMaterialCfg):
raise ValueError("Rigid properties require a rigid physics material.")
# create all the paths we need for clarity
geom_prim_path = prim_path + "/geometry"
mesh_prim_path = geom_prim_path + "/mesh"
# create the mesh prim
mesh_prim = prim_utils.create_prim(
mesh_prim_path,
prim_type="Mesh",
translation=translation,
orientation=orientation,
scale=scale,
attributes={
"points": mesh.vertices,
"faceVertexIndices": mesh.faces.flatten(),
"faceVertexCounts": np.asarray([3] * len(mesh.faces)),
"subdivisionScheme": "bilinear",
},
)
# note: in case of deformable objects, we need to apply the deformable properties to the mesh prim.
# this is different from rigid objects where we apply the properties to the parent prim.
if cfg.deformable_props is not None:
# apply mass properties
if cfg.mass_props is not None:
schemas.define_mass_properties(mesh_prim_path, cfg.mass_props)
# apply deformable body properties
schemas.define_deformable_body_properties(mesh_prim_path, cfg.deformable_props)
elif cfg.collision_props is not None:
# decide on type of collision approximation based on the mesh
if cfg.__class__.__name__ == "MeshSphereCfg":
collision_approximation = "boundingSphere"
elif cfg.__class__.__name__ == "MeshCuboidCfg":
collision_approximation = "boundingCube"
else:
# for: MeshCylinderCfg, MeshCapsuleCfg, MeshConeCfg
collision_approximation = "convexHull"
# apply collision approximation to mesh
# note: for primitives, we use the convex hull approximation -- this should be sufficient for most cases.
mesh_collision_api = UsdPhysics.MeshCollisionAPI.Apply(mesh_prim)
mesh_collision_api.GetApproximationAttr().Set(collision_approximation)
# apply collision properties
schemas.define_collision_properties(mesh_prim_path, cfg.collision_props)
# apply visual material
if cfg.visual_material is not None:
if not cfg.visual_material_path.startswith("/"):
material_path = f"{geom_prim_path}/{cfg.visual_material_path}"
else:
material_path = cfg.visual_material_path
# create material
cfg.visual_material.func(material_path, cfg.visual_material)
# apply material
bind_visual_material(mesh_prim_path, material_path)
# apply physics material
if cfg.physics_material is not None:
if not cfg.physics_material_path.startswith("/"):
material_path = f"{geom_prim_path}/{cfg.physics_material_path}"
else:
material_path = cfg.physics_material_path
# create material
cfg.physics_material.func(material_path, cfg.physics_material)
# apply material
bind_physics_material(mesh_prim_path, material_path)
# note: we apply the rigid properties to the parent prim in case of rigid objects.
if cfg.rigid_props is not None:
# apply mass properties
if cfg.mass_props is not None:
schemas.define_mass_properties(prim_path, cfg.mass_props)
# apply rigid properties
schemas.define_rigid_body_properties(prim_path, cfg.rigid_props)
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
from __future__ import annotations
from collections.abc import Callable
from dataclasses import MISSING
from typing import Literal
from omni.isaac.lab.sim.spawners import materials
from omni.isaac.lab.sim.spawners.spawner_cfg import DeformableObjectSpawnerCfg, RigidObjectSpawnerCfg
from omni.isaac.lab.utils import configclass
from . import meshes
@configclass
class MeshCfg(RigidObjectSpawnerCfg, DeformableObjectSpawnerCfg):
"""Configuration parameters for a USD Geometry or Geom prim.
This class is similar to :class:`ShapeCfg` but is specifically for meshes.
Meshes support both rigid and deformable properties. However, their schemas are applied at
different levels in the USD hierarchy based on the type of the object. These are described below:
- Deformable body properties: Applied to the mesh prim: ``{prim_path}/geometry/mesh``.
- Collision properties: Applied to the mesh prim: ``{prim_path}/geometry/mesh``.
- Rigid body properties: Applied to the parent prim: ``{prim_path}``.
where ``{prim_path}`` is the path to the prim in the USD stage and ``{prim_path}/geometry/mesh``
is the path to the mesh prim.
.. note::
There are mututally exclusive parameters for rigid and deformable properties. If both are set,
then an error will be raised. This also holds if collision and deformable properties are set together.
"""
visual_material_path: str = "material"
"""Path to the visual material to use for the prim. Defaults to "material".
If the path is relative, then it will be relative to the prim's path.
This parameter is ignored if `visual_material` is not None.
"""
visual_material: materials.VisualMaterialCfg | None = None
"""Visual material properties.
Note:
If None, then no visual material will be added.
"""
physics_material_path: str = "material"
"""Path to the physics material to use for the prim. Defaults to "material".
If the path is relative, then it will be relative to the prim's path.
This parameter is ignored if `physics_material` is not None.
"""
physics_material: materials.PhysicsMaterialCfg | None = None
"""Physics material properties.
Note:
If None, then no physics material will be added.
"""
@configclass
class MeshSphereCfg(MeshCfg):
"""Configuration parameters for a sphere mesh prim with deformable properties.
See :meth:`spawn_mesh_sphere` for more information.
"""
func: Callable = meshes.spawn_mesh_sphere
radius: float = MISSING
"""Radius of the sphere (in m)."""
@configclass
class MeshCuboidCfg(MeshCfg):
"""Configuration parameters for a cuboid mesh prim with deformable properties.
See :meth:`spawn_mesh_cuboid` for more information.
"""
func: Callable = meshes.spawn_mesh_cuboid
size: tuple[float, float, float] = MISSING
"""Size of the cuboid (in m)."""
@configclass
class MeshCylinderCfg(MeshCfg):
"""Configuration parameters for a cylinder mesh prim with deformable properties.
See :meth:`spawn_cylinder` for more information.
"""
func: Callable = meshes.spawn_mesh_cylinder
radius: float = MISSING
"""Radius of the cylinder (in m)."""
height: float = MISSING
"""Height of the cylinder (in m)."""
axis: Literal["X", "Y", "Z"] = "Z"
"""Axis of the cylinder. Defaults to "Z"."""
@configclass
class MeshCapsuleCfg(MeshCfg):
"""Configuration parameters for a capsule mesh prim.
See :meth:`spawn_capsule` for more information.
"""
func: Callable = meshes.spawn_mesh_capsule
radius: float = MISSING
"""Radius of the capsule (in m)."""
height: float = MISSING
"""Height of the capsule (in m)."""
axis: Literal["X", "Y", "Z"] = "Z"
"""Axis of the capsule. Defaults to "Z"."""
@configclass
class MeshConeCfg(MeshCfg):
"""Configuration parameters for a cone mesh prim.
See :meth:`spawn_cone` for more information.
"""
func: Callable = meshes.spawn_mesh_cone
radius: float = MISSING
"""Radius of the cone (in m)."""
height: float = MISSING
"""Height of the v (in m)."""
axis: Literal["X", "Y", "Z"] = "Z"
"""Axis of the cone. Defaults to "Z"."""
......@@ -99,3 +99,25 @@ class RigidObjectSpawnerCfg(SpawnerCfg):
This adds the PhysxContactReporter API to all the rigid bodies in the given prim path and its children.
"""
@configclass
class DeformableObjectSpawnerCfg(SpawnerCfg):
"""Configuration parameters for spawning a deformable asset.
Unlike rigid objects, deformable objects are affected by forces and can deform when subjected to
external forces. This class is used to configure the properties of the deformable object.
Deformable bodies don't have a separate collision mesh. The collision mesh is the same as the visual mesh.
The collision properties such as rest and collision offsets are specified in the :attr:`deformable_props`.
Note:
By default, all properties are set to None. This means that no properties will be added or modified
to the prim outside of the properties available by default when spawning the prim.
"""
mass_props: schemas.MassPropertiesCfg | None = None
"""Mass properties."""
deformable_props: schemas.DeformableBodyPropertiesCfg | None = None
"""Deformable body properties."""
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""This script demonstrates different rigid and deformable meshes in the scene.
It randomly spawns different types of meshes in the scene. The meshes can be rigid or deformable
based on the probability of 0.5. The rigid meshes are spawned with rigid body and collision properties,
while the deformable meshes are spawned with deformable body properties.
.. code-block:: bash
# Usage
./isaaclab.sh -p source/extensions/omni.isaac.lab/test/sim/check_meshes.py
"""
"""Launch Isaac Sim Simulator first."""
import argparse
from omni.isaac.lab.app import AppLauncher
# create argparser
parser = argparse.ArgumentParser(description="This script demonstrates different meshes in the scene.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
args_cli = parser.parse_args()
# launch omniverse app
app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app
"""Rest everything follows."""
import numpy as np
import random
import torch
import tqdm
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.lab.sim as sim_utils
def define_origins(num_origins: int, spacing: float) -> list[list[float]]:
"""Defines the origins of the the scene."""
# create tensor based on number of environments
env_origins = torch.zeros(num_origins, 3)
# create a grid of origins
num_cols = np.floor(np.sqrt(num_origins))
num_rows = np.ceil(num_origins / num_cols)
xx, yy = torch.meshgrid(torch.arange(num_rows), torch.arange(num_cols), indexing="xy")
env_origins[:, 0] = spacing * xx.flatten()[:num_origins] - spacing * (num_rows - 1) / 2
env_origins[:, 1] = spacing * yy.flatten()[:num_origins] - spacing * (num_cols - 1) / 2
env_origins[:, 2] = torch.rand(num_origins) + 1.0
# return the origins
return env_origins.tolist()
def design_scene():
"""Designs the scene by spawning ground plane, light, and deformable meshes."""
# Ground-plane
cfg_ground = sim_utils.GroundPlaneCfg()
cfg_ground.func("/World/defaultGroundPlane", cfg_ground)
# spawn distant light
cfg_light = sim_utils.DomeLightCfg(
intensity=3000.0,
color=(0.75, 0.75, 0.75),
)
cfg_light.func("/World/light", cfg_light)
# create new xform prims for all objects to be spawned under
origins = define_origins(num_origins=4, spacing=5.5)
for idx, origin in enumerate(origins):
prim_utils.create_prim(f"/World/Origin{idx:02d}", "Xform", translation=origin)
# spawn a red cone
cfg_sphere = sim_utils.MeshSphereCfg(
radius=0.25,
mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
)
cfg_cuboid = sim_utils.MeshCuboidCfg(
size=(0.2, 0.2, 0.2),
mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
)
cfg_cylinder = sim_utils.MeshCylinderCfg(
radius=0.15,
height=0.5,
mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
)
cfg_capsule = sim_utils.MeshCapsuleCfg(
radius=0.15,
height=0.5,
mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
)
cfg_cone = sim_utils.MeshConeCfg(
radius=0.15,
height=0.5,
mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
)
# create a dictionary of all the objects to be spawned
objects_cfg = {
"sphere": cfg_sphere,
"cuboid": cfg_cuboid,
"cylinder": cfg_cylinder,
"capsule": cfg_capsule,
"cone": cfg_cone,
}
# Create separate groups of deformable objects
origins = define_origins(num_origins=25, spacing=0.5)
print("[INFO]: Spawning objects...")
# Iterate over all the origins and randomly spawn objects
for idx, origin in tqdm.tqdm(enumerate(origins), total=len(origins)):
# randomly select an object to spawn
obj_name = random.choice(list(objects_cfg.keys()))
obj_cfg = objects_cfg[obj_name]
# randomly decide if it is rigid or deformable
if random.random() < 0.5:
obj_cfg.rigid_props = None
obj_cfg.collision_props = None
obj_cfg.deformable_props = sim_utils.DeformableBodyPropertiesCfg(rest_offset=0.0)
else:
obj_cfg.deformable_props = None
obj_cfg.rigid_props = sim_utils.RigidBodyPropertiesCfg()
obj_cfg.collision_props = sim_utils.CollisionPropertiesCfg()
# randomize the color
obj_cfg.visual_material.diffuse_color = (random.random(), random.random(), random.random())
# spawn the object
obj_cfg.func(f"/World/Origin.*/Object{idx:02d}", obj_cfg, translation=origin)
def main():
"""Main function."""
# Initialize the simulation context
sim_cfg = sim_utils.SimulationCfg(dt=0.01)
sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view([8.0, 8.0, 6.0], [0.0, 0.0, 0.0])
# Design scene by adding assets to it
design_scene()
# Play the simulator
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Simulate physics
while simulation_app.is_running():
# perform step
sim.step()
if __name__ == "__main__":
# run the main function
main()
# close sim app
simulation_app.close()
......@@ -111,6 +111,31 @@ class TestSpawningMaterials(unittest.TestCase):
self.assertEqual(prim.GetAttribute("physxMaterial:restitutionCombineMode").Get(), cfg.restitution_combine_mode)
self.assertEqual(prim.GetAttribute("physxMaterial:frictionCombineMode").Get(), cfg.friction_combine_mode)
def test_spawn_deformable_body_material(self):
"""Test spawning a deformable body material."""
# spawn deformable body material
cfg = sim_utils.materials.DeformableBodyMaterialCfg(
density=1.0,
dynamic_friction=0.25,
youngs_modulus=50000000.0,
poissons_ratio=0.5,
elasticity_damping=0.005,
damping_scale=1.0,
)
prim = cfg.func("/Looks/DeformableBodyMaterial", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/Looks/DeformableBodyMaterial"))
# Check properties
self.assertEqual(prim.GetAttribute("physxDeformableBodyMaterial:density").Get(), cfg.density)
self.assertEqual(prim.GetAttribute("physxDeformableBodyMaterial:dynamicFriction").Get(), cfg.dynamic_friction)
self.assertEqual(prim.GetAttribute("physxDeformableBodyMaterial:youngsModulus").Get(), cfg.youngs_modulus)
self.assertEqual(prim.GetAttribute("physxDeformableBodyMaterial:poissonsRatio").Get(), cfg.poissons_ratio)
self.assertAlmostEqual(
prim.GetAttribute("physxDeformableBodyMaterial:elasticityDamping").Get(), cfg.elasticity_damping
)
self.assertEqual(prim.GetAttribute("physxDeformableBodyMaterial:dampingScale").Get(), cfg.damping_scale)
def test_apply_rigid_body_material_on_visual_material(self):
"""Test applying a rigid body material on a visual material."""
# Spawn mdl material
......
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Launch Isaac Sim Simulator first."""
from omni.isaac.lab.app import AppLauncher, run_tests
# launch omniverse app
simulation_app = AppLauncher(headless=True).app
"""Rest everything follows."""
import unittest
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.core.utils.stage as stage_utils
from omni.isaac.core.simulation_context import SimulationContext
import omni.isaac.lab.sim as sim_utils
class TestSpawningMeshGeometries(unittest.TestCase):
"""Test fixture for checking spawning of USD-Mesh prim with different settings."""
def setUp(self) -> None:
"""Create a blank new stage for each test."""
# Create a new stage
stage_utils.create_new_stage()
# Simulation time-step
self.dt = 0.1
# Load kit helper
self.sim = SimulationContext(physics_dt=self.dt, rendering_dt=self.dt, device="cuda:0")
# Wait for spawning
stage_utils.update_stage()
def tearDown(self) -> None:
"""Stops simulator after each test."""
# stop simulation
self.sim.stop()
self.sim.clear()
self.sim.clear_all_callbacks()
self.sim.clear_instance()
"""
Basic spawning.
"""
def test_spawn_cone(self):
"""Test spawning of UsdGeomMesh as a cone prim."""
# Spawn cone
cfg = sim_utils.MeshConeCfg(radius=1.0, height=2.0, axis="Y")
prim = cfg.func("/World/Cone", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cone"))
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Xform")
# Check properties
prim = prim_utils.get_prim_at_path("/World/Cone/geometry/mesh")
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Mesh")
def test_spawn_capsule(self):
"""Test spawning of UsdGeomMesh as a capsule prim."""
# Spawn capsule
cfg = sim_utils.MeshCapsuleCfg(radius=1.0, height=2.0, axis="Y")
prim = cfg.func("/World/Capsule", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Capsule"))
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Xform")
# Check properties
prim = prim_utils.get_prim_at_path("/World/Capsule/geometry/mesh")
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Mesh")
def test_spawn_cylinder(self):
"""Test spawning of UsdGeomMesh as a cylinder prim."""
# Spawn cylinder
cfg = sim_utils.MeshCylinderCfg(radius=1.0, height=2.0, axis="Y")
prim = cfg.func("/World/Cylinder", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cylinder"))
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Xform")
# Check properties
prim = prim_utils.get_prim_at_path("/World/Cylinder/geometry/mesh")
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Mesh")
def test_spawn_cuboid(self):
"""Test spawning of UsdGeomMesh as a cuboid prim."""
# Spawn cuboid
cfg = sim_utils.MeshCuboidCfg(size=(1.0, 2.0, 3.0))
prim = cfg.func("/World/Cube", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cube"))
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Xform")
# Check properties
prim = prim_utils.get_prim_at_path("/World/Cube/geometry/mesh")
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Mesh")
def test_spawn_sphere(self):
"""Test spawning of UsdGeomMesh as a sphere prim."""
# Spawn sphere
cfg = sim_utils.MeshSphereCfg(radius=1.0)
prim = cfg.func("/World/Sphere", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Sphere"))
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Xform")
# Check properties
prim = prim_utils.get_prim_at_path("/World/Sphere/geometry/mesh")
self.assertEqual(prim.GetPrimTypeInfo().GetTypeName(), "Mesh")
"""
Physics properties.
"""
def test_spawn_cone_with_deformable_props(self):
"""Test spawning of UsdGeomMesh prim for a cone with deformable body API."""
# Spawn cone
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
deformable_props=sim_utils.DeformableBodyPropertiesCfg(deformable_enabled=True),
)
prim = cfg.func("/World/Cone", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cone"))
# Check properties
# Unlike rigid body, deformable body properties are on the mesh prim
prim = prim_utils.get_prim_at_path("/World/Cone/geometry/mesh")
self.assertEqual(
prim.GetAttribute("physxDeformable:deformableEnabled").Get(), cfg.deformable_props.deformable_enabled
)
def test_spawn_cone_with_deformable_and_mass_props(self):
"""Test spawning of UsdGeomMesh prim for a cone with deformable body and mass API."""
# Spawn cone
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
deformable_props=sim_utils.DeformableBodyPropertiesCfg(deformable_enabled=True),
mass_props=sim_utils.MassPropertiesCfg(mass=1.0),
)
prim = cfg.func("/World/Cone", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cone"))
# Check properties
prim = prim_utils.get_prim_at_path("/World/Cone/geometry/mesh")
self.assertEqual(prim.GetAttribute("physics:mass").Get(), cfg.mass_props.mass)
# check sim playing
self.sim.play()
for _ in range(10):
self.sim.step()
def test_spawn_cone_with_deformable_and_density_props(self):
"""Test spawning of UsdGeomMesh prim for a cone with deformable body and mass API.
Note:
In this case, we specify the density instead of the mass. In that case, physics need to know
the collision shape to compute the mass. Thus, we have to set the collider properties. In
order to not have a collision shape, we disable the collision.
"""
# Spawn cone
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
deformable_props=sim_utils.DeformableBodyPropertiesCfg(deformable_enabled=True),
mass_props=sim_utils.MassPropertiesCfg(density=10.0),
)
prim = cfg.func("/World/Cone", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cone"))
# Check properties
prim = prim_utils.get_prim_at_path("/World/Cone/geometry/mesh")
self.assertEqual(prim.GetAttribute("physics:density").Get(), cfg.mass_props.density)
# check sim playing
self.sim.play()
for _ in range(10):
self.sim.step()
def test_spawn_cone_with_all_deformable_props(self):
"""Test spawning of UsdGeomMesh prim for a cone with all deformable properties."""
# Spawn cone
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
mass_props=sim_utils.MassPropertiesCfg(mass=5.0),
deformable_props=sim_utils.DeformableBodyPropertiesCfg(),
visual_material=sim_utils.materials.PreviewSurfaceCfg(diffuse_color=(0.0, 0.75, 0.5)),
physics_material=sim_utils.materials.DeformableBodyMaterialCfg(),
)
prim = cfg.func("/World/Cone", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cone"))
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cone/geometry/material"))
# Check properties
# -- deformable body
prim = prim_utils.get_prim_at_path("/World/Cone/geometry/mesh")
self.assertEqual(prim.GetAttribute("physxDeformable:deformableEnabled").Get(), True)
# check sim playing
self.sim.play()
for _ in range(10):
self.sim.step()
def test_spawn_cone_with_all_rigid_props(self):
"""Test spawning of UsdGeomMesh prim for a cone with all rigid properties."""
# Spawn cone
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
mass_props=sim_utils.MassPropertiesCfg(mass=5.0),
rigid_props=sim_utils.RigidBodyPropertiesCfg(
rigid_body_enabled=True, solver_position_iteration_count=8, sleep_threshold=0.1
),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.materials.PreviewSurfaceCfg(diffuse_color=(0.0, 0.75, 0.5)),
physics_material=sim_utils.materials.RigidBodyMaterialCfg(),
)
prim = cfg.func("/World/Cone", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cone"))
self.assertTrue(prim_utils.is_prim_path_valid("/World/Cone/geometry/material"))
# Check properties
# -- rigid body
prim = prim_utils.get_prim_at_path("/World/Cone")
self.assertEqual(prim.GetAttribute("physics:rigidBodyEnabled").Get(), cfg.rigid_props.rigid_body_enabled)
self.assertEqual(
prim.GetAttribute("physxRigidBody:solverPositionIterationCount").Get(),
cfg.rigid_props.solver_position_iteration_count,
)
self.assertAlmostEqual(
prim.GetAttribute("physxRigidBody:sleepThreshold").Get(), cfg.rigid_props.sleep_threshold
)
# -- mass
self.assertEqual(prim.GetAttribute("physics:mass").Get(), cfg.mass_props.mass)
# -- collision shape
prim = prim_utils.get_prim_at_path("/World/Cone/geometry/mesh")
self.assertEqual(prim.GetAttribute("physics:collisionEnabled").Get(), True)
# check sim playing
self.sim.play()
for _ in range(10):
self.sim.step()
def test_spawn_deformable_rigid_cone_invalid(self):
"""Test specifying both rigid and deformable properties for a cone causes an error."""
# Spawn cone
with self.assertRaises(ValueError):
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
mass_props=sim_utils.MassPropertiesCfg(mass=5.0),
rigid_props=sim_utils.RigidBodyPropertiesCfg(rigid_body_enabled=True),
deformable_props=sim_utils.DeformableBodyPropertiesCfg(deformable_enabled=True),
)
cfg.func("/World/Cone", cfg)
def test_spawn_deformable_collider_cone_invalid(self):
"""Test specifying both deformable and collider properties for a cone causes an error."""
# Spawn cone
with self.assertRaises(ValueError):
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
collision_props=sim_utils.CollisionPropertiesCfg(collision_enabled=True),
deformable_props=sim_utils.DeformableBodyPropertiesCfg(deformable_enabled=True),
)
cfg.func("/World/Cone", cfg)
def test_spawn_deformable_incorrect_material(self):
"""Test specifying incorrect material for deformable object causes an error."""
# Spawn cone
with self.assertRaises(ValueError):
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
deformable_props=sim_utils.DeformableBodyPropertiesCfg(deformable_enabled=True),
visual_material=sim_utils.materials.PreviewSurfaceCfg(),
physics_material=sim_utils.materials.RigidBodyMaterialCfg(),
)
cfg.func("/World/Cone", cfg)
def test_spawn_rigid_incorrect_material(self):
"""Test specifying incorrect material for rigid object causes an error."""
# Spawn cone
with self.assertRaises(ValueError):
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
mass_props=sim_utils.MassPropertiesCfg(mass=5.0),
rigid_props=sim_utils.RigidBodyPropertiesCfg(rigid_body_enabled=True),
visual_material=sim_utils.materials.PreviewSurfaceCfg(),
physics_material=sim_utils.materials.DeformableBodyMaterialCfg(),
)
cfg.func("/World/Cone", cfg)
"""
Cloning.
"""
def test_spawn_cone_clones_invalid_paths(self):
"""Test spawning of cone clones on invalid cloning paths."""
num_clones = 10
for i in range(num_clones):
prim_utils.create_prim(f"/World/env_{i}", "Xform", translation=(i, i, 0))
# Spawn cone
cfg = sim_utils.MeshConeCfg(radius=1.0, height=2.0, copy_from_source=True)
# Should raise error for invalid path
with self.assertRaises(RuntimeError):
cfg.func("/World/env/env_.*/Cone", cfg)
def test_spawn_cone_clones(self):
"""Test spawning of cone clones."""
num_clones = 10
for i in range(num_clones):
prim_utils.create_prim(f"/World/env_{i}", "Xform", translation=(i, i, 0))
# Spawn cone
cfg = sim_utils.MeshConeCfg(radius=1.0, height=2.0, copy_from_source=True)
prim = cfg.func("/World/env_.*/Cone", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertEqual(prim_utils.get_prim_path(prim), "/World/env_0/Cone")
# Find matching prims
prims = prim_utils.find_matching_prim_paths("/World/env_*/Cone")
self.assertEqual(len(prims), num_clones)
def test_spawn_cone_clone_with_all_props_global_material(self):
"""Test spawning of cone clones with global material reference."""
num_clones = 10
for i in range(num_clones):
prim_utils.create_prim(f"/World/env_{i}", "Xform", translation=(i, i, 0))
# Spawn cone
cfg = sim_utils.MeshConeCfg(
radius=1.0,
height=2.0,
mass_props=sim_utils.MassPropertiesCfg(mass=5.0),
deformable_props=sim_utils.DeformableBodyPropertiesCfg(),
visual_material=sim_utils.materials.PreviewSurfaceCfg(diffuse_color=(0.0, 0.75, 0.5)),
physics_material=sim_utils.materials.DeformableBodyMaterialCfg(),
visual_material_path="/Looks/visualMaterial",
physics_material_path="/Looks/physicsMaterial",
)
prim = cfg.func("/World/env_.*/Cone", cfg)
# Check validity
self.assertTrue(prim.IsValid())
self.assertEqual(prim_utils.get_prim_path(prim), "/World/env_0/Cone")
# Find matching prims
prims = prim_utils.find_matching_prim_paths("/World/env_*/Cone")
self.assertEqual(len(prims), num_clones)
# Find global materials
prims = prim_utils.find_matching_prim_paths("/Looks/visualMaterial.*")
self.assertEqual(len(prims), 1)
if __name__ == "__main__":
run_tests()
# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""This script demonstrates how to spawn deformable prims into the scene.
.. code-block:: bash
# Usage
./isaaclab.sh -p source/standalone/demos/deformables.py
"""
"""Launch Isaac Sim Simulator first."""
import argparse
from omni.isaac.lab.app import AppLauncher
# create argparser
parser = argparse.ArgumentParser(description="This script demonstrates how to spawn deformable prims into the scene.")
# append AppLauncher cli args
AppLauncher.add_app_launcher_args(parser)
# parse the arguments
args_cli = parser.parse_args()
# launch omniverse app
app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app
"""Rest everything follows."""
import numpy as np
import random
import torch
import tqdm
import omni.isaac.core.utils.prims as prim_utils
import omni.isaac.lab.sim as sim_utils
def define_origins(num_origins: int, spacing: float) -> list[list[float]]:
"""Defines the origins of the the scene."""
# create tensor based on number of environments
env_origins = torch.zeros(num_origins, 3)
# create a grid of origins
num_cols = np.floor(np.sqrt(num_origins))
num_rows = np.ceil(num_origins / num_cols)
xx, yy = torch.meshgrid(torch.arange(num_rows), torch.arange(num_cols), indexing="xy")
env_origins[:, 0] = spacing * xx.flatten()[:num_origins] - spacing * (num_rows - 1) / 2
env_origins[:, 1] = spacing * yy.flatten()[:num_origins] - spacing * (num_cols - 1) / 2
env_origins[:, 2] = torch.rand(num_origins) + 1.0
# return the origins
return env_origins.tolist()
def design_scene():
"""Designs the scene by spawning ground plane, light, and deformable meshes."""
# Ground-plane
cfg_ground = sim_utils.GroundPlaneCfg()
cfg_ground.func("/World/defaultGroundPlane", cfg_ground)
# spawn distant light
cfg_light = sim_utils.DomeLightCfg(
intensity=3000.0,
color=(0.75, 0.75, 0.75),
)
cfg_light.func("/World/light", cfg_light)
# create new xform prims for all objects to be spawned under
origins = define_origins(num_origins=4, spacing=5.5)
for idx, origin in enumerate(origins):
prim_utils.create_prim(f"/World/Origin{idx:02d}", "Xform", translation=origin)
# spawn a red cone
cfg_sphere = sim_utils.MeshSphereCfg(
radius=0.25,
deformable_props=sim_utils.DeformableBodyPropertiesCfg(rest_offset=0.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
physics_material=sim_utils.DeformableBodyMaterialCfg(),
)
cfg_cuboid = sim_utils.MeshCuboidCfg(
size=(0.2, 0.2, 0.2),
deformable_props=sim_utils.DeformableBodyPropertiesCfg(rest_offset=0.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
physics_material=sim_utils.DeformableBodyMaterialCfg(),
)
cfg_cylinder = sim_utils.MeshCylinderCfg(
radius=0.15,
height=0.5,
deformable_props=sim_utils.DeformableBodyPropertiesCfg(rest_offset=0.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
physics_material=sim_utils.DeformableBodyMaterialCfg(),
)
cfg_capsule = sim_utils.MeshCapsuleCfg(
radius=0.15,
height=0.5,
deformable_props=sim_utils.DeformableBodyPropertiesCfg(rest_offset=0.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
physics_material=sim_utils.DeformableBodyMaterialCfg(),
)
cfg_cone = sim_utils.MeshConeCfg(
radius=0.15,
height=0.5,
deformable_props=sim_utils.DeformableBodyPropertiesCfg(rest_offset=0.0),
visual_material=sim_utils.PreviewSurfaceCfg(),
physics_material=sim_utils.DeformableBodyMaterialCfg(),
)
# create a dictionary of all the objects to be spawned
objects_cfg = {
"sphere": cfg_sphere,
"cuboid": cfg_cuboid,
"cylinder": cfg_cylinder,
"capsule": cfg_capsule,
"cone": cfg_cone,
}
# Create separate groups of deformable objects
origins = define_origins(num_origins=25, spacing=0.5)
print("[INFO]: Spawning objects...")
# Iterate over all the origins and randomly spawn objects
for idx, origin in tqdm.tqdm(enumerate(origins), total=len(origins)):
# randomly select an object to spawn
obj_name = random.choice(list(objects_cfg.keys()))
obj_cfg = objects_cfg[obj_name]
# randomize the young modulus (somewhere between a Silicone 30 and Silicone 70)
obj_cfg.physics_material.youngs_modulus = random.uniform(0.7e6, 3.3e6)
# randomize the poisson's ratio
obj_cfg.physics_material.poissons_ratio = random.uniform(0.25, 0.5)
# randomize the color
obj_cfg.visual_material.diffuse_color = (random.random(), random.random(), random.random())
# spawn the object
obj_cfg.func(f"/World/Origin.*/Object{idx:02d}", obj_cfg, translation=origin)
def main():
"""Main function."""
# Initialize the simulation context
sim_cfg = sim_utils.SimulationCfg(dt=0.01)
sim = sim_utils.SimulationContext(sim_cfg)
# Set main camera
sim.set_camera_view([8.0, 8.0, 6.0], [0.0, 0.0, 0.0])
# Design scene by adding assets to it
design_scene()
# Play the simulator
sim.reset()
# Now we are ready!
print("[INFO]: Setup complete...")
# Simulate physics
while simulation_app.is_running():
# perform step
sim.step()
if __name__ == "__main__":
# run the main function
main()
# close sim app
simulation_app.close()
......@@ -74,6 +74,15 @@ def design_scene():
"/World/Objects/ConeRigid", cfg_cone_rigid, translation=(0.0, 0.0, 2.0), orientation=(0.5, 0.0, 0.5, 0.0)
)
# spawn a blue cuboid with deformable body
cfg_cuboid_deformable = sim_utils.MeshCuboidCfg(
size=(0.2, 0.5, 0.2),
deformable_props=sim_utils.DeformableBodyPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)),
physics_material=sim_utils.DeformableBodyMaterialCfg(),
)
cfg_cuboid_deformable.func("/World/Objects/CuboidDeformable", cfg_cuboid_deformable, translation=(0.15, 0.0, 2.0))
# spawn a usd file of a table into the scene
cfg = sim_utils.UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/SeattleLabTable/table_instanceable.usd")
cfg.func("/World/Objects/Table", cfg, translation=(0.0, 0.0, 1.05))
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment