isaaclab_physx.sim.schemas

Contents

isaaclab_physx.sim.schemas#

Sub-module containing PhysX schema configuration exports.

PhysX-specific schema configuration classes. Each cfg below extends a solver-common base in isaaclab.sim.schemas with PhysX-namespaced attributes (physx*:*) and applies the corresponding Physx*API applied schema. See Schema Configuration Classes for the design.

Rigid body and joint drive

PhysxRigidBodyPropertiesCfg

PhysX-specific rigid body properties.

PhysxJointDrivePropertiesCfg

PhysX-specific joint drive properties.

Collision

PhysxCollisionPropertiesCfg

PhysX-specific rigid-body collision properties.

Articulation root

PhysxArticulationRootPropertiesCfg

PhysX-specific articulation-root properties.

Mesh collision (PhysX cooking)

PhysxConvexHullPropertiesCfg

PhysX convex-hull cooking properties for a mesh collider.

PhysxConvexDecompositionPropertiesCfg

PhysX convex-decomposition cooking properties for a mesh collider.

PhysxTriangleMeshPropertiesCfg

PhysX triangle-mesh cooking properties for a mesh collider.

PhysxTriangleMeshSimplificationPropertiesCfg

PhysX triangle-mesh-simplification cooking properties for a mesh collider.

PhysxSDFMeshPropertiesCfg

PhysX SDF-mesh cooking properties for a mesh collider.

Tendon

PhysxFixedTendonPropertiesCfg

PhysX fixed-tendon properties for an articulation.

PhysxSpatialTendonPropertiesCfg

PhysX spatial-tendon properties for an articulation.

Deformable body

OmniPhysicsDeformableBodyPropertiesCfg

OmniPhysics properties for a deformable body.

PhysxDeformableCollisionPropertiesCfg

PhysX-specific collision properties for a deformable body.

PhysxDeformableBodyPropertiesCfg

PhysX-specific properties to apply to a deformable body.

DeformableBodyPropertiesCfg

Deprecated: use PhysxDeformableBodyPropertiesCfg.

Functions

define_deformable_body_properties(prim_path, cfg)

Apply the deformable body schema on the input prim and set its properties.

modify_deformable_body_properties(prim_path, cfg)

Modify deformable body parameters for a deformable body prim.

Rigid Body#

class isaaclab_physx.sim.schemas.PhysxRigidBodyPropertiesCfg[source]#

Bases: RigidBodyBaseCfg

PhysX-specific rigid body properties.

Extends RigidBodyBaseCfg with properties from the PhysxRigidBodyAPI schema.

See modify_rigid_body_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.

Attributes:

linear_damping

Linear damping for the body.

angular_damping

Angular damping for the body.

max_linear_velocity

Maximum linear velocity for rigid bodies (in m/s).

max_angular_velocity

Maximum angular velocity for rigid bodies (in deg/s).

max_depenetration_velocity

Maximum depenetration velocity permitted to be introduced by the solver (in m/s).

max_contact_impulse

The limit on the impulse that may be applied at a contact.

enable_gyroscopic_forces

Enables computation of gyroscopic forces on the rigid body.

retain_accelerations

Carries over forces/accelerations over sub-steps.

solver_position_iteration_count

Solver position iteration counts for the body.

solver_velocity_iteration_count

Solver velocity iteration counts for the body.

sleep_threshold

Mass-normalized kinetic energy threshold below which an actor may go to sleep.

stabilization_threshold

The mass-normalized kinetic energy threshold below which an actor may participate in stabilization.

rigid_body_enabled

Whether to enable or disable the rigid body.

kinematic_enabled

Determines whether the body is kinematic or not.

disable_gravity

Disable gravity for the body.

linear_damping: float | None#

Linear damping for the body.

angular_damping: float | None#

Angular damping for the body.

max_linear_velocity: float | None#

Maximum linear velocity for rigid bodies (in m/s).

max_angular_velocity: float | None#

Maximum angular velocity for rigid bodies (in deg/s).

max_depenetration_velocity: float | None#

Maximum depenetration velocity permitted to be introduced by the solver (in m/s).

max_contact_impulse: float | None#

