From d9eda7c1c4df46349419586f73deeaadf134473c Mon Sep 17 00:00:00 2001 From: Vidur Vij Date: Thu, 4 Jun 2026 16:27:04 -0700 Subject: [PATCH] refactor(schemas): migrate rigid_props to fragments; deprecate RigidBodyPropertiesCfg Build on the additive rigid-body fragment API: flip the legacy name and move every call site to the new fragment-list form. - isaaclab_physx: RigidBodyPropertiesCfg becomes a deprecation factory returning [UsdPhysicsRigidBodyCfg(...), PhysxRigidBodyCfg(...)] (removal in 5.0). - Migrate all RigidBodyPropertiesCfg usages across isaaclab_assets, isaaclab_tasks, isaaclab_mimic and the test suites to fragment lists. - Update consumer sites that treated rigid_props as a single object: disable_gravity mutations, .replace(), and attribute reads. BREAKING: RigidBodyPropertiesCfg no longer returns a single cfg object. Pass a fragment list to rigid_props; code mutating attributes on it must set the field on the PhysxRigidBodyCfg fragment in the list. --- .../mdp/actions/pink_task_space_actions.py | 5 +- source/isaaclab/isaaclab/sim/__init__.pyi | 226 +++++++++--------- .../test/controllers/test_differential_ik.py | 4 +- .../controllers/test_operational_space.py | 19 +- .../check_manager_based_env_floating_cube.py | 3 +- .../test/envs/test_scale_randomization.py | 5 +- .../test/scene/test_interactive_scene.py | 9 +- .../sensors/check_multi_mesh_ray_caster.py | 4 +- .../isaaclab/test/sensors/check_ray_caster.py | 2 +- .../generate_synthetic_gaussian_asset.py | 2 +- source/isaaclab/test/sensors/test_camera.py | 2 +- .../test/sensors/test_multi_tiled_camera.py | 2 +- .../test/sensors/test_tiled_camera.py | 2 +- source/isaaclab/test/sim/check_meshes.py | 2 +- .../test/sim/test_schema_fragments.py | 22 +- .../sim/test_simulation_stage_in_memory.py | 25 +- .../test/sim/test_spawn_from_files.py | 7 +- source/isaaclab/test/sim/test_spawn_meshes.py | 14 +- source/isaaclab/test/sim/test_spawn_shapes.py | 32 +-- .../isaaclab/test/sim/test_spawn_wrappers.py | 35 ++- .../test/terrains/check_terrain_importer.py | 4 +- .../test/terrains/test_terrain_importer.py | 4 +- .../utils/test_wrench_composer_integration.py | 2 +- .../utils/test_wrench_composer_vs_physx.py | 2 +- .../changelog.d/vidurv-schema-fragments.rst | 7 + .../isaaclab_assets/robots/agibot.py | 12 +- .../isaaclab_assets/robots/allegro.py | 24 +- .../isaaclab_assets/robots/ant.py | 14 +- .../isaaclab_assets/robots/anymal.py | 62 ++--- .../isaaclab_assets/robots/arl_robot_1.py | 22 +- .../robots/cart_double_pendulum.py | 18 +- .../isaaclab_assets/robots/cartpole.py | 18 +- .../isaaclab_assets/robots/cassie.py | 22 +- .../isaaclab_assets/robots/flexiv.py | 22 +- .../isaaclab_assets/robots/fourier.py | 21 +- .../isaaclab_assets/robots/franka.py | 16 +- .../isaaclab_assets/robots/galbot.py | 12 +- .../isaaclab_assets/robots/humanoid.py | 14 +- .../isaaclab_assets/robots/humanoid_28.py | 14 +- .../isaaclab_assets/robots/kinova.py | 32 ++- .../isaaclab_assets/robots/kuka_allegro.py | 22 +- .../isaaclab_assets/robots/openarm.py | 26 +- .../isaaclab_assets/robots/pick_and_place.py | 14 +- .../isaaclab_assets/robots/quadcopter.py | 14 +- .../isaaclab_assets/robots/sawyer.py | 12 +- .../isaaclab_assets/robots/shadow_hand.py | 14 +- .../isaaclab_assets/robots/spot.py | 22 +- .../isaaclab_assets/robots/unitree.py | 148 +++++++----- .../robots/universal_robots.py | 28 ++- .../changelog.d/vidurv-schema-fragments.skip | 1 + .../test_rigid_deformable_coupling.py | 2 +- .../changelog.d/vidurv-schema-fragments.rst | 5 + .../envs/g1_locomanipulation_sdg_env.py | 4 +- .../test/test_curobo_planner_franka.py | 9 +- .../test/assets/test_rigid_object.py | 4 +- .../assets/test_rigid_object_collection.py | 2 +- .../test/physics/physics_test_utils.py | 13 +- .../test/sensors/test_contact_sensor.py | 13 +- .../test/sensors/test_frame_transformer.py | 3 +- .../isaaclab_newton/test/sensors/test_imu.py | 4 +- .../isaaclab_newton/test/sensors/test_pva.py | 6 +- .../test/sim/test_views_xform_prim_newton.py | 2 +- .../test/assets/test_rigid_object.py | 4 +- .../assets/test_rigid_object_collection.py | 2 +- .../test/sensors/test_contact_sensor.py | 41 ++-- .../test/sim/test_views_xform_prim_ovphysx.py | 2 +- .../vidurv-schema-fragments.minor.rst | 15 +- .../isaaclab_physx/sim/schemas/schemas_cfg.py | 51 ++-- .../test/assets/test_articulation.py | 11 +- .../test/assets/test_rigid_object.py | 4 +- .../assets/test_rigid_object_collection.py | 2 +- .../test/assets/test_surface_gripper.py | 4 +- ...t_isaac_rtx_renderer_scene_partitioning.py | 3 +- .../test/sensors/check_pva_sensor.py | 2 +- .../test/sensors/test_contact_sensor.py | 41 ++-- .../test/sensors/test_frame_transformer.py | 3 +- .../isaaclab_physx/test/sensors/test_imu.py | 6 +- .../isaaclab_physx/test/sensors/test_pva.py | 6 +- source/isaaclab_physx/test/sim/test_cloner.py | 25 +- .../changelog.d/vidurv-schema-fragments.rst | 5 + .../assemble_trocar/g129_dex3_env_cfg.py | 11 +- .../contrib/automate/assembly_env_cfg.py | 27 ++- .../contrib/automate/assembly_tasks_cfg.py | 54 +++-- .../contrib/automate/disassembly_env_cfg.py | 27 ++- .../contrib/automate/disassembly_tasks_cfg.py | 54 +++-- .../config/rizon_4s/joint_pos_env_cfg.py | 27 ++- .../config/ur_10e/joint_pos_env_cfg.py | 53 ++-- .../gear_assembly/gear_assembly_env_cfg.py | 113 +++++---- .../scenes/obstacle_scenes/obstacle_scene.py | 45 ++-- .../contrib/factory/factory_env_cfg.py | 27 ++- .../contrib/factory/factory_tasks_cfg.py | 210 ++++++++-------- .../lift/config/openarm/joint_pos_env_cfg.py | 21 +- .../fixed_base_upper_body_ik_g1_env_cfg.py | 4 +- .../locomanipulation_g1_env_cfg.py | 4 +- .../exhaustpipe_gr1t2_base_env_cfg.py | 8 +- .../pick_place/nutpour_gr1t2_base_env_cfg.py | 12 +- .../pick_place/pickplace_gr1t2_env_cfg.py | 4 +- ...ckplace_unitree_g1_inspire_hand_env_cfg.py | 4 +- .../agibot/place_toy2box_rmp_rel_env_cfg.py | 21 +- .../place_upright_mug_rmp_rel_env_cfg.py | 21 +- .../franka/bin_stack_joint_pos_env_cfg.py | 23 +- .../franka/stack_ik_rel_visuomotor_env_cfg.py | 21 +- .../config/franka/stack_joint_pos_env_cfg.py | 21 +- ...ck_joint_pos_instance_randomize_env_cfg.py | 20 +- .../config/galbot/stack_joint_pos_env_cfg.py | 21 +- .../ur10_gripper/stack_joint_pos_env_cfg.py | 20 +- .../core/allegro_hand/allegro_hand_env_cfg.py | 45 ++-- .../core/dexsuite/dexsuite_env_cfg.py | 27 ++- .../franka_cabinet/franka_cabinet_env_cfg.py | 12 +- .../core/inhand/inhand_env_cfg.py | 23 +- .../lift/config/franka/joint_pos_env_cfg.py | 21 +- .../lift_franka_soft/franka_soft_env_cfg.py | 4 +- .../core/reach/config/franka/osc_env_cfg.py | 4 +- .../core/reach/reach_env_cfg.py | 4 +- .../core/shadow_hand/shadow_hand_env_cfg.py | 35 +-- .../shadow_hand_over_env_cfg.py | 35 +-- 116 files changed, 1399 insertions(+), 1043 deletions(-) create mode 100644 source/isaaclab_assets/changelog.d/vidurv-schema-fragments.rst create mode 100644 source/isaaclab_contrib/changelog.d/vidurv-schema-fragments.skip create mode 100644 source/isaaclab_mimic/changelog.d/vidurv-schema-fragments.rst create mode 100644 source/isaaclab_tasks/changelog.d/vidurv-schema-fragments.rst diff --git a/source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py b/source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py index 1612c6621c71..0692e47e8414 100644 --- a/source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py +++ b/source/isaaclab/isaaclab/envs/mdp/actions/pink_task_space_actions.py @@ -329,7 +329,10 @@ def _apply_gravity_compensation(self) -> None: rather than silently receive zeros. To use Pink IK on Newton, keep ``enable_gravity_compensation=False``. """ - if not self._asset.cfg.spawn.rigid_props.disable_gravity: + _rigid_props = self._asset.cfg.spawn.rigid_props + _rigid_frags = _rigid_props if isinstance(_rigid_props, (list, tuple)) else [_rigid_props] + _disable_gravity = any(getattr(f, "disable_gravity", None) for f in _rigid_frags if f is not None) + if not _disable_gravity: # ``gravity_compensation_forces`` shape is ``(N, num_joints + num_base_dofs)``. # Shift actuated-joint ids by ``num_base_dofs`` to skip the leading floating- # base columns (0 for fixed-base, 6 for floating-base). diff --git a/source/isaaclab/isaaclab/sim/__init__.pyi b/source/isaaclab/isaaclab/sim/__init__.pyi index 9578caa87b49..2ffb9b321370 100644 --- a/source/isaaclab/isaaclab/sim/__init__.pyi +++ b/source/isaaclab/isaaclab/sim/__init__.pyi @@ -196,6 +196,8 @@ __all__ = [ "XformPrimView", ] +from .simulation_cfg import RenderCfg, SimulationCfg +from .simulation_context import SimulationContext, build_simulation_context from .converters import ( AssetConverterBase, AssetConverterBaseCfg, @@ -210,6 +212,24 @@ from .schemas import ( MESH_APPROXIMATION_TOKENS, PHYSX_MESH_COLLISION_CFGS, USD_MESH_COLLISION_CFGS, + activate_contact_sensors, + apply_namespaced, + apply_rigid_body_properties, + define_articulation_root_properties, + define_collision_properties, + define_deformable_body_properties, + define_mass_properties, + define_mesh_collision_properties, + define_rigid_body_properties, + modify_articulation_root_properties, + modify_collision_properties, + modify_deformable_body_properties, + modify_fixed_tendon_properties, + modify_joint_drive_properties, + modify_mass_properties, + modify_mesh_collision_properties, + modify_rigid_body_properties, + modify_spatial_tendon_properties, ArticulationRootPropertiesCfg, BoundingCubePropertiesCfg, BoundingSpherePropertiesCfg, @@ -227,32 +247,12 @@ from .schemas import ( RigidBodyBaseCfg, RigidBodyFragment, SchemaFragment, + UsdPhysicsRigidBodyCfg, SDFMeshPropertiesCfg, SpatialTendonPropertiesCfg, TriangleMeshPropertiesCfg, TriangleMeshSimplificationPropertiesCfg, - UsdPhysicsRigidBodyCfg, - activate_contact_sensors, - apply_namespaced, - apply_rigid_body_properties, - define_articulation_root_properties, - define_collision_properties, - define_deformable_body_properties, - define_mass_properties, - define_mesh_collision_properties, - define_rigid_body_properties, - modify_articulation_root_properties, - modify_collision_properties, - modify_deformable_body_properties, - modify_fixed_tendon_properties, - modify_joint_drive_properties, - modify_mass_properties, - modify_mesh_collision_properties, - modify_rigid_body_properties, - modify_spatial_tendon_properties, ) -from .simulation_cfg import RenderCfg, SimulationCfg -from .simulation_context import SimulationContext, build_simulation_context # Forwarded to isaaclab_newton.sim.schemas via __getattr__ shim MujocoJointDrivePropertiesCfg = ... @@ -265,22 +265,46 @@ NewtonMeshCollisionPropertiesCfg = ... NewtonRigidBodyPropertiesCfg = ... NewtonSDFCollisionPropertiesCfg = ... from .spawners import ( - CapsuleCfg, - ConeCfg, - CuboidCfg, - CylinderCfg, - CylinderLightCfg, - DeformableBodyMaterialBaseCfg, - DeformableBodyMaterialCfg, + SpawnerCfg, + RigidObjectSpawnerCfg, DeformableObjectSpawnerCfg, + spawn_from_mjcf, + spawn_from_urdf, + spawn_from_usd, + spawn_from_usd_with_compliant_contact_material, + spawn_ground_plane, + GroundPlaneCfg, + MjcfFileCfg, + UrdfFileCfg, + UsdFileCfg, + UsdFileWithCompliantContactCfg, + spawn_light, + CylinderLightCfg, DiskLightCfg, DistantLightCfg, DomeLightCfg, - FisheyeCameraCfg, - GlassMdlCfg, - GroundPlaneCfg, LightCfg, + SphereLightCfg, + spawn_rigid_body_material, + spawn_deformable_body_material, + PhysicsMaterialCfg, + RigidBodyMaterialCfg, + DeformableBodyMaterialBaseCfg, + DeformableBodyMaterialCfg, + SurfaceDeformableBodyMaterialBaseCfg, + SurfaceDeformableBodyMaterialCfg, + spawn_from_mdl_file, + spawn_preview_surface, + GlassMdlCfg, MdlFileCfg, + PreviewSurfaceCfg, + VisualMaterialCfg, + spawn_mesh_capsule, + spawn_mesh_cone, + spawn_mesh_cuboid, + spawn_mesh_cylinder, + spawn_mesh_rectangle, + spawn_mesh_sphere, MeshCapsuleCfg, MeshCfg, MeshConeCfg, @@ -288,110 +312,82 @@ from .spawners import ( MeshCylinderCfg, MeshRectangleCfg, MeshSphereCfg, - MjcfFileCfg, - MultiAssetSpawnerCfg, - MultiUsdFileCfg, - PhysicsMaterialCfg, + spawn_camera, + spawn_sensor_frame, + FisheyeCameraCfg, PinholeCameraCfg, - PreviewSurfaceCfg, - RigidBodyMaterialCfg, - RigidObjectSpawnerCfg, SensorFrameCfg, - ShapeCfg, - SpawnerCfg, - SphereCfg, - SphereLightCfg, - SurfaceDeformableBodyMaterialBaseCfg, - SurfaceDeformableBodyMaterialCfg, - UrdfFileCfg, - UsdFileCfg, - UsdFileWithCompliantContactCfg, - VisualMaterialCfg, - spawn_camera, spawn_capsule, spawn_cone, spawn_cuboid, spawn_cylinder, - spawn_deformable_body_material, - spawn_from_mdl_file, - spawn_from_mjcf, - spawn_from_urdf, - spawn_from_usd, - spawn_from_usd_with_compliant_contact_material, - spawn_ground_plane, - spawn_light, - spawn_mesh_capsule, - spawn_mesh_cone, - spawn_mesh_cuboid, - spawn_mesh_cylinder, - spawn_mesh_rectangle, - spawn_mesh_sphere, + spawn_sphere, + CapsuleCfg, + ConeCfg, + CuboidCfg, + CylinderCfg, + ShapeCfg, + SphereCfg, spawn_multi_asset, spawn_multi_usd_file, - spawn_preview_surface, - spawn_rigid_body_material, - spawn_sensor_frame, - spawn_sphere, + MultiAssetSpawnerCfg, + MultiUsdFileCfg, ) from .utils import ( - add_labels, add_reference_to_stage, - add_usd_reference, - apply_nested, - bind_physics_material, - bind_visual_material, - change_prim_property, - check_missing_labels, - clear_stage, - clone, - close_stage, - convert_world_pose_to_local, - count_total_labels, - create_new_stage, - create_prim, + get_stage_up_axis, + traverse_stage, + get_prim_at_path, + get_prim_path, + is_prim_path_valid, define_prim, + get_prim_type_name, + get_next_free_path, + create_prim, delete_prim, + make_uninstanceable, + set_prim_visibility, + safe_set_attribute_on_usd_schema, + safe_set_attribute_on_usd_prim, + change_prim_property, export_prim_to_file, - find_first_matching_prim, - find_global_fixed_joint_prim, - find_matching_prim_paths, - find_matching_prims, - get_all_matching_child_prims, - get_current_stage, - get_current_stage_id, + apply_nested, + clone, + bind_visual_material, + bind_physics_material, + add_usd_reference, + get_usd_references, + select_usd_variants, + get_next_free_prim_path, get_first_matching_ancestor_prim, get_first_matching_child_prim, + get_all_matching_child_prims, + find_first_matching_prim, + find_matching_prims, + resolve_matching_prims_from_source, + find_matching_prim_paths, + find_global_fixed_joint_prim, + add_labels, get_labels, - get_next_free_path, - get_next_free_prim_path, - get_prim_at_path, - get_prim_path, - get_prim_type_name, - get_stage_up_axis, - get_usd_references, - is_current_stage_in_memory, - is_prim_path_valid, - make_uninstanceable, - open_stage, remove_labels, - resolve_matching_prims_from_source, + check_missing_labels, + count_total_labels, resolve_paths, - resolve_prim_pose, - resolve_prim_scale, - safe_set_attribute_on_usd_prim, - safe_set_attribute_on_usd_schema, + create_new_stage, + is_current_stage_in_memory, + open_stage, + use_stage, + update_stage, save_stage, - select_usd_variants, - set_prim_visibility, + close_stage, + clear_stage, + get_current_stage, + get_current_stage_id, standardize_xform_ops, - traverse_stage, - update_stage, - use_stage, validate_standard_xform_ops, + resolve_prim_pose, + resolve_prim_scale, + convert_world_pose_to_local, ) -from .views import ( - BaseFrameView, - FrameView, - UsdFrameView, - XformPrimView, # deprecated alias -) +from .views import BaseFrameView, UsdFrameView, FrameView +from .views import XformPrimView # deprecated alias diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index 2ba7af0ec028..3e566323bf0c 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -28,6 +28,8 @@ subtract_frame_transforms, ) +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg # isort:skip + ## # Pre-defined configs ## @@ -100,7 +102,7 @@ def test_ur10_ik_pose_abs(sim): # Create robot instance robot_cfg = UR10_CFG.replace(prim_path="/World/envs/env_.*/Robot") - robot_cfg.spawn.rigid_props.disable_gravity = True + next(f for f in robot_cfg.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True robot = Articulation(cfg=robot_cfg) # Create IK controller diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index bed0760271e7..9bbea46593d4 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -15,6 +15,7 @@ import pytest import torch from flaky import flaky +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils @@ -95,7 +96,7 @@ def sim(): robot_cfg.actuators["panda_shoulder"].damping = 0.0 robot_cfg.actuators["panda_forearm"].stiffness = 0.0 robot_cfg.actuators["panda_forearm"].damping = 0.0 - robot_cfg.spawn.rigid_props.disable_gravity = True + next(f for f in robot_cfg.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True # Define the ContactSensor contact_forces = None @@ -355,7 +356,7 @@ def test_franka_pose_abs_fixed_impedance_with_gravity_compensation(sim): frame, ) = sim - robot_cfg.spawn.rigid_props.disable_gravity = False + next(f for f in robot_cfg.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = False robot = Articulation(cfg=robot_cfg) osc_cfg = OperationalSpaceControllerCfg( target_types=["pose_abs"], @@ -560,7 +561,7 @@ def test_franka_wrench_abs_open_loop(sim): size=(0.7, 0.7, 0.01), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1), - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], activate_contact_sensors=True, ) obstacle_spawn_cfg.func( @@ -641,7 +642,7 @@ def test_franka_wrench_abs_closed_loop(sim): size=(0.7, 0.7, 0.01), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1), - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], activate_contact_sensors=True, ) obstacle_spawn_cfg.func( @@ -730,7 +731,7 @@ def test_franka_hybrid_decoupled_motion(sim): size=(1.0, 1.0, 0.01), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1), - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], activate_contact_sensors=True, ) obstacle_spawn_cfg.func( @@ -807,7 +808,7 @@ def test_franka_hybrid_variable_kp_impedance(sim): size=(1.0, 1.0, 0.01), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1), - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], activate_contact_sensors=True, ) obstacle_spawn_cfg.func( @@ -987,7 +988,7 @@ def test_franka_taskframe_hybrid(sim): size=(2.0, 1.5, 0.01), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1), - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], activate_contact_sensors=True, ) obstacle_spawn_cfg.func( @@ -1216,7 +1217,7 @@ def test_franka_taskframe_hybrid_with_nullspace_centering(sim): size=(2.0, 1.5, 0.01), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), opacity=0.1), - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], activate_contact_sensors=True, ) obstacle_spawn_cfg.func( @@ -1286,7 +1287,7 @@ class _FloatingBaseOscSceneCfg(InteractiveSceneCfg): def __post_init__(self): super().__post_init__() self.robot.spawn.articulation_props.fix_root_link = False - self.robot.spawn.rigid_props.disable_gravity = True + next(f for f in self.robot.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True @lab_configclass diff --git a/source/isaaclab/test/envs/check_manager_based_env_floating_cube.py b/source/isaaclab/test/envs/check_manager_based_env_floating_cube.py index ef0a151434b5..72ca227b5319 100644 --- a/source/isaaclab/test/envs/check_manager_based_env_floating_cube.py +++ b/source/isaaclab/test/envs/check_manager_based_env_floating_cube.py @@ -31,6 +31,7 @@ """Rest everything follows.""" import torch +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils @@ -62,7 +63,7 @@ class MySceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(max_depenetration_velocity=1.0), + rigid_props=[PhysxRigidBodyCfg(max_depenetration_velocity=1.0)], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), physics_material=sim_utils.RigidBodyMaterialCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.0, 0.0)), diff --git a/source/isaaclab/test/envs/test_scale_randomization.py b/source/isaaclab/test/envs/test_scale_randomization.py index 1104425b4b1c..119562a2d0d7 100644 --- a/source/isaaclab/test/envs/test_scale_randomization.py +++ b/source/isaaclab/test/envs/test_scale_randomization.py @@ -22,6 +22,7 @@ import pytest import torch +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg from pxr import Sdf @@ -153,7 +154,7 @@ class MySceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/cube1", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(max_depenetration_velocity=1.0, disable_gravity=True), + rigid_props=[PhysxRigidBodyCfg(max_depenetration_velocity=1.0, disable_gravity=True)], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), physics_material=sim_utils.RigidBodyMaterialCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 0.0)), @@ -166,7 +167,7 @@ class MySceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/cube2", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(max_depenetration_velocity=1.0, disable_gravity=True), + rigid_props=[PhysxRigidBodyCfg(max_depenetration_velocity=1.0, disable_gravity=True)], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), physics_material=sim_utils.RigidBodyMaterialCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 0.0)), diff --git a/source/isaaclab/test/scene/test_interactive_scene.py b/source/isaaclab/test/scene/test_interactive_scene.py index ce8b2a6cb26d..b16848668b7d 100644 --- a/source/isaaclab/test/scene/test_interactive_scene.py +++ b/source/isaaclab/test/scene/test_interactive_scene.py @@ -17,6 +17,7 @@ import pytest import torch +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -47,9 +48,11 @@ class MySceneCfg(InteractiveSceneCfg): prim_path="/World/envs/env_.*/RigidObj", spawn=sim_utils.CuboidCfg( size=(0.5, 0.5, 0.5), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), diff --git a/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py b/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py index 5823e6c79f82..9b99dde1c9cd 100644 --- a/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py +++ b/source/isaaclab/test/sensors/check_multi_mesh_ray_caster.py @@ -75,7 +75,7 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048): # -- Balls cfg = sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)), @@ -85,7 +85,7 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048): for i in range(args_cli.num_objects): object = sim_utils.CuboidCfg( size=(0.5 + random.random() * 0.5, 0.5 + random.random() * 0.5, 0.1 + random.random() * 0.05), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg( diff --git a/source/isaaclab/test/sensors/check_ray_caster.py b/source/isaaclab/test/sensors/check_ray_caster.py index 87d8a9594ad5..3bb3ba6163a4 100644 --- a/source/isaaclab/test/sensors/check_ray_caster.py +++ b/source/isaaclab/test/sensors/check_ray_caster.py @@ -69,7 +69,7 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048): # -- Balls cfg = sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)), diff --git a/source/isaaclab/test/sensors/generate_synthetic_gaussian_asset.py b/source/isaaclab/test/sensors/generate_synthetic_gaussian_asset.py index 2e6c9f471b04..492a14a73e6d 100644 --- a/source/isaaclab/test/sensors/generate_synthetic_gaussian_asset.py +++ b/source/isaaclab/test/sensors/generate_synthetic_gaussian_asset.py @@ -454,7 +454,7 @@ class SyntheticGaussianSceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/Anchor", spawn=sim_utils.CuboidCfg( size=(0.01, 0.01, 0.01), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.001), collision_props=sim_utils.CollisionPropertiesCfg(), physics_material=sim_utils.RigidBodyMaterialCfg(), diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index 9b41899765b7..8be19d65281e 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -1273,6 +1273,6 @@ def _populate_scene(): geom_prim.GetDisplayColorAttr().Set([color]) # add rigid body and collision properties using Isaac Lab schemas prim_path = f"/World/Objects/Obj_{i:02d}" - sim_utils.define_rigid_body_properties(prim_path, sim_utils.RigidBodyPropertiesCfg()) + sim_utils.apply_rigid_body_properties(prim_path, [sim_utils.UsdPhysicsRigidBodyCfg()]) sim_utils.define_mass_properties(prim_path, sim_utils.MassPropertiesCfg(mass=5.0)) sim_utils.define_collision_properties(prim_path, sim_utils.CollisionPropertiesCfg()) diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index 5188f5a897ef..f09886b9b31e 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -487,6 +487,6 @@ def _populate_scene(): geom_prim.GetDisplayColorAttr().Set([color]) # add rigid body and collision properties using Isaac Lab schemas prim_path = f"/World/Objects/Obj_{i:02d}" - sim_utils.define_rigid_body_properties(prim_path, sim_utils.RigidBodyPropertiesCfg()) + sim_utils.apply_rigid_body_properties(prim_path, [sim_utils.UsdPhysicsRigidBodyCfg()]) sim_utils.define_mass_properties(prim_path, sim_utils.MassPropertiesCfg(mass=5.0)) sim_utils.define_collision_properties(prim_path, sim_utils.CollisionPropertiesCfg()) diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index 47c5aee61d66..e2d9f3f1fccd 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -192,6 +192,6 @@ def _populate_scene(): geom_prim.GetDisplayColorAttr().Set([color]) # add rigid body and collision properties using Isaac Lab schemas prim_path = f"/World/Objects/Obj_{i:02d}" - sim_utils.define_rigid_body_properties(prim_path, sim_utils.RigidBodyPropertiesCfg()) + sim_utils.apply_rigid_body_properties(prim_path, [sim_utils.UsdPhysicsRigidBodyCfg()]) sim_utils.define_mass_properties(prim_path, sim_utils.MassPropertiesCfg(mass=5.0)) sim_utils.define_collision_properties(prim_path, sim_utils.CollisionPropertiesCfg()) diff --git a/source/isaaclab/test/sim/check_meshes.py b/source/isaaclab/test/sim/check_meshes.py index 705677281d3c..6798e453874d 100644 --- a/source/isaaclab/test/sim/check_meshes.py +++ b/source/isaaclab/test/sim/check_meshes.py @@ -130,7 +130,7 @@ def design_scene(): 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.rigid_props = [sim_utils.UsdPhysicsRigidBodyCfg()] obj_cfg.collision_props = sim_utils.CollisionPropertiesCfg() # randomize the color obj_cfg.visual_material.diffuse_color = (random.random(), random.random(), random.random()) diff --git a/source/isaaclab/test/sim/test_schema_fragments.py b/source/isaaclab/test/sim/test_schema_fragments.py index de74a77af299..fb437958f351 100644 --- a/source/isaaclab/test/sim/test_schema_fragments.py +++ b/source/isaaclab/test/sim/test_schema_fragments.py @@ -12,6 +12,8 @@ """Rest everything follows.""" +import warnings + from pxr import UsdGeom, UsdPhysics import isaaclab.sim as sim_utils @@ -151,6 +153,24 @@ def test_spawn_shape_with_rigid_fragment_list(): assert abs(prim.GetAttribute("physxRigidBody:linearDamping").Get() - 0.3) < 1e-6 +# ------------------------------------------------------------------------------------- +# Task 7 -- RigidBodyPropertiesCfg deprecation factory (isaaclab_physx) +# ------------------------------------------------------------------------------------- + + +def test_rigidbody_properties_factory_returns_fragments(): + from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg, RigidBodyPropertiesCfg + + from isaaclab.sim.schemas import UsdPhysicsRigidBodyCfg + + with warnings.catch_warnings(record=True) as w: + warnings.simplefilter("always") + frags = RigidBodyPropertiesCfg(rigid_body_enabled=True, linear_damping=0.1) + assert any(issubclass(x.category, DeprecationWarning) for x in w) + assert any(isinstance(f, UsdPhysicsRigidBodyCfg) and f.rigid_body_enabled is True for f in frags) + assert any(isinstance(f, PhysxRigidBodyCfg) and abs(f.linear_damping - 0.1) < 1e-6 for f in frags) + + # ------------------------------------------------------------------------------------- # Task 8 -- public imports # ------------------------------------------------------------------------------------- @@ -158,7 +178,7 @@ def test_spawn_shape_with_rigid_fragment_list(): def test_public_imports(): from isaaclab_newton.sim.schemas import MujocoRigidBodyCfg # noqa: F401 - from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg # noqa: F401 + from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg, RigidBodyPropertiesCfg # noqa: F401 from isaaclab.sim.schemas import ( # noqa: F401 RigidBodyFragment, diff --git a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py index 1add70c70989..20668c7c75fc 100644 --- a/source/isaaclab/test/sim/test_simulation_stage_in_memory.py +++ b/source/isaaclab/test/sim/test_simulation_stage_in_memory.py @@ -18,6 +18,7 @@ import pytest import torch +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import omni.physx import omni.usd @@ -98,9 +99,7 @@ def test_stage_in_memory_with_shapes(sim): ), ], random_choice=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=4, solver_velocity_iteration_count=0 - ), + rigid_props=[PhysxRigidBodyCfg(solver_position_iteration_count=4, solver_velocity_iteration_count=0)], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ) @@ -145,15 +144,17 @@ def test_stage_in_memory_with_usds(sim): cfg = sim_utils.MultiUsdFileCfg( usd_path=usd_paths, random_choice=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), diff --git a/source/isaaclab/test/sim/test_spawn_from_files.py b/source/isaaclab/test/sim/test_spawn_from_files.py index 009949de4c9c..ffe7eb12f7f2 100644 --- a/source/isaaclab/test/sim/test_spawn_from_files.py +++ b/source/isaaclab/test/sim/test_spawn_from_files.py @@ -13,6 +13,7 @@ """Rest everything follows.""" import pytest +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import omni.kit.app @@ -108,7 +109,7 @@ def test_spawn_usd_with_compliant_contact_material(sim): # Create spawn configuration spawn_cfg = sim_utils.UsdFileWithCompliantContactCfg( usd_path=usd_file_path, - rigid_props=sim_utils.RigidBodyPropertiesCfg(disable_gravity=True), + rigid_props=[PhysxRigidBodyCfg(disable_gravity=True)], compliant_contact_stiffness=1000.0, compliant_contact_damping=100.0, physics_material_prim_path="elastomer", @@ -142,7 +143,7 @@ def test_spawn_usd_with_compliant_contact_material_on_multiple_prims(sim): # Create spawn configuration spawn_cfg = sim_utils.UsdFileWithCompliantContactCfg( usd_path=usd_file_path, - rigid_props=sim_utils.RigidBodyPropertiesCfg(disable_gravity=True), + rigid_props=[PhysxRigidBodyCfg(disable_gravity=True)], compliant_contact_stiffness=1000.0, compliant_contact_damping=100.0, physics_material_prim_path=["elastomer", "gelsight_finger"], @@ -178,7 +179,7 @@ def test_spawn_usd_with_compliant_contact_material_no_prim_path(sim): # Create spawn configuration without physics material prim path spawn_cfg = sim_utils.UsdFileWithCompliantContactCfg( usd_path=usd_file_path, - rigid_props=sim_utils.RigidBodyPropertiesCfg(disable_gravity=True), + rigid_props=[PhysxRigidBodyCfg(disable_gravity=True)], compliant_contact_stiffness=1000.0, compliant_contact_damping=100.0, physics_material_prim_path=None, diff --git a/source/isaaclab/test/sim/test_spawn_meshes.py b/source/isaaclab/test/sim/test_spawn_meshes.py index 97aca4a23f78..48abfd6a0434 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -14,6 +14,7 @@ import pytest +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -148,9 +149,10 @@ def test_spawn_cone_with_all_rigid_props(sim): 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 - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(rigid_body_enabled=True), + PhysxRigidBodyCfg(solver_position_iteration_count=8, sleep_threshold=0.1), + ], collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.75, 0.5)), physics_material=sim_utils.RigidBodyMaterialCfg(), @@ -164,12 +166,12 @@ def test_spawn_cone_with_all_rigid_props(sim): # Check properties # -- rigid body prim = sim.stage.GetPrimAtPath("/World/Cone") - assert prim.GetAttribute("physics:rigidBodyEnabled").Get() == cfg.rigid_props.rigid_body_enabled + assert prim.GetAttribute("physics:rigidBodyEnabled").Get() == cfg.rigid_props[0].rigid_body_enabled assert ( prim.GetAttribute("physxRigidBody:solverPositionIterationCount").Get() - == cfg.rigid_props.solver_position_iteration_count + == cfg.rigid_props[1].solver_position_iteration_count ) - assert prim.GetAttribute("physxRigidBody:sleepThreshold").Get() == pytest.approx(cfg.rigid_props.sleep_threshold) + assert prim.GetAttribute("physxRigidBody:sleepThreshold").Get() == pytest.approx(cfg.rigid_props[1].sleep_threshold) # -- mass assert prim.GetAttribute("physics:mass").Get() == cfg.mass_props.mass # -- collision shape diff --git a/source/isaaclab/test/sim/test_spawn_shapes.py b/source/isaaclab/test/sim/test_spawn_shapes.py index 532b29c22849..cc0a24f7d151 100644 --- a/source/isaaclab/test/sim/test_spawn_shapes.py +++ b/source/isaaclab/test/sim/test_spawn_shapes.py @@ -13,6 +13,7 @@ """Rest everything follows.""" import pytest +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -133,9 +134,10 @@ def test_spawn_cone_with_rigid_props(sim): cfg = sim_utils.ConeCfg( radius=1.0, height=2.0, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - rigid_body_enabled=True, solver_position_iteration_count=8, sleep_threshold=0.1 - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(rigid_body_enabled=True), + PhysxRigidBodyCfg(solver_position_iteration_count=8, sleep_threshold=0.1), + ], ) prim = cfg.func("/World/Cone", cfg) @@ -144,12 +146,12 @@ def test_spawn_cone_with_rigid_props(sim): assert sim.stage.GetPrimAtPath("/World/Cone").IsValid() # Check properties prim = sim.stage.GetPrimAtPath("/World/Cone") - assert prim.GetAttribute("physics:rigidBodyEnabled").Get() == cfg.rigid_props.rigid_body_enabled + assert prim.GetAttribute("physics:rigidBodyEnabled").Get() == cfg.rigid_props[0].rigid_body_enabled assert ( prim.GetAttribute("physxRigidBody:solverPositionIterationCount").Get() - == cfg.rigid_props.solver_position_iteration_count + == cfg.rigid_props[1].solver_position_iteration_count ) - assert prim.GetAttribute("physxRigidBody:sleepThreshold").Get() == pytest.approx(cfg.rigid_props.sleep_threshold) + assert prim.GetAttribute("physxRigidBody:sleepThreshold").Get() == pytest.approx(cfg.rigid_props[1].sleep_threshold) def test_spawn_cone_with_rigid_and_mass_props(sim): @@ -157,9 +159,10 @@ def test_spawn_cone_with_rigid_and_mass_props(sim): cfg = sim_utils.ConeCfg( radius=1.0, height=2.0, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - rigid_body_enabled=True, solver_position_iteration_count=8, sleep_threshold=0.1 - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(rigid_body_enabled=True), + PhysxRigidBodyCfg(solver_position_iteration_count=8, sleep_threshold=0.1), + ], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), ) prim = cfg.func("/World/Cone", cfg) @@ -188,9 +191,10 @@ def test_spawn_cone_with_rigid_and_density_props(sim): cfg = sim_utils.ConeCfg( radius=1.0, height=2.0, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - rigid_body_enabled=True, solver_position_iteration_count=8, sleep_threshold=0.1 - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(rigid_body_enabled=True), + PhysxRigidBodyCfg(solver_position_iteration_count=8, sleep_threshold=0.1), + ], mass_props=sim_utils.MassPropertiesCfg(density=10.0), collision_props=sim_utils.CollisionPropertiesCfg(collision_enabled=False), ) @@ -215,7 +219,7 @@ def test_spawn_cone_with_all_props(sim): radius=1.0, height=2.0, mass_props=sim_utils.MassPropertiesCfg(mass=5.0), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.75, 0.5)), physics_material=sim_utils.RigidBodyMaterialCfg(), @@ -275,7 +279,7 @@ def test_spawn_cone_clone_with_all_props_global_material(sim): radius=1.0, height=2.0, mass_props=sim_utils.MassPropertiesCfg(mass=5.0), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.75, 0.5)), physics_material=sim_utils.RigidBodyMaterialCfg(), diff --git a/source/isaaclab/test/sim/test_spawn_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index 69ad8b105723..6afec082383b 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -14,6 +14,7 @@ import pytest +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -60,9 +61,7 @@ def test_spawn_multiple_shapes_with_regex_prefix(sim): visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0), metallic=0.2), ), ], - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=4, solver_velocity_iteration_count=0 - ), + rigid_props=[PhysxRigidBodyCfg(solver_position_iteration_count=4, solver_velocity_iteration_count=0)], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ) @@ -101,9 +100,7 @@ def test_spawn_multiple_shapes_with_global_settings(sim): visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0), metallic=0.2), ), ], - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=4, solver_velocity_iteration_count=0 - ), + rigid_props=[PhysxRigidBodyCfg(solver_position_iteration_count=4, solver_velocity_iteration_count=0)], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ) @@ -130,21 +127,21 @@ def test_spawn_multiple_shapes_with_individual_settings(sim): radius=0.3, height=0.6, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=mass_variations[0]), collision_props=sim_utils.CollisionPropertiesCfg(), ), sim_utils.CuboidCfg( size=(0.3, 0.3, 0.3), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0), metallic=0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=mass_variations[1]), collision_props=sim_utils.CollisionPropertiesCfg(), ), sim_utils.SphereCfg( radius=0.3, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0), metallic=0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=mass_variations[2]), collision_props=sim_utils.CollisionPropertiesCfg(), ), @@ -211,15 +208,17 @@ def test_spawn_multiple_files_with_global_settings(sim): f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd", f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-D/anymal_d.usd", ], - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), diff --git a/source/isaaclab/test/terrains/check_terrain_importer.py b/source/isaaclab/test/terrains/check_terrain_importer.py index a8229023f90c..1c3fdbd60148 100644 --- a/source/isaaclab/test/terrains/check_terrain_importer.py +++ b/source/isaaclab/test/terrains/check_terrain_importer.py @@ -126,7 +126,7 @@ def main(): # Spawn a geom sphere with rigid body properties sphere_cfg = sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=visual_material_cfg, @@ -137,7 +137,7 @@ def main(): # Spawn a mesh sphere with rigid body properties mesh_sphere_cfg = sim_utils.MeshSphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(collision_enabled=True), visual_material=visual_material_cfg, diff --git a/source/isaaclab/test/terrains/test_terrain_importer.py b/source/isaaclab/test/terrains/test_terrain_importer.py index 5234df4cae51..2aa3e4ca69e0 100644 --- a/source/isaaclab/test/terrains/test_terrain_importer.py +++ b/source/isaaclab/test/terrains/test_terrain_importer.py @@ -281,7 +281,7 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: # Spawn a geom sphere with rigid body properties sphere_cfg = sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=visual_material_cfg, @@ -292,7 +292,7 @@ def _populate_scene(sim: SimulationContext, num_balls: int = 2048, geom_sphere: # Spawn a mesh sphere with rigid body properties mesh_sphere_cfg = sim_utils.MeshSphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(collision_enabled=True), visual_material=visual_material_cfg, diff --git a/source/isaaclab/test/utils/test_wrench_composer_integration.py b/source/isaaclab/test/utils/test_wrench_composer_integration.py index acb1682bde02..647fdfc50ac7 100644 --- a/source/isaaclab/test/utils/test_wrench_composer_integration.py +++ b/source/isaaclab/test/utils/test_wrench_composer_integration.py @@ -39,7 +39,7 @@ def generate_cubes_scene( spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ) cube_object_cfg = RigidObjectCfg( diff --git a/source/isaaclab/test/utils/test_wrench_composer_vs_physx.py b/source/isaaclab/test/utils/test_wrench_composer_vs_physx.py index ca8f22be437c..74c3bcb4327c 100644 --- a/source/isaaclab/test/utils/test_wrench_composer_vs_physx.py +++ b/source/isaaclab/test/utils/test_wrench_composer_vs_physx.py @@ -67,7 +67,7 @@ def generate_dual_cube_scene( spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ) cube_composer_cfg = RigidObjectCfg( diff --git a/source/isaaclab_assets/changelog.d/vidurv-schema-fragments.rst b/source/isaaclab_assets/changelog.d/vidurv-schema-fragments.rst new file mode 100644 index 000000000000..8702f2b5bbcb --- /dev/null +++ b/source/isaaclab_assets/changelog.d/vidurv-schema-fragments.rst @@ -0,0 +1,7 @@ +Changed +^^^^^^^ + +* Migrated the robot configurations off the deprecated ``RigidBodyPropertiesCfg`` to the new + rigid-body fragment list (``rigid_props=[UsdPhysicsRigidBodyCfg(...), PhysxRigidBodyCfg(...)]``). + The ``rigid_props`` attribute on the pre-defined robot cfgs is now a list of fragments rather + than a single cfg object. diff --git a/source/isaaclab_assets/isaaclab_assets/robots/agibot.py b/source/isaaclab_assets/isaaclab_assets/robots/agibot.py index c5483721d2e0..bbbba806ef0c 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/agibot.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/agibot.py @@ -12,6 +12,8 @@ """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -25,10 +27,12 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Agibot/A2D/A2D_physics.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=8, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/allegro.py b/source/isaaclab_assets/isaaclab_assets/robots/allegro.py index 10d96e277770..f75a5a2600e5 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/allegro.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/allegro.py @@ -17,6 +17,8 @@ import math +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -30,16 +32,18 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/WonikRobotics/AllegroHand/allegro_hand_instanceable.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - retain_accelerations=False, - enable_gyroscopic_forces=False, - angular_damping=0.01, - max_linear_velocity=1000.0, - max_angular_velocity=64 / math.pi * 180.0, - max_depenetration_velocity=1000.0, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + retain_accelerations=False, + enable_gyroscopic_forces=False, + angular_damping=0.01, + max_linear_velocity=1000.0, + max_angular_velocity=64 / math.pi * 180.0, + max_depenetration_velocity=1000.0, + max_contact_impulse=1e32, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=8, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/ant.py b/source/isaaclab_assets/isaaclab_assets/robots/ant.py index 97695e76edd9..e6598e23de0d 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/ant.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/ant.py @@ -7,6 +7,8 @@ from __future__ import annotations +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -20,11 +22,13 @@ prim_path="{ENV_REGEX_NS}/Robot", spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/IsaacSim/Ant/ant_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=10.0, - enable_gyroscopic_forces=True, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=10.0, + enable_gyroscopic_forces=True, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/anymal.py b/source/isaaclab_assets/isaaclab_assets/robots/anymal.py index 18beaccc5d92..be3c657654b2 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/anymal.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/anymal.py @@ -19,6 +19,8 @@ """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ActuatorNetLSTMCfg, DCMotorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -60,15 +62,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-B/anymal_b.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), @@ -95,15 +99,17 @@ usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-C/anymal_c.usd", # usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/ANYbotics/anymal_instanceable.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), @@ -130,15 +136,17 @@ usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-D/anymal_d.usd", # usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/ANYbotics/ANYmal-D/anymal_d_minimal.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), diff --git a/source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py b/source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py index 4f81f8a0645c..3aada50dfbcc 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py @@ -10,6 +10,8 @@ * :obj:`ARL_ROBOT_1_CFG`: The ARL_Robot_1 """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR @@ -37,15 +39,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/NTNU/ARL-Robot-1/arl_robot_1.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), diff --git a/source/isaaclab_assets/isaaclab_assets/robots/cart_double_pendulum.py b/source/isaaclab_assets/isaaclab_assets/robots/cart_double_pendulum.py index 22028f39baf2..200a56d714b8 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/cart_double_pendulum.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/cart_double_pendulum.py @@ -5,6 +5,8 @@ """Configuration for a simple inverted Double Pendulum on a Cart robot.""" +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -17,13 +19,15 @@ CART_DOUBLE_PENDULUM_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Classic/CartDoublePendulum/cart_double_pendulum.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - rigid_body_enabled=True, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=100.0, - enable_gyroscopic_forces=True, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(rigid_body_enabled=True), + PhysxRigidBodyCfg( + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=100.0, + enable_gyroscopic_forces=True, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/cartpole.py b/source/isaaclab_assets/isaaclab_assets/robots/cartpole.py index 1e236eda6b93..13393d398b7a 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/cartpole.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/cartpole.py @@ -5,6 +5,8 @@ """Configuration for a simple Cartpole robot.""" +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -17,13 +19,15 @@ CARTPOLE_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Classic/Cartpole/cartpole.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - rigid_body_enabled=True, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=100.0, - enable_gyroscopic_forces=True, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(rigid_body_enabled=True), + PhysxRigidBodyCfg( + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=100.0, + enable_gyroscopic_forces=True, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/cassie.py b/source/isaaclab_assets/isaaclab_assets/robots/cassie.py index faaefc414164..056fa5a996a6 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/cassie.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/cassie.py @@ -12,6 +12,8 @@ Reference: https://github.com/UMich-BipedLab/Cassie_Model/blob/master/urdf/cassie.urdf """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -25,15 +27,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Agility/Cassie/cassie.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), diff --git a/source/isaaclab_assets/isaaclab_assets/robots/flexiv.py b/source/isaaclab_assets/isaaclab_assets/robots/flexiv.py index 18adf4312022..31653e60ef77 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/flexiv.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/flexiv.py @@ -14,6 +14,8 @@ Reference: https://www.flexiv.com/product/rizon """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -26,10 +28,12 @@ FLEXIV_RIZON4S_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Flexiv/Rizon4s/rizon4s.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=16, @@ -86,10 +90,12 @@ FLEXIV_RIZON4S_GRAV_GRIPPER_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Flexiv/Rizon4s/rizon4s_with_grav.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=16, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/fourier.py b/source/isaaclab_assets/isaaclab_assets/robots/fourier.py index 58e143d11885..43a3b6f8c111 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/fourier.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/fourier.py @@ -15,6 +15,7 @@ """ import torch +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -32,15 +33,17 @@ f"{ISAAC_NUCLEUS_DIR}/Robots/FourierIntelligence/GR-1/GR1T2_fourier_hand_6dof/GR1T2_fourier_hand_6dof.usd" ), activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=8, solver_velocity_iteration_count=4 ), diff --git a/source/isaaclab_assets/isaaclab_assets/robots/franka.py b/source/isaaclab_assets/isaaclab_assets/robots/franka.py index f03d21760f90..fb84c36ef8d8 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/franka.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/franka.py @@ -14,6 +14,8 @@ Reference: https://github.com/frankaemika/franka_ros """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -27,10 +29,12 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/FrankaEmika/panda_instanceable.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=8, solver_velocity_iteration_count=0 ), @@ -76,7 +80,7 @@ FRANKA_PANDA_HIGH_PD_CFG = FRANKA_PANDA_CFG.copy() -FRANKA_PANDA_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True +next(f for f in FRANKA_PANDA_HIGH_PD_CFG.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True FRANKA_PANDA_HIGH_PD_CFG.actuators["panda_shoulder"].stiffness = 400.0 FRANKA_PANDA_HIGH_PD_CFG.actuators["panda_shoulder"].damping = 80.0 FRANKA_PANDA_HIGH_PD_CFG.actuators["panda_forearm"].stiffness = 400.0 @@ -90,7 +94,7 @@ FRANKA_ROBOTIQ_GRIPPER_CFG = FRANKA_PANDA_CFG.copy() FRANKA_ROBOTIQ_GRIPPER_CFG.spawn.usd_path = f"{ISAAC_NUCLEUS_DIR}/Robots/FrankaRobotics/FrankaPanda/franka.usd" FRANKA_ROBOTIQ_GRIPPER_CFG.spawn.variants = {"Gripper": "Robotiq_2F_85"} -FRANKA_ROBOTIQ_GRIPPER_CFG.spawn.rigid_props.disable_gravity = True +next(f for f in FRANKA_ROBOTIQ_GRIPPER_CFG.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True FRANKA_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos = { "panda_joint1": 0.0, "panda_joint2": -0.569, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/galbot.py b/source/isaaclab_assets/isaaclab_assets/robots/galbot.py index 9827c7c8d31e..cdb6c9f2a7ff 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/galbot.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/galbot.py @@ -12,6 +12,8 @@ """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -26,10 +28,12 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Galbot/galbot_one_charlie/galbot_one_charlie.usd", variants={"Physics": "PhysX"}, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), activate_contact_sensors=True, ), diff --git a/source/isaaclab_assets/isaaclab_assets/robots/humanoid.py b/source/isaaclab_assets/isaaclab_assets/robots/humanoid.py index 3ac06535d34e..d4860b06cbe7 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/humanoid.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/humanoid.py @@ -7,6 +7,8 @@ from __future__ import annotations +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -20,11 +22,13 @@ prim_path="{ENV_REGEX_NS}/Robot", spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/IsaacSim/Humanoid/humanoid_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=None, - max_depenetration_velocity=10.0, - enable_gyroscopic_forces=True, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=None, + max_depenetration_velocity=10.0, + enable_gyroscopic_forces=True, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/humanoid_28.py b/source/isaaclab_assets/isaaclab_assets/robots/humanoid_28.py index 84f44339a537..797a25b7d557 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/humanoid_28.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/humanoid_28.py @@ -7,6 +7,8 @@ from __future__ import annotations +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -20,11 +22,13 @@ prim_path="{ENV_REGEX_NS}/Robot", spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Classic/Humanoid28/humanoid_28.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=None, - max_depenetration_velocity=10.0, - enable_gyroscopic_forces=True, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=None, + max_depenetration_velocity=10.0, + enable_gyroscopic_forces=True, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/kinova.py b/source/isaaclab_assets/isaaclab_assets/robots/kinova.py index 3bef3896232e..7a184dcb5ef0 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/kinova.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/kinova.py @@ -14,6 +14,8 @@ Reference: https://github.com/Kinovarobotics/kinova-ros """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -26,10 +28,12 @@ KINOVA_JACO2_N7S300_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Kinova/Jaco2/J2N7S300/j2n7s300_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=8, solver_velocity_iteration_count=0 ), @@ -79,10 +83,12 @@ KINOVA_JACO2_N6S300_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Kinova/Jaco2/J2N6S300/j2n6s300_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=8, solver_velocity_iteration_count=0 ), @@ -131,10 +137,12 @@ KINOVA_GEN3_N7_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Kinova/Gen3/gen3n7_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=8, solver_velocity_iteration_count=0 ), diff --git a/source/isaaclab_assets/isaaclab_assets/robots/kuka_allegro.py b/source/isaaclab_assets/isaaclab_assets/robots/kuka_allegro.py index f521f45bff57..6a1e55976e9c 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/kuka_allegro.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/kuka_allegro.py @@ -16,6 +16,8 @@ """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -29,15 +31,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/KukaAllegro/kuka.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - retain_accelerations=True, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1000.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + retain_accelerations=True, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1000.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=32, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index 02743c5da915..c9079ecd81b4 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -26,6 +26,8 @@ https://files.seeedstudio.com/products/Damiao/DM-J4310-en.pdf """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -34,10 +36,12 @@ OPENARM_BI_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/OpenArm/openarm_bimanual/openarm_bimanual.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=8, @@ -102,10 +106,12 @@ OPENARM_UNI_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/OpenArm/openarm_unimanual/openarm_unimanual.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=8, @@ -153,7 +159,7 @@ """Configuration of OpenArm Unimanual robot.""" OPENARM_BI_HIGH_PD_CFG = OPENARM_BI_CFG.copy() -OPENARM_BI_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True +next(f for f in OPENARM_BI_HIGH_PD_CFG.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True OPENARM_BI_HIGH_PD_CFG.actuators["openarm_arm"].stiffness = 400.0 OPENARM_BI_HIGH_PD_CFG.actuators["openarm_arm"].damping = 80.0 OPENARM_BI_HIGH_PD_CFG.actuators["openarm_gripper"].stiffness = 2e3 @@ -164,7 +170,7 @@ """ OPENARM_UNI_HIGH_PD_CFG = OPENARM_UNI_CFG.copy() -OPENARM_UNI_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True +next(f for f in OPENARM_UNI_HIGH_PD_CFG.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True OPENARM_UNI_HIGH_PD_CFG.actuators["openarm_arm"].stiffness = 400.0 OPENARM_UNI_HIGH_PD_CFG.actuators["openarm_arm"].damping = 80.0 """Configuration of OpenArm Unimanual robot with stiffer PD control. diff --git a/source/isaaclab_assets/isaaclab_assets/robots/pick_and_place.py b/source/isaaclab_assets/isaaclab_assets/robots/pick_and_place.py index 988e042fcf65..dba7404357bc 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/pick_and_place.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/pick_and_place.py @@ -7,6 +7,8 @@ from __future__ import annotations +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -20,11 +22,13 @@ prim_path="{ENV_REGEX_NS}/Robot", spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Tests/PickAndPlace/pick_and_place_robot.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=10.0, - enable_gyroscopic_forces=True, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=10.0, + enable_gyroscopic_forces=True, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/quadcopter.py b/source/isaaclab_assets/isaaclab_assets/robots/quadcopter.py index f404a90e3f14..93b7fee42800 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/quadcopter.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/quadcopter.py @@ -7,6 +7,8 @@ from __future__ import annotations +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -20,11 +22,13 @@ prim_path="{ENV_REGEX_NS}/Robot", spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Bitcraze/Crazyflie/cf2x.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=10.0, - enable_gyroscopic_forces=True, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=10.0, + enable_gyroscopic_forces=True, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/sawyer.py b/source/isaaclab_assets/isaaclab_assets/robots/sawyer.py index 179df09e7d81..4aeb90e2b23b 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/sawyer.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/sawyer.py @@ -12,6 +12,8 @@ Reference: https://github.com/RethinkRobotics/sawyer_robot """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -24,10 +26,12 @@ SAWYER_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/RethinkRobotics/Sawyer/sawyer_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=8, solver_velocity_iteration_count=0 ), diff --git a/source/isaaclab_assets/isaaclab_assets/robots/shadow_hand.py b/source/isaaclab_assets/isaaclab_assets/robots/shadow_hand.py index 696b8f9b5a4d..7180d712a8b5 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/shadow_hand.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/shadow_hand.py @@ -15,6 +15,8 @@ """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -28,11 +30,13 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/ShadowRobot/ShadowHand/shadow_hand_instanceable.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - retain_accelerations=True, - max_depenetration_velocity=1000.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + retain_accelerations=True, + max_depenetration_velocity=1000.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=8, diff --git a/source/isaaclab_assets/isaaclab_assets/robots/spot.py b/source/isaaclab_assets/isaaclab_assets/robots/spot.py index 3bc98b8b2da3..703a39ecbcb3 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/spot.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/spot.py @@ -11,6 +11,8 @@ * :obj:`SPOT_CFG`: The Spot robot with delay PD and remote PD actuators. """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import DelayedPDActuatorCfg, RemotizedPDActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -135,15 +137,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/BostonDynamics/spot/spot.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), diff --git a/source/isaaclab_assets/isaaclab_assets/robots/unitree.py b/source/isaaclab_assets/isaaclab_assets/robots/unitree.py index 8e4f692ca6df..6eddfbf505bd 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/unitree.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/unitree.py @@ -20,6 +20,8 @@ Reference: https://github.com/unitreerobotics/unitree_ros """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ActuatorNetMLPCfg, DCMotorCfg, IdealPDActuatorCfg, ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -60,15 +62,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/A1/a1.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), @@ -107,15 +111,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/Go1/go1.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), @@ -143,15 +149,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/Go2/go2.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), @@ -187,15 +195,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/H1/h1.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=4 ), @@ -275,15 +285,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/G1/g1.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=8, solver_velocity_iteration_count=4 ), @@ -391,15 +403,17 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Unitree/G1/g1.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, fix_root_link=False, # Configurable - can be set to True for fixed base @@ -568,7 +582,7 @@ G1_INSPIRE_FTP_CFG = G1_29DOF_CFG.copy() G1_INSPIRE_FTP_CFG.spawn.usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/G1/g1_29dof_inspire_hand.usd" G1_INSPIRE_FTP_CFG.spawn.activate_contact_sensors = True -G1_INSPIRE_FTP_CFG.spawn.rigid_props.disable_gravity = True +next(f for f in G1_INSPIRE_FTP_CFG.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True G1_INSPIRE_FTP_CFG.spawn.articulation_props.fix_root_link = True G1_INSPIRE_FTP_CFG.init_state = ArticulationCfg.InitialStateCfg( pos=(0.0, 0.0, 1.0), @@ -617,17 +631,19 @@ spawn=sim_utils.UsdFileCfg( usd_path=f"{HEALTHCARE_S3}/Robots/UnitreeG1/g1_29dof_with_dex3_base_fix/g1_29dof_with_dex3_base_fix.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - retain_accelerations=False, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=1000.0, - max_depenetration_velocity=1.0, - solver_position_iteration_count=4, - solver_velocity_iteration_count=0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + retain_accelerations=False, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=1000.0, + max_depenetration_velocity=1.0, + solver_position_iteration_count=4, + solver_velocity_iteration_count=0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=0 ), diff --git a/source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py b/source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py index 9047fc14e764..885137326159 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/universal_robots.py @@ -15,6 +15,8 @@ Reference: https://github.com/ros-industrial/universal_robot """ +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg @@ -27,10 +29,12 @@ UR10_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/UniversalRobots/UR10/ur10_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], activate_contact_sensors=False, ), init_state=ArticulationCfg.InitialStateCfg( @@ -56,10 +60,12 @@ UR10e_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/UniversalRobots/ur10e/ur10e.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=16, solver_velocity_iteration_count=1 ), @@ -108,7 +114,7 @@ UR10_LONG_SUCTION_CFG = UR10_CFG.copy() UR10_LONG_SUCTION_CFG.spawn.usd_path = f"{ISAAC_NUCLEUS_DIR}/Robots/UniversalRobots/ur10/ur10.usd" UR10_LONG_SUCTION_CFG.spawn.variants = {"Gripper": "Long_Suction"} -UR10_LONG_SUCTION_CFG.spawn.rigid_props.disable_gravity = True +next(f for f in UR10_LONG_SUCTION_CFG.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True UR10_LONG_SUCTION_CFG.init_state.joint_pos = { "shoulder_pan_joint": 0.0, "shoulder_lift_joint": -1.5707, @@ -128,7 +134,7 @@ UR10e_ROBOTIQ_GRIPPER_CFG = UR10e_CFG.copy() """Configuration of UR10e arm with Robotiq_2f_140 gripper.""" UR10e_ROBOTIQ_GRIPPER_CFG.spawn.variants = {"Gripper": "Robotiq_2f_140"} -UR10e_ROBOTIQ_GRIPPER_CFG.spawn.rigid_props.disable_gravity = True +next(f for f in UR10e_ROBOTIQ_GRIPPER_CFG.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True UR10e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos["finger_joint"] = 0.0 UR10e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos[".*_inner_finger_joint"] = 0.0 UR10e_ROBOTIQ_GRIPPER_CFG.init_state.joint_pos[".*_inner_finger_pad_joint"] = 0.0 @@ -168,7 +174,7 @@ UR10e_ROBOTIQ_2F_85_CFG = UR10e_CFG.copy() """Configuration of UR-10E arm with Robotiq_2f_140 gripper.""" UR10e_ROBOTIQ_2F_85_CFG.spawn.variants = {"Gripper": "Robotiq_2f_85"} -UR10e_ROBOTIQ_2F_85_CFG.spawn.rigid_props.disable_gravity = True +next(f for f in UR10e_ROBOTIQ_2F_85_CFG.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True UR10e_ROBOTIQ_2F_85_CFG.init_state.joint_pos["finger_joint"] = 0.0 UR10e_ROBOTIQ_2F_85_CFG.init_state.joint_pos[".*_inner_finger_joint"] = 0.0 UR10e_ROBOTIQ_2F_85_CFG.init_state.joint_pos[".*_inner_finger_knuckle_joint"] = 0.0 diff --git a/source/isaaclab_contrib/changelog.d/vidurv-schema-fragments.skip b/source/isaaclab_contrib/changelog.d/vidurv-schema-fragments.skip new file mode 100644 index 000000000000..92616399b9bd --- /dev/null +++ b/source/isaaclab_contrib/changelog.d/vidurv-schema-fragments.skip @@ -0,0 +1 @@ +Test-only: migrated a test off the deprecated RigidBodyPropertiesCfg to the fragment-list API. diff --git a/source/isaaclab_contrib/test/deformable/test_rigid_deformable_coupling.py b/source/isaaclab_contrib/test/deformable/test_rigid_deformable_coupling.py index 4b00c0d2e371..3de5287933d8 100644 --- a/source/isaaclab_contrib/test/deformable/test_rigid_deformable_coupling.py +++ b/source/isaaclab_contrib/test/deformable/test_rigid_deformable_coupling.py @@ -190,7 +190,7 @@ def generate_lateral_rigid_and_deformable_cubes( prim_path="/World/env_.*/rigid_cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.05), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.2, 0.2, 0.8)), diff --git a/source/isaaclab_mimic/changelog.d/vidurv-schema-fragments.rst b/source/isaaclab_mimic/changelog.d/vidurv-schema-fragments.rst new file mode 100644 index 000000000000..8c7d51ab79dc --- /dev/null +++ b/source/isaaclab_mimic/changelog.d/vidurv-schema-fragments.rst @@ -0,0 +1,5 @@ +Changed +^^^^^^^ + +* Migrated SDG env configuration off the deprecated ``RigidBodyPropertiesCfg`` to the new + rigid-body fragment list. diff --git a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/g1_locomanipulation_sdg_env.py b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/g1_locomanipulation_sdg_env.py index 27cfd3156c63..5049aaea407b 100644 --- a/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/g1_locomanipulation_sdg_env.py +++ b/source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/g1_locomanipulation_sdg_env.py @@ -48,7 +48,7 @@ class G1LocomanipulationSDGSceneCfg(LocomanipulationG1SceneCfg): ), spawn=UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/PackingTable/packing_table.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], ), ) @@ -85,7 +85,7 @@ def add_forklifts(self, num_forklifts: int): init_state=AssetBaseCfg.InitialStateCfg(pos=[0.0, 0.0, 0.0], rot=[0.0, 0.0, 0.0, 1.0]), spawn=UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Forklift/forklift.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], ), ) setattr(self, f"forklift_{i}", forklift) diff --git a/source/isaaclab_mimic/test/test_curobo_planner_franka.py b/source/isaaclab_mimic/test/test_curobo_planner_franka.py index e4c939f4a824..ed4d7b5112c7 100644 --- a/source/isaaclab_mimic/test/test_curobo_planner_franka.py +++ b/source/isaaclab_mimic/test/test_curobo_planner_franka.py @@ -27,11 +27,13 @@ from isaaclab.assets import Articulation, RigidObjectCfg from isaaclab.envs.manager_based_env import ManagerBasedEnv from isaaclab.markers import FRAME_MARKER_CFG, VisualizationMarkers -from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg +from isaaclab.sim.schemas.schemas_cfg import UsdPhysicsRigidBodyCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg ISAAC_NUCLEUS_DIR: str = getattr(_al_assets, "ISAAC_NUCLEUS_DIR", "/Isaac") +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + from isaaclab_mimic.motion_planners.curobo.curobo_planner import CuroboPlanner from isaaclab_mimic.motion_planners.curobo.curobo_planner_cfg import CuroboPlannerCfg @@ -58,7 +60,10 @@ def curobo_test_env() -> Generator[dict[str, Any], None, None]: env_cfg.scene.num_envs = 1 # Add a static wall for the robot to avoid - wall_props = RigidBodyPropertiesCfg(kinematic_enabled=True, disable_gravity=True) + wall_props = [ + UsdPhysicsRigidBodyCfg(kinematic_enabled=True), + PhysxRigidBodyCfg(disable_gravity=True), + ] wall_cfg = RigidObjectCfg( prim_path="/World/envs/env_0/moving_wall", spawn=UsdFileCfg( diff --git a/source/isaaclab_newton/test/assets/test_rigid_object.py b/source/isaaclab_newton/test/assets/test_rigid_object.py index 8811de5b9db7..066fbfa789f9 100644 --- a/source/isaaclab_newton/test/assets/test_rigid_object.py +++ b/source/isaaclab_newton/test/assets/test_rigid_object.py @@ -98,12 +98,12 @@ def generate_cubes_scene( elif api == "rigid_body": spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ) elif api == "articulation_root": spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Tests/RigidObject/Cube/dex_cube_instanceable_with_articulation_root.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ) else: raise ValueError(f"Unknown api: {api}") diff --git a/source/isaaclab_newton/test/assets/test_rigid_object_collection.py b/source/isaaclab_newton/test/assets/test_rigid_object_collection.py index 18928bedb5d8..1b349635e91a 100644 --- a/source/isaaclab_newton/test/assets/test_rigid_object_collection.py +++ b/source/isaaclab_newton/test/assets/test_rigid_object_collection.py @@ -92,7 +92,7 @@ def generate_cubes_scene( if has_api: spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ) else: # since no rigid body properties defined, this is just a static collider diff --git a/source/isaaclab_newton/test/physics/physics_test_utils.py b/source/isaaclab_newton/test/physics/physics_test_utils.py index 65177a9c8a93..751921ced68f 100644 --- a/source/isaaclab_newton/test/physics/physics_test_utils.py +++ b/source/isaaclab_newton/test/physics/physics_test_utils.py @@ -17,6 +17,7 @@ import pytest from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.assets import RigidObjectCfg @@ -135,11 +136,13 @@ def create_shape_cfg( activate_contact_sensors: bool = True, ) -> RigidObjectCfg: """Create RigidObjectCfg for a shape type.""" - rigid_props = sim_utils.RigidBodyPropertiesCfg( - disable_gravity=disable_gravity, - linear_damping=0.0, - angular_damping=0.0, - ) + rigid_props = [ + PhysxRigidBodyCfg( + disable_gravity=disable_gravity, + linear_damping=0.0, + angular_damping=0.0, + ) + ] collision_props = sim_utils.CollisionPropertiesCfg(collision_enabled=True) mass_props = sim_utils.MassPropertiesCfg(mass=1.0) diff --git a/source/isaaclab_newton/test/sensors/test_contact_sensor.py b/source/isaaclab_newton/test/sensors/test_contact_sensor.py index 2d92e3274a7e..1e91b692460a 100644 --- a/source/isaaclab_newton/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_newton/test/sensors/test_contact_sensor.py @@ -27,6 +27,7 @@ import pytest import torch from isaaclab_newton.sensors.contact_sensor import ContactSensorCfg as NewtonContactSensorCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg from physics.physics_test_utils import ( COLLISION_PIPELINES, STABLE_SHAPES, @@ -325,7 +326,7 @@ def test_resting_object_contact_force(device: str, use_mujoco_contacts: bool): sim._app_control_on_stop_handle = None scene_cfg = ContactSensorTestSceneCfg(num_envs=num_envs, env_spacing=5.0, lazy_sensor_update=False) - rigid_props = sim_utils.RigidBodyPropertiesCfg(disable_gravity=False, linear_damping=0.5, angular_damping=0.5) + rigid_props = [PhysxRigidBodyCfg(disable_gravity=False, linear_damping=0.5, angular_damping=0.5)] scene_cfg.object_a = RigidObjectCfg( prim_path="{ENV_REGEX_NS}/BoxA", @@ -522,7 +523,7 @@ def test_filter_enables_force_matrix(device: str, use_mujoco_contacts: bool): scene_cfg = ContactSensorTestSceneCfg(num_envs=num_envs, env_spacing=5.0, lazy_sensor_update=False) - rigid_props_a = sim_utils.RigidBodyPropertiesCfg(disable_gravity=False, linear_damping=0.5, angular_damping=0.5) + rigid_props_a = [PhysxRigidBodyCfg(disable_gravity=False, linear_damping=0.5, angular_damping=0.5)] scene_cfg.object_a = RigidObjectCfg( prim_path="{ENV_REGEX_NS}/ObjectA", spawn=sim_utils.CuboidCfg( @@ -535,7 +536,7 @@ def test_filter_enables_force_matrix(device: str, use_mujoco_contacts: bool): init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 0.2)), ) - rigid_props_b = sim_utils.RigidBodyPropertiesCfg(disable_gravity=False, linear_damping=2.0, angular_damping=2.0) + rigid_props_b = [PhysxRigidBodyCfg(disable_gravity=False, linear_damping=2.0, angular_damping=2.0)] scene_cfg.object_b = RigidObjectCfg( prim_path="{ENV_REGEX_NS}/ObjectB", spawn=sim_utils.CuboidCfg( @@ -673,9 +674,7 @@ def test_finger_contact_sensor_isolation(device: str, use_mujoco_contacts: bool, ), ) - drop_rigid_props = sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, linear_damping=0.0, angular_damping=0.0 - ) + drop_rigid_props = [PhysxRigidBodyCfg(disable_gravity=False, linear_damping=0.0, angular_damping=0.0)] drop_collision_props = sim_utils.CollisionPropertiesCfg(collision_enabled=True) drop_mass_props = sim_utils.MassPropertiesCfg(mass=1.0) drop_visual = sim_utils.PreviewSurfaceCfg(diffuse_color=(1.0, 0.0, 0.0)) @@ -788,7 +787,7 @@ def test_finger_contact_sensor_isolation(device: str, use_mujoco_contacts: bool, def _make_two_box_scene_cfg(num_envs: int) -> ContactSensorTestSceneCfg: """Scene with two distinct Cuboid bodies (BoxA, BoxB) per env.""" - rigid_props = sim_utils.RigidBodyPropertiesCfg(disable_gravity=True, linear_damping=0.0, angular_damping=0.0) + rigid_props = [PhysxRigidBodyCfg(disable_gravity=True, linear_damping=0.0, angular_damping=0.0)] scene_cfg = ContactSensorTestSceneCfg(num_envs=num_envs, env_spacing=5.0, lazy_sensor_update=False) scene_cfg.object_a = RigidObjectCfg( prim_path="{ENV_REGEX_NS}/BoxA", diff --git a/source/isaaclab_newton/test/sensors/test_frame_transformer.py b/source/isaaclab_newton/test/sensors/test_frame_transformer.py index 484f175f67e6..2b0b1b588af2 100644 --- a/source/isaaclab_newton/test/sensors/test_frame_transformer.py +++ b/source/isaaclab_newton/test/sensors/test_frame_transformer.py @@ -16,6 +16,7 @@ import scipy.spatial.transform as tf import torch from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils @@ -62,7 +63,7 @@ class MySceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(max_depenetration_velocity=1.0), + rigid_props=[PhysxRigidBodyCfg(max_depenetration_velocity=1.0)], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), physics_material=sim_utils.RigidBodyMaterialCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.0, 0.0)), diff --git a/source/isaaclab_newton/test/sensors/test_imu.py b/source/isaaclab_newton/test/sensors/test_imu.py index b875d623061a..a76c2bc7acdb 100644 --- a/source/isaaclab_newton/test/sensors/test_imu.py +++ b/source/isaaclab_newton/test/sensors/test_imu.py @@ -35,7 +35,7 @@ class ImuTestSceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/Cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), physics_material=sim_utils.RigidBodyMaterialCfg(), @@ -183,7 +183,7 @@ class FreefallSceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/Cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), physics_material=sim_utils.RigidBodyMaterialCfg(), diff --git a/source/isaaclab_newton/test/sensors/test_pva.py b/source/isaaclab_newton/test/sensors/test_pva.py index 3fbc42719280..1e71cafe5696 100644 --- a/source/isaaclab_newton/test/sensors/test_pva.py +++ b/source/isaaclab_newton/test/sensors/test_pva.py @@ -35,7 +35,7 @@ class PvaTestSceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/Cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), physics_material=sim_utils.RigidBodyMaterialCfg(), @@ -198,7 +198,7 @@ class FreefallSceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/Cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), physics_material=sim_utils.RigidBodyMaterialCfg(), @@ -282,7 +282,7 @@ class OffsetRotatedSceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/Cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), physics_material=sim_utils.RigidBodyMaterialCfg(), diff --git a/source/isaaclab_newton/test/sim/test_views_xform_prim_newton.py b/source/isaaclab_newton/test/sim/test_views_xform_prim_newton.py index d114a1da2a80..4fd008695d9d 100644 --- a/source/isaaclab_newton/test/sim/test_views_xform_prim_newton.py +++ b/source/isaaclab_newton/test/sim/test_views_xform_prim_newton.py @@ -41,7 +41,7 @@ class _SceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/Cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ), diff --git a/source/isaaclab_ovphysx/test/assets/test_rigid_object.py b/source/isaaclab_ovphysx/test/assets/test_rigid_object.py index 407cf4b41e22..a11a6de7d725 100644 --- a/source/isaaclab_ovphysx/test/assets/test_rigid_object.py +++ b/source/isaaclab_ovphysx/test/assets/test_rigid_object.py @@ -139,12 +139,12 @@ def generate_cubes_scene( elif api == "rigid_body": spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ) elif api == "articulation_root": spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Tests/RigidObject/Cube/dex_cube_instanceable_with_articulation_root.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ) else: raise ValueError(f"Unknown api: {api}") diff --git a/source/isaaclab_ovphysx/test/assets/test_rigid_object_collection.py b/source/isaaclab_ovphysx/test/assets/test_rigid_object_collection.py index 07ec860d6ec6..7fd492c7c2b9 100644 --- a/source/isaaclab_ovphysx/test/assets/test_rigid_object_collection.py +++ b/source/isaaclab_ovphysx/test/assets/test_rigid_object_collection.py @@ -143,7 +143,7 @@ def generate_cubes_scene( if has_api: spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ) else: # since no rigid body properties defined, this is just a static collider diff --git a/source/isaaclab_ovphysx/test/sensors/test_contact_sensor.py b/source/isaaclab_ovphysx/test/sensors/test_contact_sensor.py index 38b3bd9e579d..b5ae759fb883 100644 --- a/source/isaaclab_ovphysx/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_ovphysx/test/sensors/test_contact_sensor.py @@ -53,6 +53,7 @@ from isaaclab_ovphysx.assets import RigidObject # noqa: E402 from isaaclab_ovphysx.physics import OvPhysxCfg # noqa: E402 from isaaclab_ovphysx.sensors import ContactSensor, ContactSensorCfg # noqa: E402 +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg # noqa: E402 import isaaclab.sim as sim_utils # noqa: E402 from isaaclab.assets import RigidObjectCfg # noqa: E402 @@ -180,9 +181,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): prim_path="/World/Objects/Cube", spawn=sim_utils.CuboidCfg( size=(0.5, 0.5, 0.5), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), @@ -199,9 +202,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): prim_path="/World/Objects/Sphere", spawn=sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), @@ -220,9 +225,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): radius=0.5, height=0.01, axis="Y", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), @@ -241,9 +248,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): radius=0.25, height=0.5, axis="Z", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), @@ -262,9 +271,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): radius=0.5, height=0.5, axis="Z", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), diff --git a/source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py b/source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py index bebd8aaa460d..f3324f3675c5 100644 --- a/source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py +++ b/source/isaaclab_ovphysx/test/sim/test_views_xform_prim_ovphysx.py @@ -91,7 +91,7 @@ class _OvPhysxFrameViewSceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/Cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ), diff --git a/source/isaaclab_physx/changelog.d/vidurv-schema-fragments.minor.rst b/source/isaaclab_physx/changelog.d/vidurv-schema-fragments.minor.rst index 6bd8bcac8b86..6c4629718bb0 100644 --- a/source/isaaclab_physx/changelog.d/vidurv-schema-fragments.minor.rst +++ b/source/isaaclab_physx/changelog.d/vidurv-schema-fragments.minor.rst @@ -3,6 +3,15 @@ Added * Added :class:`~isaaclab_physx.sim.schemas.PhysxRigidBodyCfg`, the ``physxRigidBody:*`` single-namespace rigid-body fragment (PhysX ``PhysxRigidBodyAPI``). It carries the PhysX - damping / velocity-limit / solver-iteration / sleep fields plus ``disable_gravity``, and - composes with :class:`~isaaclab.sim.schemas.UsdPhysicsRigidBodyCfg` in a ``rigid_props`` - fragment list. + damping / velocity-limit / solver-iteration / sleep fields plus ``disable_gravity``. + +Changed +^^^^^^^ + +* **Breaking:** Changed :class:`~isaaclab_physx.sim.schemas.RigidBodyPropertiesCfg` from a + deprecated cfg class into a deprecated factory that returns the equivalent fragment list + ``[UsdPhysicsRigidBodyCfg(...), PhysxRigidBodyCfg(...)]``. Pass a fragment list to + ``rigid_props`` instead of constructing ``RigidBodyPropertiesCfg``; code that mutated + attributes on the returned object (e.g. ``cfg.spawn.rigid_props.disable_gravity = True``) + must instead set the field on the ``PhysxRigidBodyCfg`` fragment in the list. The factory is + scheduled for removal in 5.0. diff --git a/source/isaaclab_physx/isaaclab_physx/sim/schemas/schemas_cfg.py b/source/isaaclab_physx/isaaclab_physx/sim/schemas/schemas_cfg.py index 18a5de023f90..0013930264b8 100644 --- a/source/isaaclab_physx/isaaclab_physx/sim/schemas/schemas_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/sim/schemas/schemas_cfg.py @@ -16,6 +16,7 @@ MeshCollisionBaseCfg, RigidBodyBaseCfg, RigidBodyFragment, + UsdPhysicsRigidBodyCfg, ) from isaaclab.utils.configclass import configclass @@ -320,27 +321,39 @@ class PhysxRigidBodyCfg(RigidBodyFragment): """ -@configclass -class RigidBodyPropertiesCfg(PhysxRigidBodyPropertiesCfg): - """Deprecated: use :class:`PhysxRigidBodyPropertiesCfg` or :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg`. +# UsdPhysics ``physics:*`` rigid-body fields; everything else routes to the PhysX fragment. +_USD_RIGID_FIELDS = ("rigid_body_enabled", "kinematic_enabled") - .. deprecated:: 4.6.22 - ``RigidBodyPropertiesCfg`` has been split into - :class:`~isaaclab.sim.schemas.RigidBodyBaseCfg` (solver-common) and - :class:`PhysxRigidBodyPropertiesCfg` (PhysX-specific) and relocated to - :mod:`isaaclab_physx.sim.schemas`. This alias preserves backwards compatibility and is - scheduled for removal in 5.0. - """ - def __post_init__(self): - warnings.warn( - "'RigidBodyPropertiesCfg' is deprecated and will be removed in 5.0. Use" - " 'isaaclab_physx.sim.schemas.PhysxRigidBodyPropertiesCfg' for PhysX properties, or" - " 'isaaclab.sim.schemas.RigidBodyBaseCfg' for solver-common properties only.", - DeprecationWarning, - stacklevel=2, - ) - super().__post_init__() +def RigidBodyPropertiesCfg(**kwargs) -> list[RigidBodyFragment]: + """Deprecated factory returning the equivalent rigid-body fragment list. + + .. deprecated:: 4.6.22 + ``RigidBodyPropertiesCfg`` no longer returns a single cfg. Pass a list of fragments + instead, e.g. ``rigid_props=[UsdPhysicsRigidBodyCfg(...), PhysxRigidBodyCfg(...)]``. + This factory forwards the legacy keyword arguments to the matching fragments + (``physics:*`` fields to :class:`~isaaclab.sim.schemas.UsdPhysicsRigidBodyCfg`, the rest to + :class:`PhysxRigidBodyCfg`) and is scheduled for removal in 5.0. + + Args: + **kwargs: Any field accepted by the legacy ``RigidBodyPropertiesCfg`` cfg. + + Returns: + The equivalent fragment list. Always contains a + :class:`~isaaclab.sim.schemas.UsdPhysicsRigidBodyCfg` (so the ``RigidBodyAPI`` anchor is + applied) and, when any PhysX field is set, a :class:`PhysxRigidBodyCfg`. + """ + warnings.warn( + "'RigidBodyPropertiesCfg' is deprecated and will be removed in 5.0. Pass a list of" + " fragments instead, e.g. [UsdPhysicsRigidBodyCfg(...), PhysxRigidBodyCfg(...)].", + DeprecationWarning, + stacklevel=2, + ) + usd = {k: kwargs.pop(k) for k in _USD_RIGID_FIELDS if k in kwargs} + frags: list[RigidBodyFragment] = [UsdPhysicsRigidBodyCfg(**usd)] + if kwargs: # remaining kwargs are physxRigidBody:* fields (incl. disable_gravity) + frags.append(PhysxRigidBodyCfg(**kwargs)) + return frags @configclass diff --git a/source/isaaclab_physx/test/assets/test_articulation.py b/source/isaaclab_physx/test/assets/test_articulation.py index af36a365cb66..79d82dacd8b3 100644 --- a/source/isaaclab_physx/test/assets/test_articulation.py +++ b/source/isaaclab_physx/test/assets/test_articulation.py @@ -23,6 +23,7 @@ import torch import warp as wp from isaaclab_physx.assets import Articulation +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils @@ -225,7 +226,10 @@ def _setup_franka_at_home_pose(sim, *, zero_actuator_pd: bool = False, enable_ri if enable_rigid_body_gravity: cfg = cfg.replace( spawn=cfg.spawn.replace( - rigid_props=cfg.spawn.rigid_props.replace(disable_gravity=False), + rigid_props=[ + f.replace(disable_gravity=False) if isinstance(f, PhysxRigidBodyCfg) else f + for f in cfg.spawn.rigid_props + ], ), ) sim_utils.create_prim("/World/Env_0", "Xform", translation=(0.0, 0.0, 0.0)) @@ -2527,7 +2531,10 @@ def test_get_gravity_compensation_forces_static_equilibrium(sim, num_articulatio # defensive — gravity must be ON for τ_gc to have anything to cancel. cfg = cfg.replace( spawn=cfg.spawn.replace( - rigid_props=cfg.spawn.rigid_props.replace(disable_gravity=False), + rigid_props=[ + f.replace(disable_gravity=False) if isinstance(f, PhysxRigidBodyCfg) else f + for f in cfg.spawn.rigid_props + ], ), ) diff --git a/source/isaaclab_physx/test/assets/test_rigid_object.py b/source/isaaclab_physx/test/assets/test_rigid_object.py index b7f422c4f2f0..bebb62a4dee9 100644 --- a/source/isaaclab_physx/test/assets/test_rigid_object.py +++ b/source/isaaclab_physx/test/assets/test_rigid_object.py @@ -76,12 +76,12 @@ def generate_cubes_scene( elif api == "rigid_body": spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ) elif api == "articulation_root": spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Tests/RigidObject/Cube/dex_cube_instanceable_with_articulation_root.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ) else: raise ValueError(f"Unknown api: {api}") diff --git a/source/isaaclab_physx/test/assets/test_rigid_object_collection.py b/source/isaaclab_physx/test/assets/test_rigid_object_collection.py index f42f6dfcb085..479e437bff2c 100644 --- a/source/isaaclab_physx/test/assets/test_rigid_object_collection.py +++ b/source/isaaclab_physx/test/assets/test_rigid_object_collection.py @@ -70,7 +70,7 @@ def generate_cubes_scene( if has_api: spawn_cfg = sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ) else: # since no rigid body properties defined, this is just a static collider diff --git a/source/isaaclab_physx/test/assets/test_surface_gripper.py b/source/isaaclab_physx/test/assets/test_surface_gripper.py index c075821bb985..8394700152ec 100644 --- a/source/isaaclab_physx/test/assets/test_surface_gripper.py +++ b/source/isaaclab_physx/test/assets/test_surface_gripper.py @@ -65,7 +65,7 @@ def generate_surface_gripper_cfgs( articulation_cfg = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Tests/SurfaceGripper/test_gripper.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=kinematic_enabled), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=kinematic_enabled)], ), init_state=ArticulationCfg.InitialStateCfg( pos=(0.0, 0.0, 0.5), @@ -129,7 +129,7 @@ def generate_grippable_object(sim, num_grippable_objects: int): prim_path="/World/Env_.*/Object", spawn=sim_utils.CuboidCfg( size=(1.0, 1.0, 1.0), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0)), diff --git a/source/isaaclab_physx/test/renderers/test_isaac_rtx_renderer_scene_partitioning.py b/source/isaaclab_physx/test/renderers/test_isaac_rtx_renderer_scene_partitioning.py index c54bf9ee85ef..d9879655a5b1 100644 --- a/source/isaaclab_physx/test/renderers/test_isaac_rtx_renderer_scene_partitioning.py +++ b/source/isaaclab_physx/test/renderers/test_isaac_rtx_renderer_scene_partitioning.py @@ -32,6 +32,7 @@ import pytest import torch import warp as wp +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg @@ -59,7 +60,7 @@ class _Scene(InteractiveSceneCfg): spawn=sim_utils.CuboidCfg( size=(0.25, 0.25, 0.25), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.9, 0.2, 0.2)), - rigid_props=sim_utils.RigidBodyPropertiesCfg(disable_gravity=True), + rigid_props=[PhysxRigidBodyCfg(disable_gravity=True)], collision_props=sim_utils.CollisionPropertiesCfg(), mass_props=sim_utils.MassPropertiesCfg(mass=0.2), ), diff --git a/source/isaaclab_physx/test/sensors/check_pva_sensor.py b/source/isaaclab_physx/test/sensors/check_pva_sensor.py index 41476babf542..aa0b6d13ef42 100644 --- a/source/isaaclab_physx/test/sensors/check_pva_sensor.py +++ b/source/isaaclab_physx/test/sensors/check_pva_sensor.py @@ -89,7 +89,7 @@ def design_scene(sim: SimulationContext, num_envs: int = 2048) -> RigidObject: cfg = RigidObjectCfg( spawn=sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)), diff --git a/source/isaaclab_physx/test/sensors/test_contact_sensor.py b/source/isaaclab_physx/test/sensors/test_contact_sensor.py index f0793c3054c5..1121852b3fd4 100644 --- a/source/isaaclab_physx/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/test_contact_sensor.py @@ -21,6 +21,7 @@ import torch import warp as wp from flaky import flaky +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.app.settings_manager import get_settings_manager @@ -94,9 +95,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): prim_path="/World/Objects/Cube", spawn=sim_utils.CuboidCfg( size=(0.5, 0.5, 0.5), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), @@ -113,9 +116,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): prim_path="/World/Objects/Sphere", spawn=sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), @@ -134,9 +139,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): radius=0.5, height=0.01, axis="Y", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), @@ -155,9 +162,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): radius=0.25, height=0.5, axis="Z", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), @@ -176,9 +185,11 @@ class ContactSensorSceneCfg(InteractiveSceneCfg): radius=0.5, height=0.5, axis="Z", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg( collision_enabled=True, ), diff --git a/source/isaaclab_physx/test/sensors/test_frame_transformer.py b/source/isaaclab_physx/test/sensors/test_frame_transformer.py index f7d9c5db5817..2458b14934f4 100644 --- a/source/isaaclab_physx/test/sensors/test_frame_transformer.py +++ b/source/isaaclab_physx/test/sensors/test_frame_transformer.py @@ -17,6 +17,7 @@ import pytest import scipy.spatial.transform as tf import torch +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils @@ -62,7 +63,7 @@ class MySceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/cube", spawn=sim_utils.CuboidCfg( size=(0.2, 0.2, 0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg(max_depenetration_velocity=1.0), + rigid_props=[PhysxRigidBodyCfg(max_depenetration_velocity=1.0)], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), physics_material=sim_utils.RigidBodyMaterialCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.0, 0.0)), diff --git a/source/isaaclab_physx/test/sensors/test_imu.py b/source/isaaclab_physx/test/sensors/test_imu.py index 422aeeed1f39..0ef058c1c347 100644 --- a/source/isaaclab_physx/test/sensors/test_imu.py +++ b/source/isaaclab_physx/test/sensors/test_imu.py @@ -61,7 +61,7 @@ class MySceneCfg(InteractiveSceneCfg): init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 0.5)), spawn=sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)), @@ -73,7 +73,7 @@ class MySceneCfg(InteractiveSceneCfg): init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, -2.0, 0.5)), spawn=sim_utils.CuboidCfg( size=(0.25, 0.25, 0.25), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)), @@ -495,7 +495,7 @@ class _StaleResetSceneCfg(InteractiveSceneCfg): init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 2.0)), spawn=sim_utils.CuboidCfg( size=(0.25, 0.25, 0.25), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), ), diff --git a/source/isaaclab_physx/test/sensors/test_pva.py b/source/isaaclab_physx/test/sensors/test_pva.py index f0c1982373b6..3a284a36a38b 100644 --- a/source/isaaclab_physx/test/sensors/test_pva.py +++ b/source/isaaclab_physx/test/sensors/test_pva.py @@ -62,7 +62,7 @@ class MySceneCfg(InteractiveSceneCfg): init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 0.5)), spawn=sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)), @@ -74,7 +74,7 @@ class MySceneCfg(InteractiveSceneCfg): init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, -2.0, 0.5)), spawn=sim_utils.CuboidCfg( size=(0.25, 0.25, 0.25), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0)), @@ -765,7 +765,7 @@ class _StaleResetSceneCfg(InteractiveSceneCfg): init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, 0.0, 2.0)), spawn=sim_utils.CuboidCfg( size=(0.25, 0.25, 0.25), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), ), diff --git a/source/isaaclab_physx/test/sim/test_cloner.py b/source/isaaclab_physx/test/sim/test_cloner.py index 882963076bb1..eb68797ae829 100644 --- a/source/isaaclab_physx/test/sim/test_cloner.py +++ b/source/isaaclab_physx/test/sim/test_cloner.py @@ -18,6 +18,7 @@ import torch import warp as wp from isaaclab_physx.cloner import physx_replicate +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.cloner import ( @@ -164,7 +165,7 @@ def test_physx_replicate_isolated_source_loaded_without_replication(sim, device) sim_utils.create_prim("/World/template", "Xform") sphere_cfg = sim_utils.SphereCfg( radius=0.1, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ) @@ -265,9 +266,9 @@ def test_direct_clone_plan_multi_asset(sim): visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0), metallic=0.2), ), ], - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=4, solver_velocity_iteration_count=0 - ), + rigid_props=[ + PhysxRigidBodyCfg(solver_position_iteration_count=4, solver_velocity_iteration_count=0), + ], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ) @@ -369,9 +370,9 @@ def test_colocation_collision_filter_homogeneous(sim): height=0.6, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2), mass_props=sim_utils.MassPropertiesCfg(mass=100.0), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=4, solver_velocity_iteration_count=0 - ), + rigid_props=[ + PhysxRigidBodyCfg(solver_position_iteration_count=4, solver_velocity_iteration_count=0), + ], collision_props=sim_utils.CollisionPropertiesCfg(), ), expected_types=["Cone"], @@ -406,9 +407,9 @@ def test_colocation_collision_filter_heterogeneous(sim): visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 0.0, 1.0), metallic=0.2), ), ], - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=4, solver_velocity_iteration_count=0 - ), + rigid_props=[ + PhysxRigidBodyCfg(solver_position_iteration_count=4, solver_velocity_iteration_count=0), + ], mass_props=sim_utils.MassPropertiesCfg(mass=1.0), collision_props=sim_utils.CollisionPropertiesCfg(), ), @@ -430,7 +431,7 @@ def _run_sphere_velocity_sim(sim, use_physx_replicate: bool, num_steps: int = 10 sphere_cfg = sim_utils.SphereCfg( radius=0.25, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=sim_utils.MassPropertiesCfg(mass=0.5), collision_props=sim_utils.CollisionPropertiesCfg(), ) @@ -595,7 +596,7 @@ def test_disabled_fabric_change_notifies_speedup_regression(): def _body(i: int) -> RigidObjectCfg: return RigidObjectCfg( prim_path=f"/World/envs/env_.*/Body_{i}", - spawn=sim_utils.SphereCfg(radius=0.1, rigid_props=sim_utils.RigidBodyPropertiesCfg()), + spawn=sim_utils.SphereCfg(radius=0.1, rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()]), init_state=RigidObjectCfg.InitialStateCfg(pos=(0.3 * (i % 4), 0.3 * (i // 4), 0.5)), ) diff --git a/source/isaaclab_tasks/changelog.d/vidurv-schema-fragments.rst b/source/isaaclab_tasks/changelog.d/vidurv-schema-fragments.rst new file mode 100644 index 000000000000..09dd44818616 --- /dev/null +++ b/source/isaaclab_tasks/changelog.d/vidurv-schema-fragments.rst @@ -0,0 +1,5 @@ +Changed +^^^^^^^ + +* Migrated task configurations off the deprecated ``RigidBodyPropertiesCfg`` to the new + rigid-body fragment list (``rigid_props=[UsdPhysicsRigidBodyCfg(...), PhysxRigidBodyCfg(...)]``). diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/assemble_trocar/g129_dex3_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/assemble_trocar/g129_dex3_env_cfg.py index f42568fdc621..557913170147 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/assemble_trocar/g129_dex3_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/assemble_trocar/g129_dex3_env_cfg.py @@ -4,6 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.envs.mdp as base_mdp import isaaclab.sim as sim_utils @@ -123,10 +124,12 @@ class AssembleTrocarSceneCfg(InteractiveSceneCfg): "DisposableLaparoscopicPunctureDevice001/" "DisposableLaparoscopicPunctureDevice005-xform.usd" ), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - rigid_body_enabled=True, - disable_gravity=False, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(rigid_body_enabled=True), + PhysxRigidBodyCfg( + disable_gravity=False, + ), + ], ), init_state=RigidObjectCfg.InitialStateCfg( rot=[-0.71475, -0.000243, 0.05853, 0.69692], pos=[-1.50635, 1.90997, 0.8631] diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py index a8dae7034eb3..cccc342583b6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_env_cfg.py @@ -4,6 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -134,18 +135,20 @@ class AssemblyEnvCfg(DirectRLEnvCfg): usd_path=f"{ASSET_DIR}/franka_mimic.usd", # usd_path=f'{ASSET_DIR}/automate_franka.usd', activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=192, diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_tasks_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_tasks_cfg.py index 635cedc27143..103ee0a2ac16 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_tasks_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/assembly_tasks_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, RigidObjectCfg from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -210,18 +212,20 @@ class Insertion(AssemblyTask): spawn=sim_utils.UsdFileCfg( usd_path=f"{assembly_dir}{fixed_asset_cfg.usd_path}", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, fix_root_link=True, # add this so the fixed asset is set to have a fixed base @@ -244,18 +248,20 @@ class Insertion(AssemblyTask): spawn=sim_utils.UsdFileCfg( usd_path=f"{assembly_dir}{held_asset_cfg.usd_path}", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=held_asset_cfg.mass), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py index c5c197393b65..2b874718b92e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_env_cfg.py @@ -5,6 +5,7 @@ from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -134,18 +135,20 @@ class DisassemblyEnvCfg(DirectRLEnvCfg): spawn=sim_utils.UsdFileCfg( usd_path=f"{ASSET_DIR}/franka_mimic.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=192, diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_tasks_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_tasks_cfg.py index 53307fd40341..79066bd5f4c3 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_tasks_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/automate/disassembly_tasks_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, RigidObjectCfg from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -160,18 +162,20 @@ class Extraction(DisassemblyTask): spawn=sim_utils.UsdFileCfg( usd_path=f"{assembly_dir}{fixed_asset_cfg.usd_path}", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=True, fix_root_link=True, # add this so the fixed asset is set to have a fixed base @@ -194,18 +198,20 @@ class Extraction(DisassemblyTask): spawn=sim_utils.UsdFileCfg( usd_path=f"{assembly_dir}{held_asset_cfg.usd_path}", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=held_asset_cfg.mass), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/config/rizon_4s/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/config/rizon_4s/joint_pos_env_cfg.py index 885e9b8b0d27..5d3eb0e45fa6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/config/rizon_4s/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/config/rizon_4s/joint_pos_env_cfg.py @@ -6,6 +6,7 @@ import math import torch +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -281,18 +282,20 @@ def __post_init__(self): self.scene.robot = FLEXIV_RIZON4S_GRAV_GRIPPER_CFG.replace( prim_path="{ENV_REGEX_NS}/Robot", spawn=FLEXIV_RIZON4S_GRAV_GRIPPER_CFG.spawn.replace( - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=4, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=4, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=1 ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/config/ur_10e/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/config/ur_10e/joint_pos_env_cfg.py index 8b0535081b45..c658dae89c9a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/config/ur_10e/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/config/ur_10e/joint_pos_env_cfg.py @@ -6,6 +6,7 @@ import math import torch +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -319,18 +320,20 @@ def __post_init__(self): self.scene.robot = UR10e_ROBOTIQ_GRIPPER_CFG.replace( prim_path="{ENV_REGEX_NS}/Robot", spawn=UR10e_ROBOTIQ_GRIPPER_CFG.spawn.replace( - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=4, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=4, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=1 ), @@ -408,18 +411,20 @@ def __post_init__(self): self.scene.robot = UR10e_ROBOTIQ_2F_85_CFG.replace( prim_path="{ENV_REGEX_NS}/Robot", spawn=UR10e_ROBOTIQ_2F_85_CFG.spawn.replace( - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=4, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=4, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=1 ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/gear_assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/gear_assembly_env_cfg.py index 8ac943fdd9bf..73ee7ab04f10 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/gear_assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/deploy/gear_assembly/gear_assembly_env_cfg.py @@ -7,6 +7,7 @@ from dataclasses import MISSING from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg @@ -57,19 +58,21 @@ class GearAssemblySceneCfg(InteractiveSceneCfg): spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Factory/gear_assets/factory_gear_base/factory_gear_base.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - kinematic_enabled=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=32, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True), + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=32, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=None), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.02, rest_offset=0.0), ), @@ -82,19 +85,21 @@ class GearAssemblySceneCfg(InteractiveSceneCfg): spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Factory/gear_assets/factory_gear_small/factory_gear_small.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - kinematic_enabled=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=32, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=32, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=None), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.02, rest_offset=0.0), ), @@ -107,19 +112,21 @@ class GearAssemblySceneCfg(InteractiveSceneCfg): spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Factory/gear_assets/factory_gear_medium/factory_gear_medium.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - kinematic_enabled=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=32, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=32, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=None), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.02, rest_offset=0.0), ), @@ -132,19 +139,21 @@ class GearAssemblySceneCfg(InteractiveSceneCfg): spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Factory/gear_assets/factory_gear_large/factory_gear_large.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - kinematic_enabled=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=32, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=32, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=None), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.02, rest_offset=0.0), ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene.py index be3fe2e1fc53..fc20fac57f75 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/drone_arl/navigation/config/arl_robot_1/scenes/obstacle_scenes/obstacle_scene.py @@ -4,6 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause import numpy as np +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.assets import RigidObjectCfg, RigidObjectCollectionCfg @@ -62,16 +63,18 @@ def generate_obstacle_collection(cfg: ObstaclesSceneCfg) -> RigidObjectCollectio spawn=sim_utils.CuboidCfg( size=wall_cfg.size, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.5, 0.5, color), metallic=0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=4, - solver_velocity_iteration_count=0, - disable_gravity=True, - kinematic_enabled=False, - linear_damping=9999.0, - angular_damping=9999.0, - max_linear_velocity=0.0, - max_angular_velocity=0.0, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + solver_position_iteration_count=4, + solver_velocity_iteration_count=0, + disable_gravity=True, + linear_damping=9999.0, + angular_damping=9999.0, + max_linear_velocity=0.0, + max_angular_velocity=0.0, + ), + ], # mass of walls needs to be way larger than weight of obstacles to make them not move during reset mass_props=sim_utils.MassPropertiesCfg(mass=10000000.0), collision_props=sim_utils.CollisionPropertiesCfg(), @@ -94,16 +97,18 @@ def generate_obstacle_collection(cfg: ObstaclesSceneCfg) -> RigidObjectCollectio spawn=sim_utils.CuboidCfg( size=obs_cfg.size, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=color_normalized, metallic=0.2), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=4, - solver_velocity_iteration_count=0, - disable_gravity=True, - kinematic_enabled=False, - linear_damping=1.0, - angular_damping=1.0, - max_linear_velocity=0.0, - max_angular_velocity=0.0, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + solver_position_iteration_count=4, + solver_velocity_iteration_count=0, + disable_gravity=True, + linear_damping=1.0, + angular_damping=1.0, + max_linear_velocity=0.0, + max_angular_velocity=0.0, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=100.0), collision_props=sim_utils.CollisionPropertiesCfg(), ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_env_cfg.py index a250380e2566..ce469524c0e0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_env_cfg.py @@ -4,6 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg @@ -125,18 +126,20 @@ class FactoryEnvCfg(DirectRLEnvCfg): spawn=sim_utils.UsdFileCfg( usd_path=f"{ASSET_DIR}/franka_mimic.usd", activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=192, diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_tasks_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_tasks_cfg.py index 4841f58d161b..9d6ef017f600 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_tasks_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/factory/factory_tasks_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR @@ -136,18 +138,20 @@ class PegInsert(FactoryTask): spawn=sim_utils.UsdFileCfg( usd_path=fixed_asset_cfg.usd_path, activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=fixed_asset_cfg.mass), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), @@ -161,18 +165,20 @@ class PegInsert(FactoryTask): spawn=sim_utils.UsdFileCfg( usd_path=held_asset_cfg.usd_path, activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=held_asset_cfg.mass), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), @@ -216,18 +222,20 @@ class GearMesh(FactoryTask): spawn=sim_utils.UsdFileCfg( usd_path=small_gear_usd, activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=0.019), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), @@ -242,18 +250,20 @@ class GearMesh(FactoryTask): spawn=sim_utils.UsdFileCfg( usd_path=large_gear_usd, activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=0.019), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), @@ -294,18 +304,20 @@ class GearMesh(FactoryTask): spawn=sim_utils.UsdFileCfg( usd_path=fixed_asset_cfg.usd_path, activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=fixed_asset_cfg.mass), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), @@ -319,18 +331,20 @@ class GearMesh(FactoryTask): spawn=sim_utils.UsdFileCfg( usd_path=held_asset_cfg.usd_path, activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=held_asset_cfg.mass), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), @@ -400,18 +414,20 @@ class NutThread(FactoryTask): spawn=sim_utils.UsdFileCfg( usd_path=fixed_asset_cfg.usd_path, activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=fixed_asset_cfg.mass), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), @@ -425,18 +441,20 @@ class NutThread(FactoryTask): spawn=sim_utils.UsdFileCfg( usd_path=held_asset_cfg.usd_path, activate_contact_sensors=True, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - max_depenetration_velocity=5.0, - linear_damping=0.0, - angular_damping=0.0, - max_linear_velocity=1000.0, - max_angular_velocity=3666.0, - enable_gyroscopic_forces=True, - solver_position_iteration_count=192, - solver_velocity_iteration_count=1, - max_contact_impulse=1e32, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + max_depenetration_velocity=5.0, + linear_damping=0.0, + angular_damping=0.0, + max_linear_velocity=1000.0, + max_angular_velocity=3666.0, + enable_gyroscopic_forces=True, + solver_position_iteration_count=192, + solver_velocity_iteration_count=1, + max_contact_impulse=1e32, + ), + ], mass_props=sim_utils.MassPropertiesCfg(mass=held_asset_cfg.mass), collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0), ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/lift/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/lift/config/openarm/joint_pos_env_cfg.py index b57667a5b323..853747091ad8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/lift/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/lift/config/openarm/joint_pos_env_cfg.py @@ -6,9 +6,10 @@ import math +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + from isaaclab.assets import RigidObjectCfg from isaaclab.sensors import FrameTransformerCfg -from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -61,14 +62,16 @@ def __post_init__(self): spawn=UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", scale=(0.8, 0.8, 0.8), - rigid_props=RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ], ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_pick_place/fixed_base_upper_body_ik_g1_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_pick_place/fixed_base_upper_body_ik_g1_env_cfg.py index 7c09df732bf4..02c626ef47b0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_pick_place/fixed_base_upper_body_ik_g1_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_pick_place/fixed_base_upper_body_ik_g1_env_cfg.py @@ -243,7 +243,7 @@ class FixedBaseUpperBodyIKG1SceneCfg(InteractiveSceneCfg): init_state=AssetBaseCfg.InitialStateCfg(pos=[0.0, 0.55, -0.3], rot=[0.0, 0.0, 0.0, 1.0]), spawn=UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/PackingTable/packing_table.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], ), ) @@ -253,7 +253,7 @@ class FixedBaseUpperBodyIKG1SceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/pick_place_task/pick_place_assets/steering_wheel.usd", scale=(0.75, 0.75, 0.75), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_pick_place/locomanipulation_g1_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_pick_place/locomanipulation_g1_env_cfg.py index effb0b09788f..8894c585720d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_pick_place/locomanipulation_g1_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/locomanip_pick_place/locomanipulation_g1_env_cfg.py @@ -272,7 +272,7 @@ class LocomanipulationG1SceneCfg(InteractiveSceneCfg): init_state=AssetBaseCfg.InitialStateCfg(pos=[0.0, 0.55, -0.3], rot=[0.0, 0.0, 0.0, 1.0]), spawn=UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/PackingTable/packing_table.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], ), ) @@ -282,7 +282,7 @@ class LocomanipulationG1SceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/pick_place_task/pick_place_assets/steering_wheel.usd", scale=(0.75, 0.75, 0.75), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/exhaustpipe_gr1t2_base_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/exhaustpipe_gr1t2_base_env_cfg.py index f2e7c8b6775a..4b5ce39f29fe 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/exhaustpipe_gr1t2_base_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/exhaustpipe_gr1t2_base_env_cfg.py @@ -51,7 +51,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/exhaust_pipe_task/exhaust_pipe_assets/table.usd", scale=(1.0, 1.0, 1.3), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) @@ -61,7 +61,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/exhaust_pipe_task/exhaust_pipe_assets/blue_exhaust_pipe.usd", scale=(0.5, 0.5, 1.5), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) @@ -71,7 +71,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/exhaust_pipe_task/exhaust_pipe_assets/blue_sorting_bin.usd", scale=(1.0, 1.7, 1.0), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) @@ -81,7 +81,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/exhaust_pipe_task/exhaust_pipe_assets/black_sorting_bin.usd", scale=(1.0, 1.7, 1.0), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/nutpour_gr1t2_base_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/nutpour_gr1t2_base_env_cfg.py index 6317e0ed2fbc..9126be510e80 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/nutpour_gr1t2_base_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/nutpour_gr1t2_base_env_cfg.py @@ -51,7 +51,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/nut_pour_task/nut_pour_assets/table.usd", scale=(1.0, 1.0, 1.3), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) @@ -61,7 +61,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/nut_pour_task/nut_pour_assets/sorting_scale.usd", scale=(1.0, 1.0, 1.0), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) @@ -71,7 +71,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/nut_pour_task/nut_pour_assets/sorting_bowl_yellow.usd", scale=(1.0, 1.0, 1.5), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005), ), ) @@ -82,7 +82,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/nut_pour_task/nut_pour_assets/sorting_beaker_red.usd", scale=(0.45, 0.45, 1.3), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) @@ -92,7 +92,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/nut_pour_task/nut_pour_assets/factory_m16_nut_green.usd", scale=(0.5, 0.5, 0.5), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], collision_props=sim_utils.CollisionPropertiesCfg(contact_offset=0.005), ), ) @@ -103,7 +103,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/nut_pour_task/nut_pour_assets/sorting_bin_blue.usd", scale=(0.75, 1.0, 1.0), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/pickplace_gr1t2_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/pickplace_gr1t2_env_cfg.py index c736375ab96e..e0d8b6715d8f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/pickplace_gr1t2_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/pickplace_gr1t2_env_cfg.py @@ -273,7 +273,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): init_state=AssetBaseCfg.InitialStateCfg(pos=[0.0, 0.55, 0.0], rot=[0.0, 0.0, 0.0, 1.0]), spawn=UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/PackingTable/packing_table.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], ), ) @@ -283,7 +283,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/pick_place_task/pick_place_assets/steering_wheel.usd", scale=(0.75, 0.75, 0.75), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py index 8afa97e6a42c..a65f9189b4f7 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py @@ -270,7 +270,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): init_state=AssetBaseCfg.InitialStateCfg(pos=[0.0, 0.55, 0.0], rot=[0.0, 0.0, 0.0, 1.0]), spawn=UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/PackingTable/packing_table.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], ), ) @@ -280,7 +280,7 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/pick_place_task/pick_place_assets/steering_wheel.usd", scale=(0.75, 0.75, 0.75), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], mass_props=MassPropertiesCfg( mass=0.05, ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py index 93ceae8d33a8..3f1f967928a5 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py @@ -7,6 +7,7 @@ from dataclasses import MISSING from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg from isaaclab.assets import AssetBaseCfg, RigidObjectCfg from isaaclab.devices.device_base import DevicesCfg @@ -21,7 +22,7 @@ from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.sensors import ContactSensorCfg, FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg -from isaaclab.sim.schemas.schemas_cfg import MassPropertiesCfg, RigidBodyPropertiesCfg +from isaaclab.sim.schemas.schemas_cfg import MassPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -261,14 +262,16 @@ def __post_init__(self): self.gripper_threshold = 0.2 # Rigid body properties of toy_truck and box - toy_truck_properties = RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ) + toy_truck_properties = [ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ] box_properties = toy_truck_properties.copy() diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py index 792baf5afdca..d7ddf9156930 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py @@ -6,6 +6,8 @@ import os from dataclasses import MISSING +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + from isaaclab.assets import AssetBaseCfg, RigidObjectCfg from isaaclab.devices.device_base import DevicesCfg from isaaclab.devices.keyboard import Se3KeyboardCfg @@ -18,7 +20,6 @@ from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.sensors import ContactSensorCfg, FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg -from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -214,14 +215,16 @@ def __post_init__(self): self.gripper_threshold = 0.2 # Rigid body properties of mug - mug_properties = RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ) + mug_properties = [ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ] self.scene.mug = RigidObjectCfg( prim_path="{ENV_REGEX_NS}/Mug", diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/bin_stack_joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/bin_stack_joint_pos_env_cfg.py index a99506622902..cdd1d61ab183 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/bin_stack_joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/bin_stack_joint_pos_env_cfg.py @@ -4,13 +4,14 @@ # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.assets import RigidObjectCfg from isaaclab.managers import EventTermCfg as EventTerm from isaaclab.managers import SceneEntityCfg from isaaclab.sensors import FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg -from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -120,14 +121,16 @@ def __post_init__(self): self.gripper_threshold = 0.005 # Rigid body properties of each cube - cube_properties = RigidBodyPropertiesCfg( - solver_position_iteration_count=40, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ) + cube_properties = [ + PhysxRigidBodyCfg( + solver_position_iteration_count=40, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ] # Blue sorting bin positioned at table center self.scene.blue_sorting_bin = RigidObjectCfg( @@ -136,7 +139,7 @@ def __post_init__(self): spawn=UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Mimic/nut_pour_task/nut_pour_assets/sorting_bin_blue.usd", scale=(1.1, 1.6, 3.3), - rigid_props=sim_utils.RigidBodyPropertiesCfg(), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg()], ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_ik_rel_visuomotor_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_ik_rel_visuomotor_env_cfg.py index 15f872c90fba..a8031c29c277 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_ik_rel_visuomotor_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_ik_rel_visuomotor_env_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, RigidObjectCfg from isaaclab.controllers.differential_ik_cfg import DifferentialIKControllerCfg @@ -13,7 +15,6 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.sensors import CameraCfg, FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg -from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, NVIDIA_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -257,14 +258,16 @@ def __post_init__(self): self.gripper_threshold = 0.005 # Rigid body properties of each cube - cube_properties = RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ) + cube_properties = [ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ] # Set each stacking cube deterministically self.scene.cube_1 = RigidObjectCfg( diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_joint_pos_env_cfg.py index 0bb1a635b921..389e08bf20d7 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_joint_pos_env_cfg.py @@ -3,12 +3,13 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + from isaaclab.assets import ArticulationCfg, RigidObjectCfg from isaaclab.managers import EventTermCfg as EventTerm from isaaclab.managers import SceneEntityCfg from isaaclab.sensors import FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg -from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -103,14 +104,16 @@ def __post_init__(self): self.gripper_threshold = 0.005 # Rigid body properties of each cube - cube_properties = RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ) + cube_properties = [ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ] # Set each stacking cube deterministically self.scene.cube_1 = RigidObjectCfg( diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_joint_pos_instance_randomize_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_joint_pos_instance_randomize_env_cfg.py index 91b2f8176966..c715011f7f2a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_joint_pos_instance_randomize_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/franka/stack_joint_pos_instance_randomize_env_cfg.py @@ -4,13 +4,13 @@ # SPDX-License-Identifier: BSD-3-Clause import torch +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg from isaaclab.assets import RigidObjectCfg, RigidObjectCollectionCfg from isaaclab.managers import EventTermCfg as EventTerm from isaaclab.managers import SceneEntityCfg from isaaclab.sensors import FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg -from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -94,14 +94,16 @@ def __post_init__(self): self.gripper_threshold = 0.005 # Rigid body properties of each cube - cube_properties = RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ) + cube_properties = [ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ] # Set each stacking cube to be a collection of rigid objects cube_1_config_dict = { diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/galbot/stack_joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/galbot/stack_joint_pos_env_cfg.py index a2dd4cef41c3..66f8e9e5e256 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/galbot/stack_joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/galbot/stack_joint_pos_env_cfg.py @@ -5,6 +5,7 @@ from isaaclab_physx.assets import SurfaceGripperCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg from isaaclab_teleop import IsaacTeleopCfg from isaaclab.assets import RigidObjectCfg @@ -15,7 +16,7 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.sensors import FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg -from isaaclab.sim.schemas.schemas_cfg import CollisionPropertiesCfg, RigidBodyPropertiesCfg +from isaaclab.sim.schemas.schemas_cfg import CollisionPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -261,14 +262,16 @@ def __post_init__(self): self.gripper_threshold = 0.010 # Rigid body properties of each cube - cube_properties = RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ) + cube_properties = [ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ] cube_collision_properties = CollisionPropertiesCfg(contact_offset=0.005, rest_offset=0.0) # Set each stacking cube deterministically diff --git a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py index 28365001a464..e4e3fa0390b2 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/contrib/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py @@ -4,6 +4,7 @@ # SPDX-License-Identifier: BSD-3-Clause from isaaclab_physx.assets import SurfaceGripperCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg from isaaclab.assets import RigidObjectCfg from isaaclab.envs.mdp.actions.actions_cfg import SurfaceGripperBinaryActionCfg @@ -11,7 +12,6 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.sensors import FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg -from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -68,14 +68,16 @@ class EventCfgLongSuction: @configclass class UR10CubeStackEnvCfg(StackEnvCfg): # Rigid body properties of each cube - cube_properties = RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ) + cube_properties = [ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ] cube_scale = (1.0, 1.0, 1.0) # Listens to the required transforms marker_cfg = FRAME_MARKER_CFG.copy() diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/allegro_hand/allegro_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/allegro_hand/allegro_hand_env_cfg.py index 8f32326763f6..12321eb13826 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/allegro_hand/allegro_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/allegro_hand/allegro_hand_env_cfg.py @@ -7,6 +7,7 @@ from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg from isaaclab_ovphysx.physics import OvPhysxCfg from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, RigidObjectCfg @@ -29,16 +30,18 @@ class ObjectCfg(PresetCfg): prim_path="/World/envs/env_.*/object", spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - kinematic_enabled=False, - disable_gravity=False, - enable_gyroscopic_forces=True, - solver_position_iteration_count=8, - solver_velocity_iteration_count=0, - sleep_threshold=0.005, - stabilization_threshold=0.0025, - max_depenetration_velocity=1000.0, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + disable_gravity=False, + enable_gyroscopic_forces=True, + solver_position_iteration_count=8, + solver_velocity_iteration_count=0, + sleep_threshold=0.005, + stabilization_threshold=0.0025, + max_depenetration_velocity=1000.0, + ), + ], mass_props=sim_utils.MassPropertiesCfg(density=400.0), scale=(1.2, 1.2, 1.2), ), @@ -61,16 +64,18 @@ class ObjectCfg(PresetCfg): prim_path="/World/envs/env_.*/object", spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - kinematic_enabled=False, - disable_gravity=False, - enable_gyroscopic_forces=True, - solver_position_iteration_count=8, - solver_velocity_iteration_count=0, - sleep_threshold=0.005, - stabilization_threshold=0.0025, - max_depenetration_velocity=1000.0, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + disable_gravity=False, + enable_gyroscopic_forces=True, + solver_position_iteration_count=8, + solver_velocity_iteration_count=0, + sleep_threshold=0.005, + stabilization_threshold=0.0025, + max_depenetration_velocity=1000.0, + ), + ], mass_props=sim_utils.MassPropertiesCfg(density=400.0), scale=(1.2, 1.2, 1.2), ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/dexsuite/dexsuite_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/dexsuite/dexsuite_env_cfg.py index eeea53b48415..215d00e0fba5 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/dexsuite/dexsuite_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/dexsuite/dexsuite_env_cfg.py @@ -7,6 +7,7 @@ from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg, NewtonCollisionPipelineCfg, NewtonShapeCfg from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg @@ -31,7 +32,7 @@ TABLE_SPAWN_CFG = sim_utils.CuboidCfg( size=(0.8, 1.5, 0.04), - rigid_props=sim_utils.RigidBodyPropertiesCfg(kinematic_enabled=True), + rigid_props=[sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=True)], collision_props=sim_utils.CollisionPropertiesCfg(), # trick: we let visualizer's color to show the table with success coloring visible=False, @@ -65,22 +66,26 @@ class ObjectCfg(PresetCfg): MeshConeCfg(radius=0.05, height=0.1, **OBJECT_PHYSICS), MeshConeCfg(radius=0.025, height=0.1, **OBJECT_PHYSICS), ], - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=0, - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=0, + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg(), mass_props=sim_utils.MassPropertiesCfg(mass=0.2), ) cube = sim_utils.CuboidCfg( size=(0.05, 0.1, 0.1), physics_material=RigidBodyMaterialCfg(static_friction=0.5), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=0, - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=0, + disable_gravity=False, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg(), mass_props=sim_utils.MassPropertiesCfg(mass=0.2), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/franka_cabinet/franka_cabinet_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/franka_cabinet/franka_cabinet_env_cfg.py index 107d9443695e..597350a70157 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/franka_cabinet/franka_cabinet_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/franka_cabinet/franka_cabinet_env_cfg.py @@ -5,6 +5,8 @@ from __future__ import annotations +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets import ArticulationCfg @@ -49,10 +51,12 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg): spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/FrankaEmika/panda_instanceable.usd", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=False, - max_depenetration_velocity=5.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg( enabled_self_collisions=False, solver_position_iteration_count=12, solver_velocity_iteration_count=1 ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/inhand/inhand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/inhand/inhand_env_cfg.py index abf2bb5a216b..2485008f8cbd 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/inhand/inhand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/inhand/inhand_env_cfg.py @@ -8,6 +8,7 @@ from dataclasses import MISSING from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg @@ -44,16 +45,18 @@ class InHandObjectSceneCfg(InteractiveSceneCfg): prim_path="{ENV_REGEX_NS}/object", spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - kinematic_enabled=False, - disable_gravity=False, - enable_gyroscopic_forces=True, - solver_position_iteration_count=8, - solver_velocity_iteration_count=0, - sleep_threshold=0.005, - stabilization_threshold=0.0025, - max_depenetration_velocity=1000.0, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + disable_gravity=False, + enable_gyroscopic_forces=True, + solver_position_iteration_count=8, + solver_velocity_iteration_count=0, + sleep_threshold=0.005, + stabilization_threshold=0.0025, + max_depenetration_velocity=1000.0, + ), + ], mass_props=sim_utils.MassPropertiesCfg(density=400.0), ), init_state=RigidObjectCfg.InitialStateCfg(pos=(0.0, -0.19, 0.56), rot=(0.0, 0.0, 0.0, 1.0)), diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/joint_pos_env_cfg.py index 9f6787cb9423..e2c7212625b9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift/config/franka/joint_pos_env_cfg.py @@ -3,10 +3,11 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + from isaaclab.assets import RigidObjectCfg from isaaclab.sensors import FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg -from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass @@ -50,14 +51,16 @@ def __post_init__(self): spawn=UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", scale=(0.8, 0.8, 0.8), - rigid_props=RigidBodyPropertiesCfg( - solver_position_iteration_count=16, - solver_velocity_iteration_count=1, - max_angular_velocity=1000.0, - max_linear_velocity=1000.0, - max_depenetration_velocity=5.0, - disable_gravity=False, - ), + rigid_props=[ + PhysxRigidBodyCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ], ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_soft_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_soft_env_cfg.py index 500d020ccb60..e921110ef6e3 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_soft_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/lift_franka_soft/franka_soft_env_cfg.py @@ -17,7 +17,7 @@ from isaaclab_newton.sim.schemas import NewtonDeformableBodyPropertiesCfg from isaaclab_newton.sim.spawners.materials import NewtonDeformableBodyMaterialCfg from isaaclab_physx.physics import PhysxCfg -from isaaclab_physx.sim.schemas import PhysxDeformableBodyPropertiesCfg +from isaaclab_physx.sim.schemas import PhysxDeformableBodyPropertiesCfg, PhysxRigidBodyCfg from isaaclab_physx.sim.spawners.materials import PhysxDeformableBodyMaterialCfg import isaaclab.sim as sim_utils @@ -215,7 +215,7 @@ class _FrankaSoftSceneCfg(InteractiveSceneCfg): def __post_init__(self) -> None: # disable gravity on the arm so the low-PD actuators do not need to fight gravity sag, # which is the dominant source of steady-state IK tracking error. - self.robot.spawn.rigid_props.disable_gravity = True + next(f for f in self.robot.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True # increase franka gripper stiffness self.robot.actuators["panda_hand"].effort_limit_sim = 500.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/osc_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/osc_env_cfg.py index 24b94f266433..cd81967457b9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/osc_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/reach/config/franka/osc_env_cfg.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: BSD-3-Clause +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg + from isaaclab.controllers.operational_space_cfg import OperationalSpaceControllerCfg from isaaclab.envs.mdp.actions.actions_cfg import OperationalSpaceControllerActionCfg from isaaclab.utils.configclass import configclass @@ -28,7 +30,7 @@ def __post_init__(self): self.scene.robot.actuators["panda_shoulder"].damping = 0.0 self.scene.robot.actuators["panda_forearm"].stiffness = 0.0 self.scene.robot.actuators["panda_forearm"].damping = 0.0 - self.scene.robot.spawn.rigid_props.disable_gravity = True + next(f for f in self.scene.robot.spawn.rigid_props if isinstance(f, PhysxRigidBodyCfg)).disable_gravity = True # If closed-loop contact force control is desired, contact sensors should be enabled for the robot # self.scene.robot.spawn.activate_contact_sensors = True diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/reach/reach_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/reach/reach_env_cfg.py index eb5d38b20c9d..d6d2464fbc50 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/reach/reach_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/reach/reach_env_cfg.py @@ -24,7 +24,7 @@ from isaaclab.managers import SceneEntityCfg from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.scene import InteractiveSceneCfg -from isaaclab.sim import CollisionPropertiesCfg, RigidBodyPropertiesCfg, UsdFileCfg +from isaaclab.sim import CollisionPropertiesCfg, UsdFileCfg, UsdPhysicsRigidBodyCfg from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.configclass import configclass from isaaclab.utils.noise import UniformNoiseCfg as Unoise @@ -74,7 +74,7 @@ class TableCfg(PresetCfg): spawn=sim_utils.CuboidCfg( size=(0.9, 1.3, 1.00), collision_props=CollisionPropertiesCfg(), - rigid_props=RigidBodyPropertiesCfg(rigid_body_enabled=True), + rigid_props=[UsdPhysicsRigidBodyCfg(rigid_body_enabled=True)], ), actuators={}, articulation_root_prim_path="", diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand/shadow_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand/shadow_hand_env_cfg.py index c4d785115555..1d2f459948bf 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand/shadow_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand/shadow_hand_env_cfg.py @@ -5,6 +5,7 @@ from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils @@ -152,11 +153,13 @@ class ShadowHandRobotCfg(PresetCfg): # newton/mujoco have separate usd schema usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/ShadowRobot/ShadowHandNewton/shadow_hand_instanceable.usda", activate_contact_sensors=False, - rigid_props=sim_utils.RigidBodyPropertiesCfg( - disable_gravity=True, - retain_accelerations=True, - max_depenetration_velocity=1000.0, - ), + rigid_props=[ + PhysxRigidBodyCfg( + disable_gravity=True, + retain_accelerations=True, + max_depenetration_velocity=1000.0, + ), + ], articulation_props=sim_utils.ArticulationRootPropertiesCfg(enabled_self_collisions=True), joint_drive_props=sim_utils.JointDrivePropertiesCfg(drive_type="force", ensure_drives_exist=True), fixed_tendons_props=sim_utils.FixedTendonPropertiesCfg(damping=0.1), @@ -215,16 +218,18 @@ class ObjectCfg(PresetCfg): prim_path="/World/envs/env_.*/object", spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", - rigid_props=sim_utils.RigidBodyPropertiesCfg( - kinematic_enabled=False, - disable_gravity=False, - enable_gyroscopic_forces=True, - solver_position_iteration_count=8, - solver_velocity_iteration_count=0, - sleep_threshold=0.005, - stabilization_threshold=0.0025, - max_depenetration_velocity=1000.0, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + disable_gravity=False, + enable_gyroscopic_forces=True, + solver_position_iteration_count=8, + solver_velocity_iteration_count=0, + sleep_threshold=0.005, + stabilization_threshold=0.0025, + max_depenetration_velocity=1000.0, + ), + ], mass_props=sim_utils.MassPropertiesCfg(density=567.0), semantic_tags=[("class", "cube")], ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand_over/shadow_hand_over_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand_over/shadow_hand_over_env_cfg.py index 3cac6fe91d63..d805a623f185 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand_over/shadow_hand_over_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/core/shadow_hand_over/shadow_hand_over_env_cfg.py @@ -5,6 +5,7 @@ from isaaclab_newton.physics import MJWarpSolverCfg, NewtonCfg from isaaclab_physx.physics import PhysxCfg +from isaaclab_physx.sim.schemas import PhysxRigidBodyCfg import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils @@ -199,16 +200,18 @@ class ObjectCfg(PresetCfg): radius=0.0335, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.8, 1.0, 0.0)), physics_material=sim_utils.RigidBodyMaterialCfg(static_friction=0.7), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - kinematic_enabled=False, - disable_gravity=False, - enable_gyroscopic_forces=True, - solver_position_iteration_count=8, - solver_velocity_iteration_count=0, - sleep_threshold=0.005, - stabilization_threshold=0.0025, - max_depenetration_velocity=1000.0, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + disable_gravity=False, + enable_gyroscopic_forces=True, + solver_position_iteration_count=8, + solver_velocity_iteration_count=0, + sleep_threshold=0.005, + stabilization_threshold=0.0025, + max_depenetration_velocity=1000.0, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg(), mass_props=sim_utils.MassPropertiesCfg(density=500.0), ), @@ -219,11 +222,13 @@ class ObjectCfg(PresetCfg): spawn=sim_utils.SphereCfg( radius=0.0335, visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.8, 1.0, 0.0)), - rigid_props=sim_utils.RigidBodyPropertiesCfg( - kinematic_enabled=False, - disable_gravity=False, - enable_gyroscopic_forces=True, - ), + rigid_props=[ + sim_utils.UsdPhysicsRigidBodyCfg(kinematic_enabled=False), + PhysxRigidBodyCfg( + disable_gravity=False, + enable_gyroscopic_forces=True, + ), + ], collision_props=sim_utils.CollisionPropertiesCfg(), mass_props=sim_utils.MassPropertiesCfg(density=500.0), ),