The limit on the impulse that may be applied at a contact.

enable_gyroscopic_forces: bool | None#

Enables computation of gyroscopic forces on the rigid body.

retain_accelerations: bool | None#

Carries over forces/accelerations over sub-steps.

solver_position_iteration_count: int | None#

Solver position iteration counts for the body.

solver_velocity_iteration_count: int | None#

Solver velocity iteration counts for the body.

sleep_threshold: float | None#

Mass-normalized kinetic energy threshold below which an actor may go to sleep.

stabilization_threshold: float | None#

The mass-normalized kinetic energy threshold below which an actor may participate in stabilization.

rigid_body_enabled: bool | None#

Whether to enable or disable the rigid body.

kinematic_enabled: bool | None#

Determines whether the body is kinematic or not.

A kinematic body is a body that is moved through animated poses or through user defined poses. The simulation still derives velocities for the kinematic body based on the external motion.

For more information on kinematic bodies, please refer to the documentation.

disable_gravity: bool | None#

Disable gravity for the body.

PhysX honors this per-body via physxRigidBody:disableGravity: setting True excludes the body from world gravity integration.

Newton currently consumes the same USD attribute at the scene level – Newton’s importer reads physxRigidBody:disableGravity on the scene prim and uses it to drive the scene-wide builder.gravity flag (import_usd.py:1212). Per-body intent is therefore partially honored on Newton: whichever rigid body has the attribute authored ends up controlling scene-wide gravity, and other bodies cannot be selectively excluded.

The field is placed on the base because the user-facing intent (per-body gravity exclusion for markers, sensors, kinematic targets) is universal physics and PhysX honors it fully. Closing the Newton gap is a kernel-level fix (introduce Model.body_disable_gravity boolean array consumed by the integrator) that does not require a cfg-API change.

Joint Drive#

class isaaclab_physx.sim.schemas.PhysxJointDrivePropertiesCfg[source]#

Bases: JointDriveBaseCfg

PhysX-specific joint drive properties.

Currently empty after the consumption-gated split moved max_joint_velocity to JointDriveBaseCfg. This class is retained as the deprecation-alias target for the legacy JointDrivePropertiesCfg name and as the home for any future PhysX-only joint-drive fields (e.g. PhysX-specific drive force-limit modes).

Inherits all fields and USD metadata from JointDriveBaseCfg.

See modify_joint_drive_properties() for more information.

Attributes:

drive_type

Joint drive type to apply.

max_force

Maximum force/torque that can be applied to the joint [N for linear joints, N-m for angular joints].

max_effort

Deprecated alias for max_force.

stiffness

Stiffness of the joint drive.

damping

Damping of the joint drive.

ensure_drives_exist

If True, ensure every joint has a non-zero drive so that physics backends (e.g. Newton) create proper actuators for it.

max_joint_velocity

Maximum velocity of the joint [m/s for linear joints, rad/s for angular joints].

max_velocity

Deprecated alias for max_joint_velocity.

drive_type: Literal['force', 'acceleration'] | None#

Joint drive type to apply.

If the drive type is “force”, then the joint is driven by a force. If the drive type is “acceleration”, then the joint is driven by an acceleration (usually used for kinematic joints).

max_force: float | None#

Maximum force/torque that can be applied to the joint [N for linear joints, N-m for angular joints].

Writes drive:<linear|angular>:physics:maxForce via UsdPhysics.DriveAPI.

max_effort: float | None#

Deprecated alias for max_force.

Deprecated since version 4.6.25: Use max_force instead. The cfg field is renamed so its snake_case name maps identity-style to the USD camelCase attribute (maxForce on UsdPhysics.DriveAPI). The alias is forwarded to max_force in __post_init__() and will be removed in 4.0.

stiffness: float | None#

Stiffness of the joint drive.

The unit depends on the joint model:

  • For linear joints, the unit is kg-m/s^2 (N/m).

  • For angular joints, the unit is kg-m^2/s^2/rad (N-m/rad).

damping: float | None#

Damping of the joint drive.

The unit depends on the joint model:

  • For linear joints, the unit is kg-m/s (N-s/m).

  • For angular joints, the unit is kg-m^2/s/rad (N-m-s/rad).

ensure_drives_exist: bool#

If True, ensure every joint has a non-zero drive so that physics backends (e.g. Newton) create proper actuators for it.

When a USD asset defines PhysicsDriveAPI with stiffness=0 and damping=0, some backends treat the joint as passive (no PD control). Enabling this flag writes a minimal stiffness (1e-3) to any drive whose stiffness and damping are both zero, guaranteeing that the backend recognises the drive as active. The actual gains are expected to be overridden later by the actuator model.

max_joint_velocity: float | None#

Maximum velocity of the joint [m/s for linear joints, rad/s for angular joints].

Notes

Today this writes physxJoint:maxJointVelocity (a PhysX add-on schema attribute). Newton’s USD importer consumes the same attribute via its PhysX-bridge resolver and populates Model.joint_velocity_limit; the PhysX engine consumes it natively. The Kamino solver honors the limit at the simulation step. The XPBD, Featherstone, and Semi-implicit Newton solvers import the value but do not consume it in their kernels; the MuJoCo (MJC) solver explicitly drops it. When Newton ships newton:maxJointVelocity as a registered applied API, the writer namespace will switch transparently and this docstring caveat will be removed.

max_velocity: float | None#

Deprecated alias for max_joint_velocity.

Deprecated since version 4.6.25: Use max_joint_velocity instead. The cfg field is renamed so its snake_case name maps identity-style to the USD camelCase attribute (physxJoint:maxJointVelocity). The alias is forwarded to max_joint_velocity in __post_init__() and will be removed in 4.0.

Collision#

class isaaclab_physx.sim.schemas.PhysxCollisionPropertiesCfg[source]#

Bases: CollisionBaseCfg

PhysX-specific rigid-body collision properties.

Extends CollisionBaseCfg with the PhysX-only torsional patch friction approximations (torsional_patch_radius, min_torsional_patch_radius). These fields have no Newton equivalent and are consumed only by the PhysX solver.

See modify_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.

Attributes:

torsional_patch_radius

Radius of the contact patch for applying torsional friction [m].

min_torsional_patch_radius

Minimum radius of the contact patch for applying torsional friction [m].

collision_enabled

Whether to enable or disable collisions.

contact_offset

Contact offset for the collision shape [m].

rest_offset

Rest offset for the collision shape [m].

torsional_patch_radius: float | None#

Radius of the contact patch for applying torsional friction [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#

Minimum radius of the contact patch for applying torsional friction [m].

collision_enabled: bool | None#

Whether to enable or disable collisions.

Writes physics:collisionEnabled via UsdPhysics.CollisionAPI.

contact_offset: float | None#

Contact offset for the collision shape [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.

Writes physxCollision:contactOffset. Newton’s USD importer consumes the same attribute via its PhysX-bridge resolver.

rest_offset: float | None#

Rest offset for the collision shape [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.

Writes physxCollision:restOffset. Newton’s USD importer consumes the same attribute via its PhysX-bridge resolver.

Articulation Root#

class isaaclab_physx.sim.schemas.PhysxArticulationRootPropertiesCfg[source]#

Bases: ArticulationRootBaseCfg

PhysX-specific articulation-root properties.

Extends ArticulationRootBaseCfg with the PhysxArticulationAPI schema fields that are PhysX-only or dual-namespace (Rule 2 — the conceptual quantity also has a newton:* attribute, and a future NewtonArticulationRootPropertiesCfg would carry it on the Newton side). Use this class when authoring PhysX-specific articulation knobs; use ArticulationRootBaseCfg when only the solver-common fix_root_link / articulation_enabled fields are needed.

See modify_articulation_root_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.

Attributes:

enabled_self_collisions

Whether self-collisions between bodies in the same articulation are enabled.

solver_position_iteration_count

Solver position iteration counts for the body.

solver_velocity_iteration_count

Solver velocity iteration counts for the body.

sleep_threshold

Mass-normalized kinetic energy threshold below which an actor may go to sleep.

stabilization_threshold

The mass-normalized kinetic energy threshold below which an articulation may participate in stabilization.

articulation_enabled

Whether to enable or disable the articulation.

fix_root_link

Whether to fix the root link of the articulation.

enabled_self_collisions: bool | None#

Whether self-collisions between bodies in the same articulation are enabled.

The conceptual quantity exists in two USD namespaces simultaneously:

  • physxArticulation:enabledSelfCollisions (PhysX, PhysxArticulationAPI)

  • newton:selfCollisionEnabled (Newton-native, on a future NewtonArticulationRootAPI)

Newton’s resolver checks the native newton:* attribute first and falls back to the PhysX namespace. Both backends honor the field end-to-end.

Because the conceptual quantity has a dedicated USD attribute in each backend’s namespace, this field is placed on the PhysX subclass (one cfg per namespace). A future NewtonArticulationRootPropertiesCfg will carry the same field over the newton:* namespace.

solver_position_iteration_count: int | None#

Solver position iteration counts for the body.

solver_velocity_iteration_count: int | None#

Solver velocity iteration counts for the body.

sleep_threshold: float | None#

Mass-normalized kinetic energy threshold below which an actor may go to sleep.

stabilization_threshold: float | None#

The mass-normalized kinetic energy threshold below which an articulation may participate in stabilization.

articulation_enabled: bool | None#

Whether to enable or disable the articulation.

PhysX honors this per-articulation at sim time via physxArticulation:articulationEnabled: setting False makes PhysX skip the articulation in its solver passes.

On Newton, the field is read by the IsaacLab Newton wrapper at spawn time (isaaclab_newton/assets/rigid_object/rigid_object.py:1035) as a guard against accidentally spawning a RigidObject over a prim that still has ArticulationRootAPI applied; setting False suppresses the guard error. The Newton solver itself does not consult the flag at sim time.

Placed on the solver-common class because the user-facing intent is universal and both PhysX (sim-time) and the IL Newton wrapper (spawn-time) honor it.

Whether to fix the root link of the articulation.

  • If set to None, the root link is not modified.

  • If the articulation already has a fixed root link, this flag will enable or disable the fixed joint.

  • If the articulation does not have a fixed root link, this flag will create a fixed joint between the world frame and the root link. The joint is created with the name “FixedJoint” under the articulation prim.

Note

This is a non-USD schema property. It is handled by the modify_articulation_root_properties() function.

Mesh Collision (PhysX cooking)#

class isaaclab_physx.sim.schemas.PhysxConvexHullPropertiesCfg[source]#

Bases: MeshCollisionBaseCfg

PhysX convex-hull cooking properties for a mesh collider.

Extends MeshCollisionBaseCfg with the PhysxConvexHullCollisionAPI schema’s tuning fields. The convexHull token is written to physics:approximation; the cooking schema is applied only when at least one tuning field is set (consistent with the other consumption-gated writers).

See modify_mesh_collision_properties() for more information.

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

Attributes:

mesh_approximation_name

"convexHull".

hull_vertex_limit

Convex hull vertex limit used for convex hull cooking.

min_thickness

Convex hull min thickness.

mesh_approximation_name: str#

“convexHull”.

Type:

Name of mesh collision approximation method. Default

hull_vertex_limit: int | None#

Convex hull vertex limit used for convex hull cooking.

Defaults to 64.

min_thickness: float | None#

Convex hull min thickness.

Range: [0, inf). Units are distance. Default value is 0.001.

class isaaclab_physx.sim.schemas.PhysxConvexDecompositionPropertiesCfg[source]#

Bases: MeshCollisionBaseCfg

PhysX convex-decomposition cooking properties for a mesh collider.

See modify_mesh_collision_properties() for more information.

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

Attributes:

mesh_approximation_name

"convexDecomposition".

hull_vertex_limit

Convex hull vertex limit used for convex hull cooking.

max_convex_hulls

Maximum of convex hulls created during convex decomposition.

min_thickness

Convex hull min thickness.

voxel_resolution

Voxel resolution used for convex decomposition.

error_percentage

Convex decomposition error percentage parameter.

shrink_wrap

Attempts to adjust the convex hull points so that they are projected onto the surface of the original graphics mesh.

mesh_approximation_name: str#

“convexDecomposition”.

Type:

Name of mesh collision approximation method. Default

hull_vertex_limit: int | None#

Convex hull vertex limit used for convex hull cooking.

Defaults to 64.

max_convex_hulls: int | None#

Maximum of convex hulls created during convex decomposition. Default value is 32.

min_thickness: float | None#

Convex hull min thickness.

Range: [0, inf). Units are distance. Default value is 0.001.

voxel_resolution: int | None#

Voxel resolution used for convex decomposition.

Defaults to 500,000 voxels.

error_percentage: float | None#

Convex decomposition error percentage parameter.

Defaults to 10 percent. Units are percent.

shrink_wrap: bool | None#

Attempts to adjust the convex hull points so that they are projected onto the surface of the original graphics mesh.

Defaults to False.

class isaaclab_physx.sim.schemas.PhysxTriangleMeshPropertiesCfg[source]#

Bases: MeshCollisionBaseCfg

PhysX triangle-mesh cooking properties for a mesh collider.

Triangle-mesh colliders are PhysX-only.

See modify_mesh_collision_properties() for more information.

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

Attributes:

mesh_approximation_name

"none" (uses triangle mesh).

weld_tolerance

Mesh weld tolerance, controls the distance at which vertices are welded.

mesh_approximation_name: str#

“none” (uses triangle mesh).

Type:

Name of mesh collision approximation method. Default

weld_tolerance: float | 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

class isaaclab_physx.sim.schemas.PhysxTriangleMeshSimplificationPropertiesCfg[source]#

Bases: MeshCollisionBaseCfg

PhysX triangle-mesh-simplification cooking properties for a mesh collider.

See modify_mesh_collision_properties() for more information.

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

Attributes:

mesh_approximation_name

"meshSimplification".

simplification_metric

Mesh simplification accuracy.

weld_tolerance

Mesh weld tolerance, controls the distance at which vertices are welded.

mesh_approximation_name: str#

“meshSimplification”.

Type:

Name of mesh collision approximation method. Default

simplification_metric: float | None#

Mesh simplification accuracy.

Defaults to 0.55.

weld_tolerance: float | 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

class isaaclab_physx.sim.schemas.PhysxSDFMeshPropertiesCfg[source]#

Bases: MeshCollisionBaseCfg

PhysX SDF-mesh cooking properties for a mesh collider.

SDF-mesh colliders are PhysX-only.

See modify_mesh_collision_properties() for more information.

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

Attributes:

mesh_approximation_name

"sdf".

sdf_margin

Margin to increase the size of the SDF relative to the bounding box diagonal length of the mesh.

sdf_narrow_band_thickness

Size of the narrow band around the mesh surface where high resolution SDF samples are available.

sdf_resolution

The spacing of the uniformly sampled SDF is equal to the largest AABB extent of the mesh, divided by the resolution.

sdf_subgrid_resolution

A positive subgrid resolution enables sparsity on signed-distance-fields (SDF) while a value of 0 leads to the usage of a dense SDF.

mesh_approximation_name: str#

“sdf”.

Type:

Name of mesh collision approximation method. Default

sdf_margin: float | 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#

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#

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#

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)

Tendon#

class isaaclab_physx.sim.schemas.PhysxFixedTendonPropertiesCfg[source]#

Bases: object

PhysX fixed-tendon properties for an articulation.

Tendons are a PhysX-only feature – Newton has no tendon system – so this class is a pure data carrier that is consumed by the PhysX-specific writer modify_fixed_tendon_properties(). The writer authors the multi-instance PhysxTendonAxisRootAPI schema; this cfg class declares no metadata-driven writer plumbing of its own.

See modify_fixed_tendon_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.

Attributes:

tendon_enabled

Whether to enable or disable the tendon.

stiffness

Spring stiffness term acting on the tendon's length.

damping

The damping term acting on both the tendon length and the tendon-length limits.

limit_stiffness

Limit stiffness term acting on the tendon's length limits.

offset

Length offset term for the tendon.

rest_length

Spring rest length of the tendon.

tendon_enabled: bool | None#

Whether to enable or disable the tendon.

stiffness: float | None#

Spring stiffness term acting on the tendon’s length.

damping: float | None#

The damping term acting on both the tendon length and the tendon-length limits.

limit_stiffness: float | None#

Limit stiffness term acting on the tendon’s length limits.

offset: float | 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#

Spring rest length of the tendon.

class isaaclab_physx.sim.schemas.PhysxSpatialTendonPropertiesCfg[source]#

Bases: object

PhysX spatial-tendon properties for an articulation.

Tendons are a PhysX-only feature – Newton has no tendon system – so this class is a pure data carrier that is consumed by the PhysX-specific writer modify_spatial_tendon_properties(). The writer authors the multi-instance PhysxTendonAttachmentRootAPI / PhysxTendonAttachmentLeafAPI schemas; this cfg class declares no metadata-driven writer plumbing of its own.

See modify_spatial_tendon_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.

Attributes:

tendon_enabled

Whether to enable or disable the tendon.

stiffness

Spring stiffness term acting on the tendon's length.

damping

The damping term acting on both the tendon length and the tendon-length limits.

limit_stiffness

Limit stiffness term acting on the tendon's length limits.

offset

Length offset term for the tendon.

tendon_enabled: bool | None#

Whether to enable or disable the tendon.

stiffness: float | None#

Spring stiffness term acting on the tendon’s length.

damping: float | None#

The damping term acting on both the tendon length and the tendon-length limits.

limit_stiffness: float | None#

Limit stiffness term acting on the tendon’s length limits.

offset: float | 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.

Deformable Body#

class isaaclab_physx.sim.schemas.OmniPhysicsDeformableBodyPropertiesCfg[source]#

Bases: DeformableBodyPropertiesBaseCfg

OmniPhysics properties for a deformable body.

These properties are set with the prefix omniphysics:<property_name>.

Attributes:

deformable_body_enabled

Enables deformable body.

kinematic_enabled

Enables kinematic body.

mass

The material mass [kg].

deformable_body_enabled: bool | None#

Enables deformable body.

kinematic_enabled: bool#

Enables kinematic body. Defaults to False, which means that the body is not kinematic.

mass: float | None#

The material mass [kg]. Defaults to None, in which case the material density is used to compute the mass.

class isaaclab_physx.sim.schemas.PhysxDeformableCollisionPropertiesCfg[source]#

Bases: object

PhysX-specific collision properties for a deformable body.

These properties are set with the prefix physxCollision:<property_name>.

See the PhysX documentation for more information on the available properties.

Note

This class is distinct from PhysxCollisionPropertiesCfg (lowercase x), which is the rigid-body collision cfg layered on CollisionBaseCfg. This class is used internally as a base of DeformableBodyPropertiesCfg.

Attributes:

contact_offset

Contact offset for the collision shape [m].

rest_offset

Rest offset for the collision shape [m].

contact_offset: float | None#

Contact offset for the collision shape [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#

Rest offset for the collision shape [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.

class isaaclab_physx.sim.schemas.PhysxDeformableBodyPropertiesCfg[source]#

Bases: OmniPhysicsDeformableBodyPropertiesCfg, PhysXDeformableBodyPropertiesCfg, PhysxDeformableCollisionPropertiesCfg

PhysX-specific properties to apply to a deformable body.

A deformable body is a body that can deform under forces, both surface and volume deformables. 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.

See modify_deformable_body_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.

Attributes:

contact_offset

Contact offset for the collision shape [m].

rest_offset

Rest offset for the collision shape [m].

solver_position_iteration_count

Number of the solver positional iterations per step.

linear_damping

Linear damping coefficient, in units of [1/s] and constrained to the range [0, inf).

max_linear_velocity

Maximum allowable linear velocity for the deformable body, in units of distance/second and constrained to the range [0, inf).

settling_damping

Additional damping applied when a vertex's velocity falls below settling_threshold.

settling_threshold

Velocity threshold below which settling_damping is applied in addition to standard damping.

sleep_threshold

Velocity threshold below which a vertex becomes a candidate for sleeping.

max_depenetration_velocity

Maximum velocity that the solver may apply to resolve intersections.

self_collision

Enables self-collisions for the deformable body, preventing self-intersections.

self_collision_filter_distance

Distance below which self-collision is disabled [m].

enable_speculative_c_c_d

Enables dynamic adjustment of contact offset based on velocity (speculative continuous collision detection).

disable_gravity

Disables gravity for the deformable body.

collision_pair_update_frequency

Determines how often surface-to-surface collision pairs are updated during each time step.

collision_iteration_multiplier

Determines how many collision subiterations are used in each solver iteration.

deformable_body_enabled

Enables deformable body.

kinematic_enabled

Enables kinematic body.

mass

The material mass [kg].

contact_offset: float | None#

Contact offset for the collision shape [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#

Rest offset for the collision shape [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.

solver_position_iteration_count: int#

Number of the solver positional iterations per step. Range is [1,255], default to 16.

linear_damping: float | None#

Linear damping coefficient, in units of [1/s] and constrained to the range [0, inf).

max_linear_velocity: float | None#

Maximum allowable linear velocity for the deformable body, in units of distance/second and constrained to the range [0, inf). A negative value allows the simulation to choose suitable a per vertex value dynamically, currently only supported for surface deformables. This can help prevent surface-surface intersections.

settling_damping: float | None#

Additional damping applied when a vertex’s velocity falls below settling_threshold. Specified in units of [1/s] and constrained to the range [0, inf).

settling_threshold: float | None#

Velocity threshold below which settling_damping is applied in addition to standard damping. Specified in units of distance/second and constrained to the range [0, inf).

sleep_threshold: float | None#

Velocity threshold below which a vertex becomes a candidate for sleeping. Specified in units of distance/seconds and constrained to the range [0, inf).

max_depenetration_velocity: float | None#

Maximum velocity that the solver may apply to resolve intersections. Specified in units of distance/seconds and constrained to the range [0, inf).

self_collision: bool | None#

Enables self-collisions for the deformable body, preventing self-intersections.

self_collision_filter_distance: float | None#

Distance below which self-collision is disabled [m].

The default value of -inf indicates that the simulation selects a suitable value. Constrained to range [rest_offset * 2, inf].

enable_speculative_c_c_d: bool | None#

Enables dynamic adjustment of contact offset based on velocity (speculative continuous collision detection).

disable_gravity: bool | None#

Disables gravity for the deformable body.

collision_pair_update_frequency: int | None#

Determines how often surface-to-surface collision pairs are updated during each time step. Increasing this value results in more frequent updates to the contact pairs, which provides better contact points.

For example, a value of 2 means collision pairs are updated twice per time step: once at the beginning and once in the middle of the time step (i.e., during the middle solver iteration). If set to 0, the solver adaptively determines when to update the surface-to-surface contact pairs, instead of using a fixed frequency.

Valid range: [1, solver_position_iteration_count].

collision_iteration_multiplier: float | None#

Determines how many collision subiterations are used in each solver iteration. By default, collision constraints are applied once per solver iteration. Increasing this value applies collision constraints more frequently within each solver iteration.

For example, a value of 2 means collision constraints are applied twice per solver iteration (i.e., collision constraints are applied 2 x solver_position_iteration_count times per time step). Increasing this value does not update collision pairs more frequently; refer to collision_pair_update_frequency for that.

Valid range: [1, solver_position_iteration_count / 2].

deformable_body_enabled: bool | None#

Enables deformable body.

kinematic_enabled: bool#

Enables kinematic body. Defaults to False, which means that the body is not kinematic.

mass: float | None#

The material mass [kg]. Defaults to None, in which case the material density is used to compute the mass.

class isaaclab_physx.sim.schemas.DeformableBodyPropertiesCfg[source]#

Bases: PhysxDeformableBodyPropertiesCfg

Deprecated: use PhysxDeformableBodyPropertiesCfg.

Deprecated since version 4.6.x: DeformableBodyPropertiesCfg has moved to PhysxDeformableBodyPropertiesCfg for PhysX-specific deformable properties and is scheduled for removal in 5.0.

Attributes:

contact_offset

Contact offset for the collision shape [m].

rest_offset

Rest offset for the collision shape [m].

solver_position_iteration_count

Number of the solver positional iterations per step.

linear_damping

Linear damping coefficient, in units of [1/s] and constrained to the range [0, inf).

max_linear_velocity

Maximum allowable linear velocity for the deformable body, in units of distance/second and constrained to the range [0, inf).

settling_damping

Additional damping applied when a vertex's velocity falls below settling_threshold.

settling_threshold

Velocity threshold below which settling_damping is applied in addition to standard damping.

sleep_threshold

Velocity threshold below which a vertex becomes a candidate for sleeping.

max_depenetration_velocity

Maximum velocity that the solver may apply to resolve intersections.

self_collision

Enables self-collisions for the deformable body, preventing self-intersections.

self_collision_filter_distance

Distance below which self-collision is disabled [m].

enable_speculative_c_c_d

Enables dynamic adjustment of contact offset based on velocity (speculative continuous collision detection).

disable_gravity

Disables gravity for the deformable body.

collision_pair_update_frequency

Determines how often surface-to-surface collision pairs are updated during each time step.

collision_iteration_multiplier

Determines how many collision subiterations are used in each solver iteration.

deformable_body_enabled

Enables deformable body.

kinematic_enabled

Enables kinematic body.

mass

The material mass [kg].

contact_offset: float | None#

Contact offset for the collision shape [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#

Rest offset for the collision shape [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.

solver_position_iteration_count: int#

Number of the solver positional iterations per step. Range is [1,255], default to 16.

linear_damping: float | None#

Linear damping coefficient, in units of [1/s] and constrained to the range [0, inf).

max_linear_velocity: float | None#

Maximum allowable linear velocity for the deformable body, in units of distance/second and constrained to the range [0, inf). A negative value allows the simulation to choose suitable a per vertex value dynamically, currently only supported for surface deformables. This can help prevent surface-surface intersections.

settling_damping: float | None#

Additional damping applied when a vertex’s velocity falls below settling_threshold. Specified in units of [1/s] and constrained to the range [0, inf).

settling_threshold: float | None#

Velocity threshold below which settling_damping is applied in addition to standard damping. Specified in units of distance/second and constrained to the range [0, inf).

sleep_threshold: float | None#

Velocity threshold below which a vertex becomes a candidate for sleeping. Specified in units of distance/seconds and constrained to the range [0, inf).

max_depenetration_velocity: float | None#

Maximum velocity that the solver may apply to resolve intersections. Specified in units of distance/seconds and constrained to the range [0, inf).

self_collision: bool | None#

Enables self-collisions for the deformable body, preventing self-intersections.

self_collision_filter_distance: float | None#

Distance below which self-collision is disabled [m].

The default value of -inf indicates that the simulation selects a suitable value. Constrained to range [rest_offset * 2, inf].

enable_speculative_c_c_d: bool | None#

Enables dynamic adjustment of contact offset based on velocity (speculative continuous collision detection).

disable_gravity: bool | None#

Disables gravity for the deformable body.

collision_pair_update_frequency: int | None#

Determines how often surface-to-surface collision pairs are updated during each time step. Increasing this value results in more frequent updates to the contact pairs, which provides better contact points.

For example, a value of 2 means collision pairs are updated twice per time step: once at the beginning and once in the middle of the time step (i.e., during the middle solver iteration). If set to 0, the solver adaptively determines when to update the surface-to-surface contact pairs, instead of using a fixed frequency.

Valid range: [1, solver_position_iteration_count].

collision_iteration_multiplier: float | None#

Determines how many collision subiterations are used in each solver iteration. By default, collision constraints are applied once per solver iteration. Increasing this value applies collision constraints more frequently within each solver iteration.

For example, a value of 2 means collision constraints are applied twice per solver iteration (i.e., collision constraints are applied 2 x solver_position_iteration_count times per time step). Increasing this value does not update collision pairs more frequently; refer to collision_pair_update_frequency for that.

Valid range: [1, solver_position_iteration_count / 2].

deformable_body_enabled: bool | None#

Enables deformable body.

kinematic_enabled: bool#

Enables kinematic body. Defaults to False, which means that the body is not kinematic.

mass: float | None#

The material mass [kg]. Defaults to None, in which case the material density is used to compute the mass.

Schema define and modify functions remain unified in isaaclab.sim.schemas.