From 782d6bb0ca0dba6332799c8de155021c20e9a0cf Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Tue, 10 Feb 2026 15:45:12 -0800 Subject: [PATCH 1/7] Moves PhysicsManagerCfg parameters to SimulationCfg --- .../isaaclab/physics/physics_manager_cfg.py | 52 +++- .../isaaclab/isaaclab/sim/simulation_cfg.py | 260 ++++-------------- .../isaaclab/sim/simulation_context.py | 9 +- .../test/sim/test_simulation_context.py | 61 ++-- .../isaaclab_physx/physics/physx_manager.py | 2 +- .../physics/physx_manager_cfg.py | 14 - .../direct/cartpole/cartpole_camera_env.py | 3 +- .../direct/cartpole/cartpole_env.py | 3 +- .../direct/humanoid/humanoid_env.py | 4 +- 9 files changed, 137 insertions(+), 271 deletions(-) diff --git a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py index 80b00b37e3b8..0cecd821fa33 100644 --- a/source/isaaclab/isaaclab/physics/physics_manager_cfg.py +++ b/source/isaaclab/isaaclab/physics/physics_manager_cfg.py @@ -21,31 +21,55 @@ class PhysicsCfg: """Abstract base configuration for physics managers. - This base class contains common simulation parameters shared across - all physics backends. Subclasses should override :meth:`create_manager` - to return the appropriate physics manager class. + This base class contains physics backend-specific parameters. + Subclasses should override the class_type to return the appropriate + physics manager class. + + .. note:: + The following parameters can be optionally specified here to override + the values from :class:`SimulationCfg`. If left as MISSING, they will + be automatically propagated from :class:`SimulationCfg`: + + - ``dt``: Physics simulation time-step + - ``gravity``: Gravity vector + - ``physics_prim_path``: Physics scene prim path + - ``physics_material``: Default physics material """ # ------------------------------------------------------------------ - # Common Simulation Parameters + # Physics Backend Configuration # ------------------------------------------------------------------ class_type: type[PhysicsManager] = MISSING - dt: float = 1.0 / 60.0 - """The physics simulation time-step (in seconds). Default is 0.0167 seconds.""" + # ------------------------------------------------------------------ + # Override Parameters (propagated from SimulationCfg if MISSING) + # ------------------------------------------------------------------ + + dt: float = MISSING + """The physics simulation time-step (in seconds). + + If MISSING, uses the value from :attr:`SimulationCfg.dt`. + """ - gravity: tuple[float, float, float] = (0.0, 0.0, -9.81) - """The gravity vector (in m/s^2). Default is (0.0, 0.0, -9.81).""" + gravity: tuple[float, float, float] = MISSING + """The gravity vector (in m/s^2). - physics_prim_path: str = "/physicsScene" - """The prim path where the USD PhysicsScene is created. Default is "/physicsScene".""" + If MISSING, uses the value from :attr:`SimulationCfg.gravity`. + """ + + physics_prim_path: str = MISSING + """The prim path where the USD PhysicsScene is created. + + If MISSING, uses the value from :attr:`SimulationCfg.physics_prim_path`. + """ - physics_material: RigidBodyMaterialCfg = RigidBodyMaterialCfg() - """Default physics material settings for rigid bodies. Default is None (uses RigidBodyMaterialCfg defaults). + physics_material: RigidBodyMaterialCfg = MISSING + """Default physics material settings for rigid bodies. - The physics engine defaults to this physics material for all the rigid body prims that do not have any - physics material specified on them. + If MISSING, uses the value from :attr:`SimulationCfg.physics_material`. + The physics engine defaults to this physics material for all the rigid body prims + that do not have any physics material specified on them. The material is created at the path: ``{physics_prim_path}/defaultMaterial``. """ diff --git a/source/isaaclab/isaaclab/sim/simulation_cfg.py b/source/isaaclab/isaaclab/sim/simulation_cfg.py index 0f4f810db03b..22514ebccdbb 100644 --- a/source/isaaclab/isaaclab/sim/simulation_cfg.py +++ b/source/isaaclab/isaaclab/sim/simulation_cfg.py @@ -11,26 +11,12 @@ from __future__ import annotations -import contextlib -import warnings from typing import Any, Literal # Literal used by RenderCfg -from isaaclab_physx.physics import PhysxCfg - from isaaclab.physics import PhysicsCfg from isaaclab.utils import configclass from isaaclab.visualizers import VisualizerCfg -# Mapping of deprecated SimulationCfg fields to their new location in physics -_DEPRECATED_FIELDS = { - "dt": "physics.dt", - "gravity": "physics.gravity", - "physics_prim_path": "physics.physics_prim_path", - "physics_material": "physics.physics_material", - "use_fabric": "physics.use_fabric", - "physx": "physics (PhysxCfg attributes directly)", -} - @configclass class RenderCfg: @@ -183,18 +169,8 @@ class RenderCfg: class SimulationCfg: """Configuration for simulation physics. - .. note:: - The following fields have been moved to ``physics`` and are deprecated: - - - ``dt`` → ``physics.dt`` - - ``gravity`` → ``physics.gravity`` - - ``physics_prim_path`` → ``physics.physics_prim_path`` - - ``physics_material`` → ``physics.physics_material`` - - ``use_fabric`` → ``physics.use_fabric`` - - ``physx`` → Use ``PhysxCfg`` attributes directly - - Using the old field names will issue a deprecation warning and forward - the values to the new location. + This class contains the main simulation parameters including physics time-step, gravity, + device settings, and physics backend configuration. """ device: str = "cuda:0" @@ -207,6 +183,35 @@ class SimulationCfg: - ``"cuda:N"``: Use GPU, where N is the device ID. For example, "cuda:0". """ + dt: float = 1.0 / 60.0 + """The physics simulation time-step (in seconds). Default is 0.0167 seconds.""" + + gravity: tuple[float, float, float] = (0.0, 0.0, -9.81) + """The gravity vector (in m/s^2). Default is (0.0, 0.0, -9.81).""" + + physics_prim_path: str = "/physicsScene" + """The prim path where the USD PhysicsScene is created. Default is "/physicsScene".""" + + physics_material: Any = None + """Default physics material settings for rigid bodies. Default is None (uses RigidBodyMaterialCfg defaults). + + The physics engine defaults to this physics material for all the rigid body prims that do not have any + physics material specified on them. + + The material is created at the path: ``{physics_prim_path}/defaultMaterial``. + """ + + use_fabric: bool = True + """Enable/disable reading of physics buffers directly. Default is True. + + When running the simulation, updates in the states in the scene is normally synchronized with USD. + This leads to an overhead in reading the data and does not scale well with massive parallelization. + This flag allows disabling the synchronization and reading the data directly from the physics buffers. + + It is recommended to set this flag to :obj:`True` when running the simulation with a large number + of primitives in the scene. + """ + render_interval: int = 1 """The number of physics simulation steps per rendering step. Default is 1.""" @@ -225,11 +230,12 @@ class SimulationCfg: with the GUI enabled. This is to allow certain GUI features to work properly. """ - physics: PhysicsCfg = PhysxCfg() - """Physics manager configuration. Default is PhysxCfg(). + physics: PhysicsCfg | None = None + """Physics manager configuration. Default is None (uses PhysxCfg()). This configuration determines which physics manager to use. Override with a different config (e.g., NewtonManagerCfg) to use a different physics backend. + If None, PhysxCfg() will be used by default. """ render: RenderCfg = RenderCfg() @@ -257,175 +263,31 @@ class SimulationCfg: visualizer_cfgs: list[VisualizerCfg] | VisualizerCfg | None = None """The list of visualizer configurations. Default is None.""" - # Deprecated fields - accepted in constructor for backward compatibility - dt: float | None = None - """DEPRECATED: Use physics.dt instead.""" - - gravity: tuple[float, float, float] | None = None - """DEPRECATED: Use physics.gravity instead.""" - - physics_prim_path: str | None = None - """DEPRECATED: Use physics.physics_prim_path instead.""" - - physics_material: Any | None = None - """DEPRECATED: Use physics.physics_material instead.""" - - use_fabric: bool | None = None - """DEPRECATED: Use physics.use_fabric instead.""" - - physx: Any | None = None - """DEPRECATED: Use physics (PhysxCfg) directly instead. - - After initialization, this field is set to physics for backward compatibility. - """ - def __post_init__(self): - """Forward deprecated constructor arguments to physics.""" - deprecated_fields = ["dt", "gravity", "physics_prim_path", "physics_material", "use_fabric"] - - for field_name in deprecated_fields: - # Use getattr with None default - field might not exist during class definition - value = getattr(self, field_name, None) - if value is not None: - warnings.warn( - f"SimulationCfg({field_name}=...) is deprecated. " - f"Use SimulationCfg(physics=PhysxCfg({field_name}=...)) instead.", - FutureWarning, - stacklevel=4, - ) - # Forward to physics - if hasattr(self.physics, field_name): - setattr(self.physics, field_name, value) - - # Delete deprecated fields so __getattr__ is called when accessing them - # This allows runtime access like self.sim.dt to work via __getattr__ - for field_name in deprecated_fields: - if field_name != "physics_material": # physics_material needs object access - with contextlib.suppress(AttributeError): - delattr(self, field_name) - - # Set physics_material to point to physics.physics_material for backward-compatible access - if hasattr(self.physics, "physics_material"): - object.__setattr__(self, "physics_material", self.physics.physics_material) - - # Handle physx=PhysxCfg(...) - copy PhysX-specific attributes to physics - # The old PhysxCfg only had PhysX-specific settings, not dt/gravity/etc. - physx_cfg = getattr(self, "physx", None) - if physx_cfg is not None: - warnings.warn( - "SimulationCfg(physx=...) is deprecated. Use SimulationCfg(physics=PhysxCfg(...)) instead.", - FutureWarning, - stacklevel=4, - ) - # PhysX-specific fields that should be copied (not general physics settings) - physx_specific_fields = { - "bounce_threshold_velocity", - "friction_offset_threshold", - "friction_correlation_distance", - "solver_type", - "enable_stabilization", - "max_depenetration_velocity", - "enable_enhanced_determinism", - "min_position_iteration_count", - "max_position_iteration_count", - "min_velocity_iteration_count", - "max_velocity_iteration_count", - "enable_ccd", - "gpu_max_rigid_contact_count", - "gpu_max_rigid_patch_count", - "gpu_found_lost_pairs_capacity", - "gpu_found_lost_aggregate_pairs_capacity", - "gpu_total_aggregate_pairs_capacity", - "gpu_heap_capacity", - "gpu_temp_buffer_capacity", - "gpu_max_num_partitions", - "gpu_max_soft_body_contacts", - "gpu_max_particle_contacts", - "gpu_collision_stack_size", - } - - import dataclasses - - if dataclasses.is_dataclass(physx_cfg): - for field in dataclasses.fields(physx_cfg): - if field.name in physx_specific_fields: - value = getattr(physx_cfg, field.name) - # Get field default - if field.default is not dataclasses.MISSING: - default = field.default - elif field.default_factory is not dataclasses.MISSING: - default = field.default_factory() - else: - default = None - # Only copy if different from default - if value != default and hasattr(self.physics, field.name): - setattr(self.physics, field.name, value) - - # Note: 'physx' is handled in __getattr__ for backward-compatible access with deprecation warning - # Delete the physx field so __getattr__ is called when accessing it - with contextlib.suppress(AttributeError): - delattr(self, "physx") - - def __setattr__(self, name: str, value: Any) -> None: - """Intercept deprecated attribute assignment and forward to physics.""" - # Mapping of deprecated fields to their new location - deprecated_map = { - "dt": "physics.dt", - "gravity": "physics.gravity", - "physics_prim_path": "physics.physics_prim_path", - "physics_material": "physics.physics_material", - "use_fabric": "physics.use_fabric", - } - - if name in deprecated_map and value is not None: - # Only forward non-None values (None means "not set" for deprecated fields) - try: - physics = object.__getattribute__(self, "physics") - if hasattr(physics, name): - setattr(physics, name, value) - warnings.warn( - f"SimulationCfg.{name} is deprecated. Use {deprecated_map[name]} instead.", - FutureWarning, - stacklevel=2, - ) - return - except AttributeError: - # physics not yet set, fall through to normal setattr - pass - # Default behavior - object.__setattr__(self, name, value) - - def __getattr__(self, name: str) -> Any: - """Intercept deprecated attribute access and forward to physics.""" - # Mapping of deprecated fields to their new location - deprecated_map = { - "dt": "physics.dt", - "gravity": "physics.gravity", - "physics_prim_path": "physics.physics_prim_path", - "physics_material": "physics.physics_material", - "use_fabric": "physics.use_fabric", - } - - if name in deprecated_map: - try: - physics = object.__getattribute__(self, "physics") - if hasattr(physics, name): - warnings.warn( - f"SimulationCfg.{name} is deprecated. Use {deprecated_map[name]} instead.", - FutureWarning, - stacklevel=2, - ) - return getattr(physics, name) - except AttributeError: - pass - - # Handle 'physx' access for backward compatibility with sim.physx.some_setting - if name == "physx": - warnings.warn( - "SimulationCfg.physx is deprecated. Use physics directly instead.", - FutureWarning, - stacklevel=2, - ) - return object.__getattribute__(self, "physics") - - raise AttributeError(f"'{type(self).__name__}' object has no attribute '{name}'") + """Initialize defaults if not set.""" + from dataclasses import MISSING as DATACLASS_MISSING + + # Set default physics backend if None + if self.physics is None: + from isaaclab_physx.physics import PhysxCfg + + self.physics = PhysxCfg() + + # Propagate parameters from SimulationCfg to physics config if they are MISSING + if self.physics.dt is DATACLASS_MISSING: + self.physics.dt = self.dt + if self.physics.gravity is DATACLASS_MISSING: + self.physics.gravity = self.gravity + if self.physics.physics_prim_path is DATACLASS_MISSING: + self.physics.physics_prim_path = self.physics_prim_path + if self.physics.physics_material is DATACLASS_MISSING: + self.physics.physics_material = self.physics_material + + # Set default physics material if None + if self.physics_material is None: + from isaaclab.sim.spawners.materials import RigidBodyMaterialCfg + + self.physics_material = RigidBodyMaterialCfg() + # Also propagate to physics if it was MISSING + if self.physics.physics_material is DATACLASS_MISSING: + self.physics.physics_material = self.physics_material diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index b64b2be3a0a4..88844f123bf1 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -137,7 +137,7 @@ def __init__(self, cfg: SimulationCfg | None = None): def _init_usd_physics_scene(self) -> None: """Create and configure the USD physics scene.""" - cfg = self.cfg.physics + cfg = self.cfg with sim_utils.use_stage(self.stage): # Set stage conventions for metric units UsdGeom.SetStageUpAxis(self.stage, "Z") @@ -205,7 +205,7 @@ def get_physics_dt(self) -> float: def _init_visualizers(self) -> None: """Initialize visualizers based on config and settings.""" self._visualizers: list[Visualizer] = [] - self._viz_dt = self.cfg.physics.dt * self.cfg.render_interval + self._viz_dt = self.cfg.dt * self.cfg.render_interval # Determine which visualizers to create viz_str = "omniverse" # Default @@ -413,11 +413,8 @@ def build_simulation_context( stage_utils.create_new_stage() if sim_cfg is None: - from isaaclab_physx.physics import PhysxCfg - gravity = (0.0, 0.0, -9.81) if gravity_enabled else (0.0, 0.0, 0.0) - physics = PhysxCfg(dt=dt, gravity=gravity) - sim_cfg = SimulationCfg(device=device, physics=physics) + sim_cfg = SimulationCfg(device=device, dt=dt, gravity=gravity) sim = SimulationContext(sim_cfg) diff --git a/source/isaaclab/test/sim/test_simulation_context.py b/source/isaaclab/test/sim/test_simulation_context.py index 88abe9ddab7a..15aeca3e0041 100644 --- a/source/isaaclab/test/sim/test_simulation_context.py +++ b/source/isaaclab/test/sim/test_simulation_context.py @@ -48,12 +48,13 @@ def test_init(device): """Test the simulation context initialization.""" from isaaclab.sim.spawners.materials import RigidBodyMaterialCfg - physics = PhysxCfg( + cfg = SimulationCfg( + device=device, physics_prim_path="/Physics/PhysX", gravity=(0.0, -0.5, -0.5), physics_material=RigidBodyMaterialCfg(), + render_interval=5, ) - cfg = SimulationCfg(device=device, physics=physics, render_interval=5) # sim = SimulationContext(cfg) # TODO: Figure out why keyword argument doesn't work. # note: added a fix in Isaac Sim 2023.1 for this. @@ -78,7 +79,7 @@ def test_init(device): # check valid settings physics_hz = physx_scene_api.GetTimeStepsPerSecondAttr().Get() physics_dt = 1.0 / physics_hz - assert physics_dt == cfg.physics.dt + assert physics_dt == cfg.dt # check valid paths assert sim.stage.GetPrimAtPath("/Physics/PhysX").IsValid() @@ -89,7 +90,7 @@ def test_init(device): physics_scene.GetGravityMagnitudeAttr().Get(), ) gravity = np.array(gravity_dir) * gravity_mag - np.testing.assert_almost_equal(gravity, cfg.physics.gravity) + np.testing.assert_almost_equal(gravity, cfg.gravity) @pytest.mark.isaacsim_ci @@ -195,7 +196,7 @@ def test_timeline_pause(): @pytest.mark.isaacsim_ci def test_reset(): """Test simulation reset.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create a simple cube to test with @@ -215,7 +216,7 @@ def test_reset(): @pytest.mark.isaacsim_ci def test_reset_soft(): """Test soft reset (without stopping simulation).""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create a simple cube @@ -236,7 +237,7 @@ def test_reset_soft(): @pytest.mark.isaacsim_ci def test_forward(): """Test forward propagation for fabric updates.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01, use_fabric=True)) + cfg = SimulationCfg(dt=0.01, use_fabric=True) sim = SimulationContext(cfg) # create simple scene @@ -256,7 +257,7 @@ def test_forward(): @pytest.mark.parametrize("render", [True, False]) def test_step(render): """Test stepping simulation with and without rendering.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create simple scene @@ -276,7 +277,7 @@ def test_step(render): @pytest.mark.isaacsim_ci def test_render(): """Test rendering simulation.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create simple scene @@ -333,7 +334,7 @@ def test_clear_stage(): assert not sim.stage.GetPrimAtPath("/World/Cube1").IsValid() assert not sim.stage.GetPrimAtPath("/World/Cube2").IsValid() assert sim.stage.GetPrimAtPath("/World").IsValid() - assert sim.stage.GetPrimAtPath(sim.cfg.physics.physics_prim_path).IsValid() # type: ignore[union-attr] + assert sim.stage.GetPrimAtPath(sim.cfg.physics_prim_path).IsValid() # type: ignore[union-attr] """ @@ -351,7 +352,7 @@ def test_solver_type(solver_type): sim = SimulationContext(cfg) # obtain physics scene api from USD - physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics.physics_prim_path) + physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics_prim_path) physx_scene_api = PhysxSceneAPI(physics_scene_prim) # check solver type is set solver_type_str = "PGS" if solver_type == 0 else "TGS" @@ -362,7 +363,7 @@ def test_solver_type(solver_type): @pytest.mark.parametrize("use_fabric", [True, False]) def test_fabric_setting(use_fabric): """Test that fabric setting is properly set.""" - cfg = SimulationCfg(physics=PhysxCfg(use_fabric=use_fabric)) + cfg = SimulationCfg(use_fabric=use_fabric) sim = SimulationContext(cfg) # check fabric is enabled via physics setting @@ -375,11 +376,11 @@ def test_physics_dt(dt): """Test that physics time step is properly configured.""" from pxr.PhysxSchema import PhysxSceneAPI - cfg = SimulationCfg(physics=PhysxCfg(dt=dt)) + cfg = SimulationCfg(dt=dt) sim = SimulationContext(cfg) # obtain physics scene api from USD - physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics.physics_prim_path) + physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics_prim_path) physx_scene_api = PhysxSceneAPI(physics_scene_prim) # check physics dt physics_hz = physx_scene_api.GetTimeStepsPerSecondAttr().Get() @@ -393,11 +394,11 @@ def test_custom_gravity(gravity): """Test that gravity can be properly set.""" from pxr import UsdPhysics - cfg = SimulationCfg(physics=PhysxCfg(gravity=gravity)) + cfg = SimulationCfg(gravity=gravity) sim = SimulationContext(cfg) # obtain physics scene from USD - physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics.physics_prim_path) + physics_scene_prim = sim.stage.GetPrimAtPath(cfg.physics_prim_path) physics_scene = UsdPhysics.Scene(physics_scene_prim) gravity_dir, gravity_mag = ( @@ -405,7 +406,7 @@ def test_custom_gravity(gravity): physics_scene.GetGravityMagnitudeAttr().Get(), ) actual_gravity = np.array(gravity_dir) * gravity_mag - np.testing.assert_almost_equal(actual_gravity, cfg.physics.gravity, decimal=6) + np.testing.assert_almost_equal(actual_gravity, cfg.gravity, decimal=6) """ @@ -416,7 +417,7 @@ def test_custom_gravity(gravity): @pytest.mark.isaacsim_ci def test_timeline_callbacks_on_play(): """Test that timeline callbacks are triggered on play event.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create a simple scene @@ -478,7 +479,7 @@ def on_stop_callback(event): def test_timeline_callbacks_with_weakref(): """Test that timeline callbacks work correctly with weak references (similar to asset_base.py).""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create a simple scene @@ -565,7 +566,7 @@ def safe_callback(callback_name, event, obj_ref): @pytest.mark.isaacsim_ci def test_multiple_callbacks_on_same_event(): """Test that multiple callbacks can be registered for the same event.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create tracking for multiple callbacks @@ -617,7 +618,7 @@ def callback3(event): @pytest.mark.isaacsim_ci def test_callback_execution_order(): """Test that callbacks are executed in the correct order based on priority.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # track execution order @@ -667,7 +668,7 @@ def callback_high_priority(event): @pytest.mark.isaacsim_ci def test_callback_unsubscribe(): """Test that unsubscribing callbacks works correctly.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create callback counter @@ -710,7 +711,7 @@ def on_play_callback(event): @pytest.mark.isaacsim_ci def test_pause_event_callback(): """Test that pause event callbacks are triggered correctly.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create callback tracker @@ -754,7 +755,7 @@ def on_pause_callback(event): ) def test_isaac_event_triggered_on_reset(event_type): """Test that Isaac events are triggered during reset.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create simple scene @@ -789,7 +790,7 @@ def on_event(event): @pytest.mark.isaacsim_ci def test_isaac_event_prim_deletion(): """Test that PRIM_DELETION Isaac event is triggered when a prim is deleted.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create simple scene @@ -832,7 +833,7 @@ def on_prim_deletion(event): @pytest.mark.isaacsim_ci def test_isaac_event_timeline_stop(): """Test that TIMELINE_STOP Isaac event can be registered and triggered.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create callback tracker @@ -872,7 +873,7 @@ def on_timeline_stop(event): @pytest.mark.isaacsim_ci def test_isaac_event_callbacks_with_weakref(): """Test Isaac event callbacks with weak references (similar to asset_base.py pattern).""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create simple scene @@ -946,7 +947,7 @@ def safe_callback(callback_name, event, obj_ref): @pytest.mark.isaacsim_ci def test_multiple_isaac_event_callbacks(): """Test that multiple callbacks can be registered for the same Isaac event.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create simple scene @@ -1000,7 +1001,7 @@ def callback3(event): @pytest.mark.isaacsim_ci def test_exception_in_callback_on_reset(): """Test that exceptions stored during reset are raised.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create simple scene @@ -1026,7 +1027,7 @@ def failing_callback(event): @pytest.mark.isaacsim_ci def test_exception_in_callback_on_step(): """Test that exceptions stored during step are raised.""" - cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + cfg = SimulationCfg(dt=0.01) sim = SimulationContext(cfg) # create simple scene diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py index 7f2bdc9bc948..23a93f569344 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager.py @@ -525,7 +525,7 @@ def _load_fabric(cls) -> None: return settings = sim._carb_settings - use_fabric = cfg.use_fabric + use_fabric = sim.cfg.use_fabric ext_mgr = omni.kit.app.get_app().get_extension_manager() # enable/disable fabric extension diff --git a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py index bdb4f7cb27fc..d30252c78778 100644 --- a/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py +++ b/source/isaaclab_physx/isaaclab_physx/physics/physx_manager_cfg.py @@ -44,20 +44,6 @@ class PhysxCfg(PhysicsCfg): class_type: type[PhysicsManager] = PhysxManager """The class type of the PhysxManager.""" - physics_prim_path: str = "/physicsScene" - """The prim path where the USD PhysicsScene is created. Default is "/physicsScene".""" - - use_fabric: bool = True - """Enable/disable reading of physics buffers directly. Default is True. - - When running the simulation, updates in the states in the scene is normally synchronized with USD. - This leads to an overhead in reading the data and does not scale well with massive parallelization. - This flag allows disabling the synchronization and reading the data directly from the physics buffers. - - It is recommended to set this flag to :obj:`True` when running the simulation with a large number - of primitives in the scene. - """ - # ------------------------------------------------------------------ # Solver Settings # ------------------------------------------------------------------ diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py index 19685d654d05..d22412f94153 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_camera_env.py @@ -9,7 +9,6 @@ from collections.abc import Sequence import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg @@ -31,7 +30,7 @@ class CartpoleRGBCameraEnvCfg(DirectRLEnvCfg): action_scale = 100.0 # [N] # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) # robot robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py index e2a7dcc47738..f897b64f3ec9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cartpole/cartpole_env.py @@ -9,7 +9,6 @@ from collections.abc import Sequence import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg @@ -34,7 +33,7 @@ class CartpoleEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) # robot robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py index 23f71129ca8b..402409e9d35b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid/humanoid_env.py @@ -5,8 +5,6 @@ from __future__ import annotations -from isaaclab_physx.physics import PhysxCfg - import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg @@ -31,7 +29,7 @@ class HumanoidEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) terrain = TerrainImporterCfg( prim_path="/World/ground", terrain_type="plane", From a8176f9059513f4dd800d67b84ee129e503e385f Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Tue, 10 Feb 2026 15:51:00 -0800 Subject: [PATCH 2/7] fix doc --- docs/source/api/lab_physx/isaaclab_physx.assets.rst | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/docs/source/api/lab_physx/isaaclab_physx.assets.rst b/docs/source/api/lab_physx/isaaclab_physx.assets.rst index b462ccca1076..8613b86da96a 100644 --- a/docs/source/api/lab_physx/isaaclab_physx.assets.rst +++ b/docs/source/api/lab_physx/isaaclab_physx.assets.rst @@ -1,4 +1,5 @@ -isaaclab_physx.assets +isaaclab_physx.assets +===================== .. automodule:: isaaclab_physx.assets :noindex: From 6a60ae4afc404defba6e83892a44d8caeaad6f16 Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Tue, 10 Feb 2026 16:11:22 -0800 Subject: [PATCH 3/7] update more files --- scripts/benchmarks/benchmark_view_comparison.py | 5 +---- scripts/demos/bin_packing.py | 3 +-- scripts/demos/bipeds.py | 3 +-- scripts/demos/deformables.py | 3 +-- scripts/demos/hands.py | 3 +-- scripts/demos/markers.py | 3 +-- scripts/demos/multi_asset.py | 4 +--- scripts/demos/procedural_terrain.py | 3 +-- scripts/demos/quadcopter.py | 3 +-- scripts/demos/quadrupeds.py | 3 +-- scripts/demos/sensors/cameras.py | 5 +---- scripts/demos/sensors/contact_sensor.py | 3 +-- scripts/demos/sensors/frame_transformer_sensor.py | 3 +-- scripts/demos/sensors/imu_sensor.py | 3 +-- scripts/demos/sensors/multi_mesh_raycaster.py | 3 +-- .../demos/sensors/multi_mesh_raycaster_camera.py | 3 +-- scripts/demos/sensors/raycaster_sensor.py | 3 +-- scripts/tools/check_instanceable.py | 4 +--- scripts/tutorials/00_sim/create_empty.py | 3 +-- scripts/tutorials/00_sim/launch_app.py | 3 +-- scripts/tutorials/00_sim/log_time.py | 3 +-- scripts/tutorials/00_sim/spawn_prims.py | 3 +-- .../tutorials/04_sensors/add_sensors_on_robot.py | 3 +-- .../tutorials/04_sensors/run_frame_transformer.py | 3 +-- scripts/tutorials/05_controllers/run_diff_ik.py | 3 +-- scripts/tutorials/05_controllers/run_osc.py | 3 +-- .../isaaclab/sim/converters/mesh_converter.py | 2 +- source/isaaclab/setup.py | 2 +- .../isaaclab/test/app/test_non_headless_launch.py | 3 +-- source/isaaclab/test/assets/check_external_force.py | 3 +-- .../isaaclab/test/assets/check_fixed_base_assets.py | 3 +-- .../test/controllers/test_differential_ik.py | 3 +-- .../test/controllers/test_operational_space.py | 3 +-- source/isaaclab/test/devices/check_keyboard.py | 4 +--- .../isaaclab/test/envs/test_env_rendering_logic.py | 8 ++++---- .../test/managers/test_observation_manager.py | 3 +-- .../test/markers/check_markers_visibility.py | 3 +-- .../test/markers/test_visualization_markers.py | 3 +-- .../isaaclab/test/scene/check_interactive_scene.py | 3 +-- source/isaaclab/test/sensors/test_camera.py | 3 +-- .../sensors/test_multi_mesh_ray_caster_camera.py | 3 +-- .../test/sensors/test_multi_tiled_camera.py | 3 +-- .../isaaclab/test/sensors/test_ray_caster_camera.py | 3 +-- source/isaaclab/test/sensors/test_sensor_base.py | 3 +-- source/isaaclab/test/sensors/test_tiled_camera.py | 3 +-- source/isaaclab/test/sim/check_meshes.py | 3 +-- .../sim/test_build_simulation_context_headless.py | 7 ++----- .../test_build_simulation_context_nonheadless.py | 7 ++----- source/isaaclab/test/sim/test_mesh_converter.py | 3 +-- source/isaaclab/test/sim/test_mjcf_converter.py | 3 +-- source/isaaclab/test/sim/test_schemas.py | 3 +-- source/isaaclab/test/sim/test_spawn_from_files.py | 3 +-- source/isaaclab/test/sim/test_spawn_lights.py | 3 +-- source/isaaclab/test/sim/test_spawn_materials.py | 3 +-- source/isaaclab/test/sim/test_spawn_meshes.py | 3 +-- source/isaaclab/test/sim/test_spawn_sensors.py | 3 +-- source/isaaclab/test/sim/test_spawn_shapes.py | 3 +-- source/isaaclab/test/sim/test_spawn_wrappers.py | 3 +-- source/isaaclab/test/sim/test_urdf_converter.py | 3 +-- source/isaaclab/test/sim/test_views_xform_prim.py | 3 +-- .../visualization/check_scene_xr_visualization.py | 4 +--- .../test/sensors/test_visuotactile_sensor.py | 3 +-- .../test/sensors/check_contact_sensor.py | 3 +-- .../test/sensors/test_contact_sensor.py | 7 +++---- .../test/sensors/test_frame_transformer.py | 3 +-- source/isaaclab_physx/test/sensors/test_imu.py | 2 +- .../direct/allegro_hand/allegro_hand_env_cfg.py | 7 +------ .../isaaclab_tasks/direct/ant/ant_env.py | 4 +--- .../direct/anymal_c/anymal_c_env_cfg.py | 12 +----------- .../direct/automate/assembly_env_cfg.py | 11 +++++------ .../direct/automate/disassembly_env_cfg.py | 11 +++++------ .../cart_double_pendulum_env.py | 3 +-- .../direct/factory/factory_env_cfg.py | 11 +++++------ .../direct/franka_cabinet/franka_cabinet_env.py | 12 +----------- .../direct/humanoid_amp/humanoid_amp_env_cfg.py | 7 ++----- .../direct/quadcopter/quadcopter_env.py | 12 +----------- .../direct/shadow_hand/shadow_hand_env_cfg.py | 13 ++----------- .../shadow_hand_over/shadow_hand_over_env_cfg.py | 7 +------ .../deploy/gear_assembly/gear_assembly_env_cfg.py | 7 ++----- .../manipulation/inhand/inhand_env_cfg.py | 5 ----- 80 files changed, 101 insertions(+), 241 deletions(-) diff --git a/scripts/benchmarks/benchmark_view_comparison.py b/scripts/benchmarks/benchmark_view_comparison.py index 48465694360a..88b6a9eda3b5 100644 --- a/scripts/benchmarks/benchmark_view_comparison.py +++ b/scripts/benchmarks/benchmark_view_comparison.py @@ -69,7 +69,6 @@ import time import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sim.views import XformPrimView @@ -97,9 +96,7 @@ def benchmark_view(view_type: str, num_iterations: int) -> tuple[dict[str, float sim_utils.create_new_stage() # Create simulation context start_time = time.perf_counter() - sim_cfg = sim_utils.SimulationCfg( - device=args_cli.device, physics=PhysxCfg(dt=0.01, use_fabric=(view_type == "xform_fabric")) - ) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) stage = sim_utils.get_current_stage() diff --git a/scripts/demos/bin_packing.py b/scripts/demos/bin_packing.py index 48c6271a6171..b227e5b8b085 100644 --- a/scripts/demos/bin_packing.py +++ b/scripts/demos/bin_packing.py @@ -44,7 +44,6 @@ import math import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils @@ -328,7 +327,7 @@ def main() -> None: None: The function drives the simulation for its side-effects. """ # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) diff --git a/scripts/demos/bipeds.py b/scripts/demos/bipeds.py index 85b363fd74a7..bc557b745e68 100644 --- a/scripts/demos/bipeds.py +++ b/scripts/demos/bipeds.py @@ -33,7 +33,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -115,7 +114,7 @@ def run_simulator(sim: sim_utils.SimulationContext, robots: list[Articulation], def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.0, 0.0, 2.25], target=[0.0, 0.0, 1.0]) diff --git a/scripts/demos/deformables.py b/scripts/demos/deformables.py index 630a36f73c27..0ee4095dbf2c 100644 --- a/scripts/demos/deformables.py +++ b/scripts/demos/deformables.py @@ -36,7 +36,6 @@ import numpy as np import torch import tqdm -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import DeformableObject, DeformableObjectCfg @@ -179,7 +178,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Deformab def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([4.0, 4.0, 3.0], [0.5, 0.5, 0.0]) diff --git a/scripts/demos/hands.py b/scripts/demos/hands.py index 462b5c2bff43..195e87ae8399 100644 --- a/scripts/demos/hands.py +++ b/scripts/demos/hands.py @@ -34,7 +34,6 @@ import numpy as np import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -144,7 +143,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.2, 0.5]) diff --git a/scripts/demos/markers.py b/scripts/demos/markers.py index 834bc9a7d264..527474280e7f 100644 --- a/scripts/demos/markers.py +++ b/scripts/demos/markers.py @@ -32,7 +32,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg @@ -95,7 +94,7 @@ def define_markers() -> VisualizationMarkers: def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([0.0, 18.0, 12.0], [0.0, 3.0, 0.0]) diff --git a/scripts/demos/multi_asset.py b/scripts/demos/multi_asset.py index 825e1e68ee49..4dc503df9536 100644 --- a/scripts/demos/multi_asset.py +++ b/scripts/demos/multi_asset.py @@ -37,8 +37,6 @@ import random -from isaaclab_physx.physics import PhysxCfg - from pxr import Gf, Sdf import isaaclab.sim as sim_utils @@ -277,7 +275,7 @@ def run_simulator(sim: SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) diff --git a/scripts/demos/procedural_terrain.py b/scripts/demos/procedural_terrain.py index c5b48ff6ae22..093b1145f201 100644 --- a/scripts/demos/procedural_terrain.py +++ b/scripts/demos/procedural_terrain.py @@ -68,7 +68,6 @@ import random import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBase @@ -155,7 +154,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, AssetBas def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[5.0, 5.0, 5.0], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/quadcopter.py b/scripts/demos/quadcopter.py index 8f8f2d0677fc..e1e0ddbbc7f4 100644 --- a/scripts/demos/quadcopter.py +++ b/scripts/demos/quadcopter.py @@ -33,7 +33,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -48,7 +47,7 @@ def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[0.5, 0.5, 1.0], target=[0.0, 0.0, 0.5]) diff --git a/scripts/demos/quadrupeds.py b/scripts/demos/quadrupeds.py index 14d78a509cca..b9935de30dab 100644 --- a/scripts/demos/quadrupeds.py +++ b/scripts/demos/quadrupeds.py @@ -34,7 +34,6 @@ import numpy as np import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -171,7 +170,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01))) + sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01)) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) # design scene diff --git a/scripts/demos/sensors/cameras.py b/scripts/demos/sensors/cameras.py index e5b57ec4f188..1edf3cab17f7 100644 --- a/scripts/demos/sensors/cameras.py +++ b/scripts/demos/sensors/cameras.py @@ -42,7 +42,6 @@ import matplotlib.pyplot as plt import numpy as np import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg @@ -281,9 +280,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg( - device=args_cli.device, physics=PhysxCfg(dt=0.005, use_fabric=not args_cli.disable_fabric) - ) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005, use_fabric=not args_cli.disable_fabric) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/contact_sensor.py b/scripts/demos/sensors/contact_sensor.py index 05dfce51a787..cef0f531b523 100644 --- a/scripts/demos/sensors/contact_sensor.py +++ b/scripts/demos/sensors/contact_sensor.py @@ -24,7 +24,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg, RigidObjectCfg @@ -155,7 +154,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/frame_transformer_sensor.py b/scripts/demos/sensors/frame_transformer_sensor.py index 5a0848bea72f..643e8c10c2c2 100644 --- a/scripts/demos/sensors/frame_transformer_sensor.py +++ b/scripts/demos/sensors/frame_transformer_sensor.py @@ -22,7 +22,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg, RigidObjectCfg @@ -149,7 +148,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/imu_sensor.py b/scripts/demos/sensors/imu_sensor.py index e86e02630e30..e022b51d79d1 100644 --- a/scripts/demos/sensors/imu_sensor.py +++ b/scripts/demos/sensors/imu_sensor.py @@ -24,7 +24,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -122,7 +121,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/multi_mesh_raycaster.py b/scripts/demos/sensors/multi_mesh_raycaster.py index fa6fbb684966..1e285e17fd86 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster.py +++ b/scripts/demos/sensors/multi_mesh_raycaster.py @@ -47,7 +47,6 @@ import random import torch -from isaaclab_physx.physics import PhysxCfg import omni.usd from pxr import Gf, Sdf @@ -278,7 +277,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/multi_mesh_raycaster_camera.py b/scripts/demos/sensors/multi_mesh_raycaster_camera.py index 43e601583e55..dd13ab0901aa 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster_camera.py +++ b/scripts/demos/sensors/multi_mesh_raycaster_camera.py @@ -47,7 +47,6 @@ import random import torch -from isaaclab_physx.physics import PhysxCfg import omni.usd from pxr import Gf, Sdf @@ -304,7 +303,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/raycaster_sensor.py b/scripts/demos/sensors/raycaster_sensor.py index 962e9d56470d..753c077b3f46 100644 --- a/scripts/demos/sensors/raycaster_sensor.py +++ b/scripts/demos/sensors/raycaster_sensor.py @@ -23,7 +23,6 @@ import numpy as np import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -140,7 +139,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tools/check_instanceable.py b/scripts/tools/check_instanceable.py index 73be99c66a7a..d9ce51497d1a 100644 --- a/scripts/tools/check_instanceable.py +++ b/scripts/tools/check_instanceable.py @@ -64,8 +64,6 @@ """Rest everything follows.""" -from isaaclab_physx.physics import PhysxCfg - from isaacsim.core.cloner import GridCloner import isaaclab.sim as sim_utils @@ -80,7 +78,7 @@ def main(): if not check_file_path(args_cli.input): raise ValueError(f"Invalid file path: {args_cli.input}") # Load kit helper - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=0.01))) + sim = SimulationContext(SimulationCfg(dt=0.01)) # get stage handle stage = sim_utils.get_current_stage() diff --git a/scripts/tutorials/00_sim/create_empty.py b/scripts/tutorials/00_sim/create_empty.py index ff96d84c1f1a..18c2eeae938d 100644 --- a/scripts/tutorials/00_sim/create_empty.py +++ b/scripts/tutorials/00_sim/create_empty.py @@ -31,7 +31,6 @@ """Rest everything follows.""" -from isaaclab_physx.physics import PhysxCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -40,7 +39,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + sim_cfg = SimulationCfg(dt=0.01) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/00_sim/launch_app.py b/scripts/tutorials/00_sim/launch_app.py index 5b4e4b412201..3a3c1cab4fd4 100644 --- a/scripts/tutorials/00_sim/launch_app.py +++ b/scripts/tutorials/00_sim/launch_app.py @@ -41,7 +41,6 @@ """Rest everything follows.""" -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils @@ -72,7 +71,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) diff --git a/scripts/tutorials/00_sim/log_time.py b/scripts/tutorials/00_sim/log_time.py index 5934c9b387db..61bb74024679 100644 --- a/scripts/tutorials/00_sim/log_time.py +++ b/scripts/tutorials/00_sim/log_time.py @@ -34,7 +34,6 @@ """Rest everything follows.""" -from isaaclab_physx.physics import PhysxCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -55,7 +54,7 @@ def main(): print(f"[INFO] Logging experiment to directory: {log_dir_path}") # Initialize the simulation context - sim_cfg = SimulationCfg(physics=PhysxCfg(dt=0.01)) + sim_cfg = SimulationCfg(dt=0.01) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/00_sim/spawn_prims.py b/scripts/tutorials/00_sim/spawn_prims.py index 3b15b2d6e527..6c8046dc77a1 100644 --- a/scripts/tutorials/00_sim/spawn_prims.py +++ b/scripts/tutorials/00_sim/spawn_prims.py @@ -31,7 +31,6 @@ """Rest everything follows.""" -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR @@ -92,7 +91,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) diff --git a/scripts/tutorials/04_sensors/add_sensors_on_robot.py b/scripts/tutorials/04_sensors/add_sensors_on_robot.py index f64c38751f86..5854e526673e 100644 --- a/scripts/tutorials/04_sensors/add_sensors_on_robot.py +++ b/scripts/tutorials/04_sensors/add_sensors_on_robot.py @@ -40,7 +40,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg @@ -158,7 +157,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/04_sensors/run_frame_transformer.py b/scripts/tutorials/04_sensors/run_frame_transformer.py index 748b26ed699a..f4d64f94edf4 100644 --- a/scripts/tutorials/04_sensors/run_frame_transformer.py +++ b/scripts/tutorials/04_sensors/run_frame_transformer.py @@ -35,7 +35,6 @@ import math import torch -from isaaclab_physx.physics import PhysxCfg import isaacsim.util.debug_draw._debug_draw as omni_debug_draw @@ -166,7 +165,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/05_controllers/run_diff_ik.py b/scripts/tutorials/05_controllers/run_diff_ik.py index 1a0e83c601fc..3f3da9ffe204 100644 --- a/scripts/tutorials/05_controllers/run_diff_ik.py +++ b/scripts/tutorials/05_controllers/run_diff_ik.py @@ -38,7 +38,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -191,7 +190,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/05_controllers/run_osc.py b/scripts/tutorials/05_controllers/run_osc.py index 283e17d84fa0..e8de66dc2d98 100644 --- a/scripts/tutorials/05_controllers/run_osc.py +++ b/scripts/tutorials/05_controllers/run_osc.py @@ -37,7 +37,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, AssetBaseCfg @@ -463,7 +462,7 @@ def convert_to_task_frame(osc: OperationalSpaceController, command: torch.tensor def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py index ad65f7270af5..6d2df6285e05 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py @@ -232,7 +232,7 @@ async def _convert_mesh_to_usd(in_file: str, out_file: str, load_materials: bool # Merge all meshes into one converter_context.merge_all_meshes = True # Sets world units to meters, this will also scale asset if it's centimeters model. - # This does not work right now :(, so we need to scale the mesh manually + # This does not work right now :( so we need to scale the mesh manually converter_context.use_meter_as_world_unit = True converter_context.baking_scales = True # Uses double precision for all transform ops. diff --git a/source/isaaclab/setup.py b/source/isaaclab/setup.py index 360b9771f982..41089fa876b6 100644 --- a/source/isaaclab/setup.py +++ b/source/isaaclab/setup.py @@ -44,7 +44,7 @@ "pytest-mock", "junitparser", "coverage==7.6.1", - "flatdict==4.0.1", + "flatdict==4.0.0", "flaky", "packaging", ] diff --git a/source/isaaclab/test/app/test_non_headless_launch.py b/source/isaaclab/test/app/test_non_headless_launch.py index dedf6c5686e6..8fc8a051ae38 100644 --- a/source/isaaclab/test/app/test_non_headless_launch.py +++ b/source/isaaclab/test/app/test_non_headless_launch.py @@ -20,7 +20,6 @@ """Rest everything follows.""" -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -53,7 +52,7 @@ def run_simulator( @pytest.mark.isaacsim_ci def test_non_headless_launch(): # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # design scene scene_cfg = SensorsSceneCfg(num_envs=1, env_spacing=2.0) diff --git a/source/isaaclab/test/assets/check_external_force.py b/source/isaaclab/test/assets/check_external_force.py index e88131b1b323..f038b907a1f0 100644 --- a/source/isaaclab/test/assets/check_external_force.py +++ b/source/isaaclab/test/assets/check_external_force.py @@ -37,7 +37,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -53,7 +52,7 @@ def main(): """Main function.""" # Load kit helper - sim = SimulationContext(sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005))) + sim = SimulationContext(sim_utils.SimulationCfg(dt=0.005)) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/assets/check_fixed_base_assets.py b/source/isaaclab/test/assets/check_fixed_base_assets.py index 1f5d25fcbceb..c62c5a3334da 100644 --- a/source/isaaclab/test/assets/check_fixed_base_assets.py +++ b/source/isaaclab/test/assets/check_fixed_base_assets.py @@ -34,7 +34,6 @@ import numpy as np import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation @@ -144,7 +143,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01))) + sim = sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01)) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) # design scene diff --git a/source/isaaclab/test/controllers/test_differential_ik.py b/source/isaaclab/test/controllers/test_differential_ik.py index 00260abccb9d..1dc278059461 100644 --- a/source/isaaclab/test/controllers/test_differential_ik.py +++ b/source/isaaclab/test/controllers/test_differential_ik.py @@ -14,7 +14,6 @@ import pytest import torch -from isaaclab_physx.physics import PhysxCfg from isaacsim.core.cloner import GridCloner @@ -44,7 +43,7 @@ def sim(): # Constants num_envs = 1 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # TODO: Remove this once we have a better way to handle this. sim._app_control_on_stop_handle = None diff --git a/source/isaaclab/test/controllers/test_operational_space.py b/source/isaaclab/test/controllers/test_operational_space.py index f771624c0b64..438b3acd2b75 100644 --- a/source/isaaclab/test/controllers/test_operational_space.py +++ b/source/isaaclab/test/controllers/test_operational_space.py @@ -15,7 +15,6 @@ import pytest import torch from flaky import flaky -from isaaclab_physx.physics import PhysxCfg from isaacsim.core.cloner import GridCloner @@ -49,7 +48,7 @@ def sim(): # Constants num_envs = 16 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # TODO: Remove this once we have a better way to handle this. sim._app_control_on_stop_handle = None diff --git a/source/isaaclab/test/devices/check_keyboard.py b/source/isaaclab/test/devices/check_keyboard.py index 69ce1e9e89d3..c1a8b07bef82 100644 --- a/source/isaaclab/test/devices/check_keyboard.py +++ b/source/isaaclab/test/devices/check_keyboard.py @@ -23,8 +23,6 @@ import ctypes -from isaaclab_physx.physics import PhysxCfg - from isaaclab.devices import Se3Keyboard, Se3KeyboardCfg from isaaclab.sim import SimulationCfg, SimulationContext @@ -42,7 +40,7 @@ def quit_cb(): def main(): # Load kit helper - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=0.01))) + sim = SimulationContext(SimulationCfg(dt=0.01)) # Create teleoperation interface teleop_interface = Se3Keyboard(Se3KeyboardCfg(pos_sensitivity=0.1, rot_sensitivity=0.1)) diff --git a/source/isaaclab/test/envs/test_env_rendering_logic.py b/source/isaaclab/test/envs/test_env_rendering_logic.py index 1fdfbbbb244b..9c407893f349 100644 --- a/source/isaaclab/test/envs/test_env_rendering_logic.py +++ b/source/isaaclab/test/envs/test_env_rendering_logic.py @@ -15,7 +15,7 @@ import pytest import torch -from isaaclab_physx.physics import IsaacEvents, PhysxCfg +from isaaclab_physx.physics import IsaacEvents from isaaclab_physx.visualizers import RenderMode import isaaclab.sim as sim_utils @@ -48,7 +48,7 @@ class EnvCfg(ManagerBasedEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics=PhysxCfg(dt=0.005)) + sim: SimulationCfg = SimulationCfg(render_interval=render_interval, dt=0.005) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -65,7 +65,7 @@ class EnvCfg(ManagerBasedRLEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics=PhysxCfg(dt=0.005)) + sim: SimulationCfg = SimulationCfg(render_interval=render_interval, dt=0.005) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -86,7 +86,7 @@ class EnvCfg(DirectRLEnvCfg): action_space: int = 0 observation_space: int = 0 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(render_interval=render_interval, physics=PhysxCfg(dt=0.005)) + sim: SimulationCfg = SimulationCfg(render_interval=render_interval, dt=0.005) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) class Env(DirectRLEnv): diff --git a/source/isaaclab/test/managers/test_observation_manager.py b/source/isaaclab/test/managers/test_observation_manager.py index b135b0ecce5e..1ab6489c23ef 100644 --- a/source/isaaclab/test/managers/test_observation_manager.py +++ b/source/isaaclab/test/managers/test_observation_manager.py @@ -20,7 +20,6 @@ import pytest import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.managers import ( @@ -108,7 +107,7 @@ def setup_env(): num_envs = 20 device = "cuda:0" # set up sim - sim_cfg = sim_utils.SimulationCfg(device=device, physics=PhysxCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(device=device, dt=dt) sim = sim_utils.SimulationContext(sim_cfg) # create dummy environment env = namedtuple("ManagerBasedEnv", ["num_envs", "device", "data", "dt", "sim"])( diff --git a/source/isaaclab/test/markers/check_markers_visibility.py b/source/isaaclab/test/markers/check_markers_visibility.py index 40b1d85a15a7..b933a705b790 100644 --- a/source/isaaclab/test/markers/check_markers_visibility.py +++ b/source/isaaclab/test/markers/check_markers_visibility.py @@ -38,7 +38,6 @@ """Rest everything follows.""" -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg, AssetBaseCfg @@ -131,7 +130,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/markers/test_visualization_markers.py b/source/isaaclab/test/markers/test_visualization_markers.py index 096cf2210ad9..ebc183b804b8 100644 --- a/source/isaaclab/test/markers/test_visualization_markers.py +++ b/source/isaaclab/test/markers/test_visualization_markers.py @@ -14,7 +14,6 @@ import pytest import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.markers import VisualizationMarkers, VisualizationMarkersCfg @@ -32,7 +31,7 @@ def sim(): # Open a new stage sim_utils.create_new_stage() # Load kit helper - sim_context = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim_context = SimulationContext(SimulationCfg(dt=dt)) yield sim_context # Cleanup sim_context._disable_app_control_on_stop_handle = True # prevent timeout diff --git a/source/isaaclab/test/scene/check_interactive_scene.py b/source/isaaclab/test/scene/check_interactive_scene.py index f7824c415768..7c6fdfb1a894 100644 --- a/source/isaaclab/test/scene/check_interactive_scene.py +++ b/source/isaaclab/test/scene/check_interactive_scene.py @@ -27,7 +27,6 @@ """Rest everything follows.""" -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import AssetBaseCfg @@ -82,7 +81,7 @@ def main(): """Main function.""" # Load kit helper - sim = SimulationContext(sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005))) + sim = SimulationContext(sim_utils.SimulationCfg(dt=0.005)) # Set main camera sim.set_camera_view(eye=[5, 5, 5], target=[0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/sensors/test_camera.py b/source/isaaclab/test/sensors/test_camera.py index e42add9ff937..76875d76c365 100644 --- a/source/isaaclab/test/sensors/test_camera.py +++ b/source/isaaclab/test/sensors/test_camera.py @@ -23,7 +23,6 @@ import pytest import scipy.spatial.transform as tf import torch -from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf, Usd, UsdGeom @@ -63,7 +62,7 @@ def setup() -> tuple[sim_utils.SimulationContext, CameraCfg, float]: # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(dt=dt) sim = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py index 32342c7238b9..688e20086ff9 100644 --- a/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_multi_mesh_ray_caster_camera.py @@ -21,7 +21,6 @@ import numpy as np import pytest import torch -from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf @@ -50,7 +49,7 @@ def setup_simulation(): # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(dt=dt) sim: sim_utils.SimulationContext = sim_utils.SimulationContext(sim_cfg) # Ground-plane mesh = make_plane(size=(100, 100), height=0.0, center_zero=True) diff --git a/source/isaaclab/test/sensors/test_multi_tiled_camera.py b/source/isaaclab/test/sensors/test_multi_tiled_camera.py index 5d6b2f820a18..9c922ca6d1de 100644 --- a/source/isaaclab/test/sensors/test_multi_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_multi_tiled_camera.py @@ -22,7 +22,6 @@ import pytest import torch from flaky import flaky -from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf, UsdGeom @@ -50,7 +49,7 @@ def setup_camera(): # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(dt=dt) sim = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sensors/test_ray_caster_camera.py b/source/isaaclab/test/sensors/test_ray_caster_camera.py index 009cd2e0fbcc..80fa4d03a1ee 100644 --- a/source/isaaclab/test/sensors/test_ray_caster_camera.py +++ b/source/isaaclab/test/sensors/test_ray_caster_camera.py @@ -21,7 +21,6 @@ import numpy as np import pytest import torch -from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf @@ -70,7 +69,7 @@ def setup() -> tuple[sim_utils.SimulationContext, RayCasterCameraCfg, float]: # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(dt=dt) sim = sim_utils.SimulationContext(sim_cfg) # Ground-plane with visual material for RTX rendering compatibility mesh = make_plane(size=(100, 100), height=0.0, center_zero=True) diff --git a/source/isaaclab/test/sensors/test_sensor_base.py b/source/isaaclab/test/sensors/test_sensor_base.py index 12c9236bf288..207bbd5e12c8 100644 --- a/source/isaaclab/test/sensors/test_sensor_base.py +++ b/source/isaaclab/test/sensors/test_sensor_base.py @@ -19,7 +19,6 @@ import pytest import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sensors import SensorBase, SensorBaseCfg @@ -94,7 +93,7 @@ def create_dummy_sensor(request, device): # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=device, physics=PhysxCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(device=device, dt=dt) sim = sim_utils.SimulationContext(sim_cfg) # create sensor diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index e97e2188be9e..f9c6fb5194fa 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -21,7 +21,6 @@ import numpy as np import pytest import torch -from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep from pxr import Gf, UsdGeom @@ -51,7 +50,7 @@ def setup_camera(device) -> tuple[sim_utils.SimulationContext, TiledCameraCfg, f # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=device, physics=PhysxCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(device=device, dt=dt) sim: sim_utils.SimulationContext = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sim/check_meshes.py b/source/isaaclab/test/sim/check_meshes.py index f79ac4a30a8b..705677281d3c 100644 --- a/source/isaaclab/test/sim/check_meshes.py +++ b/source/isaaclab/test/sim/check_meshes.py @@ -40,7 +40,6 @@ import numpy as np import torch import tqdm -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils @@ -142,7 +141,7 @@ def design_scene(): def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.01)) + sim_cfg = sim_utils.SimulationCfg(dt=0.01) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([8.0, 8.0, 6.0], [0.0, 0.0, 0.0]) diff --git a/source/isaaclab/test/sim/test_build_simulation_context_headless.py b/source/isaaclab/test/sim/test_build_simulation_context_headless.py index 332b40d84718..ed1ba3c788f0 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_headless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_headless.py @@ -76,7 +76,6 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light @pytest.mark.isaacsim_ci def test_build_simulation_context_cfg(): """Test that the simulation context is built with the correct cfg and values don't get overridden.""" - from isaaclab_physx.physics import PhysxCfg dt = 0.001 # Non-standard gravity @@ -85,10 +84,8 @@ def test_build_simulation_context_cfg(): cfg = SimulationCfg( device=device, - physics=PhysxCfg( - gravity=gravity, - dt=dt, - ), + gravity=gravity, + dt=dt, ) with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: diff --git a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py index e1958ab5b839..3d1913366753 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py @@ -71,7 +71,6 @@ def test_build_simulation_context_auto_add_lighting(add_lighting, auto_add_light def test_build_simulation_context_cfg(): """Test that the simulation context is built with the correct cfg and values don't get overridden.""" - from isaaclab_physx.physics import PhysxCfg dt = 0.001 # Non-standard gravity @@ -80,10 +79,8 @@ def test_build_simulation_context_cfg(): cfg = SimulationCfg( device=device, - physics=PhysxCfg( - gravity=gravity, - dt=dt, - ), + gravity=gravity, + dt=dt, ) with build_simulation_context(sim_cfg=cfg, gravity_enabled=False, dt=0.01, device="cpu") as sim: diff --git a/source/isaaclab/test/sim/test_mesh_converter.py b/source/isaaclab/test/sim/test_mesh_converter.py index e08d59f82a8e..94910bc2e031 100644 --- a/source/isaaclab/test/sim/test_mesh_converter.py +++ b/source/isaaclab/test/sim/test_mesh_converter.py @@ -18,7 +18,6 @@ import tempfile import pytest -from isaaclab_physx.physics import PhysxCfg import omni from pxr import UsdGeom, UsdPhysics @@ -67,7 +66,7 @@ def sim(): # Simulation time-step dt = 0.01 # Load kit helper - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) yield sim # stop simulation sim.stop() diff --git a/source/isaaclab/test/sim/test_mjcf_converter.py b/source/isaaclab/test/sim/test_mjcf_converter.py index 675fb878eaca..0233dcc9c574 100644 --- a/source/isaaclab/test/sim/test_mjcf_converter.py +++ b/source/isaaclab/test/sim/test_mjcf_converter.py @@ -15,7 +15,6 @@ import os import pytest -from isaaclab_physx.physics import PhysxCfg from isaacsim.core.utils.extensions import enable_extension, get_extension_path_from_name @@ -32,7 +31,7 @@ def test_setup_teardown(): # Setup: Create simulation context dt = 0.01 - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) # Setup: Create MJCF config enable_extension("isaacsim.asset.importer.mjcf") diff --git a/source/isaaclab/test/sim/test_schemas.py b/source/isaaclab/test/sim/test_schemas.py index 8686e93d4158..f8b341f693c4 100644 --- a/source/isaaclab/test/sim/test_schemas.py +++ b/source/isaaclab/test/sim/test_schemas.py @@ -15,7 +15,6 @@ import math import pytest -from isaaclab_physx.physics import PhysxCfg from pxr import UsdPhysics @@ -34,7 +33,7 @@ def setup_simulation(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) # Set some default values for test arti_cfg = schemas.ArticulationRootPropertiesCfg( enabled_self_collisions=False, diff --git a/source/isaaclab/test/sim/test_spawn_from_files.py b/source/isaaclab/test/sim/test_spawn_from_files.py index 787c17196805..ccfef35837c5 100644 --- a/source/isaaclab/test/sim/test_spawn_from_files.py +++ b/source/isaaclab/test/sim/test_spawn_from_files.py @@ -13,7 +13,6 @@ """Rest everything follows.""" import pytest -from isaaclab_physx.physics import PhysxCfg from packaging.version import Version import omni.kit.app @@ -32,7 +31,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) # Wait for spawning sim_utils.update_stage() diff --git a/source/isaaclab/test/sim/test_spawn_lights.py b/source/isaaclab/test/sim/test_spawn_lights.py index 8bda2100d9e7..94add58bc11b 100644 --- a/source/isaaclab/test/sim/test_spawn_lights.py +++ b/source/isaaclab/test/sim/test_spawn_lights.py @@ -14,7 +14,6 @@ import pytest -from isaaclab_physx.physics import PhysxCfg from pxr import Usd, UsdLux @@ -31,7 +30,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) # Wait for spawning sim_utils.update_stage() diff --git a/source/isaaclab/test/sim/test_spawn_materials.py b/source/isaaclab/test/sim/test_spawn_materials.py index 9f462381f22f..1e43450c5bbc 100644 --- a/source/isaaclab/test/sim/test_spawn_materials.py +++ b/source/isaaclab/test/sim/test_spawn_materials.py @@ -14,7 +14,6 @@ import pytest -from isaaclab_physx.physics import PhysxCfg from pxr import UsdPhysics, UsdShade @@ -28,7 +27,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) sim_utils.update_stage() yield sim sim.stop() diff --git a/source/isaaclab/test/sim/test_spawn_meshes.py b/source/isaaclab/test/sim/test_spawn_meshes.py index 60e3bd83e3ee..ae1a5402608f 100644 --- a/source/isaaclab/test/sim/test_spawn_meshes.py +++ b/source/isaaclab/test/sim/test_spawn_meshes.py @@ -14,7 +14,6 @@ import pytest -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -28,7 +27,7 @@ def sim(): # Simulation time-step dt = 0.1 # Load kit helper - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) # Wait for spawning sim_utils.update_stage() yield sim diff --git a/source/isaaclab/test/sim/test_spawn_sensors.py b/source/isaaclab/test/sim/test_spawn_sensors.py index e4be4a421326..d9f58b98dc75 100644 --- a/source/isaaclab/test/sim/test_spawn_sensors.py +++ b/source/isaaclab/test/sim/test_spawn_sensors.py @@ -14,7 +14,6 @@ import pytest -from isaaclab_physx.physics import PhysxCfg from pxr import Usd @@ -29,7 +28,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) sim_utils.update_stage() yield sim sim.stop() diff --git a/source/isaaclab/test/sim/test_spawn_shapes.py b/source/isaaclab/test/sim/test_spawn_shapes.py index d6e42d2961f5..71590c76e2ad 100644 --- a/source/isaaclab/test/sim/test_spawn_shapes.py +++ b/source/isaaclab/test/sim/test_spawn_shapes.py @@ -13,7 +13,6 @@ """Rest everything follows.""" import pytest -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -24,7 +23,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) sim_utils.update_stage() yield sim sim._disable_app_control_on_stop_handle = True # prevent timeout diff --git a/source/isaaclab/test/sim/test_spawn_wrappers.py b/source/isaaclab/test/sim/test_spawn_wrappers.py index 575bfcbf327c..1791f5f9b474 100644 --- a/source/isaaclab/test/sim/test_spawn_wrappers.py +++ b/source/isaaclab/test/sim/test_spawn_wrappers.py @@ -14,7 +14,6 @@ import pytest -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.sim import SimulationCfg, SimulationContext @@ -26,7 +25,7 @@ def sim(): """Create a simulation context.""" sim_utils.create_new_stage() dt = 0.1 - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) sim_utils.update_stage() yield sim sim.stop() diff --git a/source/isaaclab/test/sim/test_urdf_converter.py b/source/isaaclab/test/sim/test_urdf_converter.py index 2fae220259c8..6e0fe50e045b 100644 --- a/source/isaaclab/test/sim/test_urdf_converter.py +++ b/source/isaaclab/test/sim/test_urdf_converter.py @@ -16,7 +16,6 @@ import numpy as np import pytest -from isaaclab_physx.physics import PhysxCfg from packaging.version import Version import omni.kit.app @@ -54,7 +53,7 @@ def sim_config(): # Simulation time-step dt = 0.01 # Load kit helper - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=dt))) + sim = SimulationContext(SimulationCfg(dt=dt)) yield sim, config # Teardown sim._disable_app_control_on_stop_handle = True # prevent timeout diff --git a/source/isaaclab/test/sim/test_views_xform_prim.py b/source/isaaclab/test/sim/test_views_xform_prim.py index afa8a53f5055..ee321cd3a5b7 100644 --- a/source/isaaclab/test/sim/test_views_xform_prim.py +++ b/source/isaaclab/test/sim/test_views_xform_prim.py @@ -20,7 +20,6 @@ except (ModuleNotFoundError, ImportError): _IsaacSimXformPrimView = None -from isaaclab_physx.physics import PhysxCfg # noqa: E402 import isaaclab.sim as sim_utils # noqa: E402 from isaaclab.sim.views import XformPrimView as XformPrimView # noqa: E402 @@ -75,7 +74,7 @@ def _prim_type_for_backend(backend: str) -> str: def _create_view(pattern: str, device: str, backend: str) -> XformPrimView: """Create an XformPrimView for the requested backend.""" if backend == "fabric": - sim_utils.SimulationContext(sim_utils.SimulationCfg(device=device, physics=PhysxCfg(dt=0.01, use_fabric=True))) + sim_utils.SimulationContext(sim_utils.SimulationCfg(device=device, dt=0.01, use_fabric=True)) return XformPrimView(pattern, device=device) diff --git a/source/isaaclab/test/visualization/check_scene_xr_visualization.py b/source/isaaclab/test/visualization/check_scene_xr_visualization.py index ed5c4ca42ed9..b03fa9e88bd2 100644 --- a/source/isaaclab/test/visualization/check_scene_xr_visualization.py +++ b/source/isaaclab/test/visualization/check_scene_xr_visualization.py @@ -37,8 +37,6 @@ import time from typing import Any -from isaaclab_physx.physics import PhysxCfg - from pxr import Gf import isaaclab.sim as sim_utils @@ -243,7 +241,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(dt=0.005) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=(8, 0, 4), target=(0.0, 0.0, 0.0)) diff --git a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py index ee5b5beb8af2..227fbf851963 100644 --- a/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py +++ b/source/isaaclab_contrib/test/sensors/test_visuotactile_sensor.py @@ -19,7 +19,6 @@ import pytest import torch -from isaaclab_physx.physics import PhysxCfg import omni.replicator.core as rep @@ -125,7 +124,7 @@ def setup(sensor_type: str = "cube"): dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(physics=PhysxCfg(dt=dt)) + sim_cfg = sim_utils.SimulationCfg(dt=dt) sim = sim_utils.SimulationContext(sim_cfg) # Ground-plane diff --git a/source/isaaclab_physx/test/sensors/check_contact_sensor.py b/source/isaaclab_physx/test/sensors/check_contact_sensor.py index 8ddbfa889648..b4fe5f555dc7 100644 --- a/source/isaaclab_physx/test/sensors/check_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/check_contact_sensor.py @@ -35,7 +35,6 @@ """Rest everything follows.""" import torch -from isaaclab_physx.physics import PhysxCfg from isaacsim.core.cloner import GridCloner @@ -75,7 +74,7 @@ def main(): """Spawns the ANYmal robot and clones it using Isaac Sim Cloner API.""" # Load kit helper - sim = SimulationContext(SimulationCfg(physics=PhysxCfg(dt=0.005))) + sim = SimulationContext(SimulationCfg(dt=0.005)) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/source/isaaclab_physx/test/sensors/test_contact_sensor.py b/source/isaaclab_physx/test/sensors/test_contact_sensor.py index d4b1891d550b..b296f286a0e5 100644 --- a/source/isaaclab_physx/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/test_contact_sensor.py @@ -20,7 +20,6 @@ import pytest import torch from flaky import flaky -from isaaclab_physx.physics import PhysxCfg import carb from pxr import PhysxSchema @@ -453,7 +452,7 @@ def test_friction_reporting(setup_simulation, grav_dir): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(device=device, physics=PhysxCfg(dt=sim_dt, gravity=grav_dir)) + sim_cfg = SimulationCfg(device=device, dt=sim_dt, gravity=grav_dir) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None @@ -506,7 +505,7 @@ def test_invalid_prim_paths_config(setup_simulation): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(device=device, physics=PhysxCfg(dt=sim_dt)) + sim_cfg = SimulationCfg(device=device, dt=sim_dt) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None @@ -540,7 +539,7 @@ def test_invalid_max_contact_points_config(setup_simulation): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(device=device, physics=PhysxCfg(dt=sim_dt)) + sim_cfg = SimulationCfg(device=device, dt=sim_dt) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None diff --git a/source/isaaclab_physx/test/sensors/test_frame_transformer.py b/source/isaaclab_physx/test/sensors/test_frame_transformer.py index f3847333c7eb..f7aa63a9b610 100644 --- a/source/isaaclab_physx/test/sensors/test_frame_transformer.py +++ b/source/isaaclab_physx/test/sensors/test_frame_transformer.py @@ -17,7 +17,6 @@ import pytest import scipy.spatial.transform as tf import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils import isaaclab.utils.math as math_utils @@ -75,7 +74,7 @@ class MySceneCfg(InteractiveSceneCfg): @pytest.fixture def sim(): """Create a simulation context.""" - sim_cfg = sim_utils.SimulationCfg(device="cpu", physics=PhysxCfg(dt=0.005)) + sim_cfg = sim_utils.SimulationCfg(device="cpu", dt=0.005) with sim_utils.build_simulation_context(sim_cfg=sim_cfg) as sim: sim._app_control_on_stop_handle = None # Set main camera diff --git a/source/isaaclab_physx/test/sensors/test_imu.py b/source/isaaclab_physx/test/sensors/test_imu.py index 2be9ced8a4d5..62f9a75e6dfc 100644 --- a/source/isaaclab_physx/test/sensors/test_imu.py +++ b/source/isaaclab_physx/test/sensors/test_imu.py @@ -203,7 +203,7 @@ def __post_init__(self): def setup_sim(): """Create a simulation context and scene.""" sim_cfg = sim_utils.SimulationCfg( - physics=PhysxCfg(dt=0.001, solver_type=0) + dt=0.001, physics=PhysxCfg(solver_type=0) ) # 0: PGS, 1: TGS --> use PGS for more accurate results with sim_utils.build_simulation_context(sim_cfg=sim_cfg) as sim: sim._app_control_on_stop_handle = None diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py index 6007d03ba483..5bb1256bd836 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/allegro_hand/allegro_hand_env_cfg.py @@ -12,7 +12,6 @@ from isaaclab.markers import VisualizationMarkersCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg -from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR @@ -32,12 +31,8 @@ class AllegroHandEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, + dt=1 / 120, physics=PhysxCfg( - dt=1 / 120, - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), bounce_threshold_velocity=0.2, ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py index dd3f9ff5dae6..0a27e5e66e6d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py @@ -5,8 +5,6 @@ from __future__ import annotations -from isaaclab_physx.physics import PhysxCfg - import isaaclab.sim as sim_utils from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg @@ -31,7 +29,7 @@ class AntEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, dt=1 / 120) terrain = TerrainImporterCfg( prim_path="/World/ground", terrain_type="plane", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py index 8e581d1e0c1d..95140addeb52 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py @@ -3,7 +3,6 @@ # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab_physx.physics import PhysxCfg import isaaclab.envs.mdp as mdp import isaaclab.sim as sim_utils @@ -64,16 +63,7 @@ class AnymalCFlatEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics=PhysxCfg( - dt=1 / 200, - physics_material=sim_utils.RigidBodyMaterialCfg( - friction_combine_mode="multiply", - restitution_combine_mode="multiply", - static_friction=1.0, - dynamic_friction=1.0, - restitution=0.0, - ), - ), + dt=1 / 200, ) terrain = TerrainImporterCfg( prim_path="/World/ground", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py index ae242e033ab4..c94a301f5373 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py @@ -107,9 +107,8 @@ class AssemblyEnvCfg(DirectRLEnvCfg): episode_length_s = 5.0 sim: SimulationCfg = SimulationCfg( device="cuda:0", + dt=1 / 120, physics=PhysxCfg( - dt=1 / 120, - gravity=(0.0, 0.0, -9.81), solver_type=1, max_position_iteration_count=192, # Important to avoid interpenetration. max_velocity_iteration_count=1, @@ -119,10 +118,10 @@ class AssemblyEnvCfg(DirectRLEnvCfg): gpu_max_rigid_contact_count=2**23, gpu_max_rigid_patch_count=2**23, gpu_max_num_partitions=1, # Important for stable simulation. - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), + ), + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py index 8d3ab83611eb..d0187424e16d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py @@ -108,9 +108,8 @@ class DisassemblyEnvCfg(DirectRLEnvCfg): episode_length_s = 5.0 sim: SimulationCfg = SimulationCfg( device="cuda:0", + dt=1 / 120, physics=PhysxCfg( - dt=1 / 120, - gravity=(0.0, 0.0, -9.81), solver_type=1, max_position_iteration_count=192, # Important to avoid interpenetration. max_velocity_iteration_count=1, @@ -120,10 +119,10 @@ class DisassemblyEnvCfg(DirectRLEnvCfg): gpu_max_rigid_contact_count=2**23, gpu_max_rigid_patch_count=2**23, gpu_max_num_partitions=1, # Important for stable simulation. - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), + ), + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py index 7bf08d272fae..c87d1ea172a3 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py @@ -9,7 +9,6 @@ from collections.abc import Sequence import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg @@ -34,7 +33,7 @@ class CartDoublePendulumEnvCfg(DirectMARLEnvCfg): state_space = -1 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics=PhysxCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(render_interval=decimation, dt=1 / 120) # robot robot_cfg: ArticulationCfg = CART_DOUBLE_PENDULUM_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py index e7d8782024ef..dba5bff23b33 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py @@ -98,9 +98,8 @@ class FactoryEnvCfg(DirectRLEnvCfg): episode_length_s = 10.0 # Probably need to override. sim: SimulationCfg = SimulationCfg( device="cuda:0", + dt=1 / 120, physics=PhysxCfg( - dt=1 / 120, - gravity=(0.0, 0.0, -9.81), solver_type=1, max_position_iteration_count=192, # Important to avoid interpenetration. max_velocity_iteration_count=1, @@ -111,10 +110,10 @@ class FactoryEnvCfg(DirectRLEnvCfg): gpu_max_rigid_patch_count=2**23, gpu_collision_stack_size=2**28, gpu_max_num_partitions=1, # Important for stable simulation. - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), + ), + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py index cdf331f8c18f..90241077800e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py @@ -6,7 +6,6 @@ from __future__ import annotations import torch -from isaaclab_physx.physics import PhysxCfg from pxr import UsdGeom @@ -35,16 +34,7 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics=PhysxCfg( - dt=1 / 120, - physics_material=sim_utils.RigidBodyMaterialCfg( - friction_combine_mode="multiply", - restitution_combine_mode="multiply", - static_friction=1.0, - dynamic_friction=1.0, - restitution=0.0, - ), - ), + dt=1 / 120, ) # scene diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py index 0a51d30d2148..faaf038f4340 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py @@ -53,11 +53,8 @@ class HumanoidAmpEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics=PhysxCfg( - dt=1 / 60, - gpu_found_lost_pairs_capacity=2**23, - gpu_total_aggregate_pairs_capacity=2**23, - ), + dt=1 / 60, + physics=PhysxCfg(gpu_found_lost_pairs_capacity=2**23, gpu_total_aggregate_pairs_capacity=2**23), ) # scene diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py index b23ea0811e04..16de87d0b816 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py @@ -7,7 +7,6 @@ import gymnasium as gym import torch -from isaaclab_physx.physics import PhysxCfg import isaaclab.sim as sim_utils from isaaclab.assets import Articulation, ArticulationCfg @@ -62,16 +61,7 @@ class QuadcopterEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, - physics=PhysxCfg( - dt=1 / 100, - physics_material=sim_utils.RigidBodyMaterialCfg( - friction_combine_mode="multiply", - restitution_combine_mode="multiply", - static_friction=1.0, - dynamic_friction=1.0, - restitution=0.0, - ), - ), + dt=1 / 100, ) terrain = TerrainImporterCfg( prim_path="/World/ground", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py index 220f67b66dbc..fcc250786e90 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py @@ -14,7 +14,6 @@ from isaaclab.markers import VisualizationMarkersCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg -from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import GaussianNoiseCfg, NoiseModelWithAdditiveBiasCfg @@ -129,12 +128,8 @@ class ShadowHandEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, + dt=1 / 120, physics=PhysxCfg( - dt=1 / 120, - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), bounce_threshold_velocity=0.2, ), ) @@ -244,12 +239,8 @@ class ShadowHandOpenAIEnvCfg(ShadowHandEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, + dt=1 / 60, physics=PhysxCfg( - dt=1 / 60, - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), bounce_threshold_velocity=0.2, gpu_max_rigid_contact_count=2**23, gpu_max_rigid_patch_count=2**23, diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py index b7e55671715a..5cd9fee50e54 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py @@ -14,7 +14,6 @@ from isaaclab.markers import VisualizationMarkersCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg -from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass from isaaclab_assets.robots.shadow_hand import SHADOW_HAND_CFG @@ -126,12 +125,8 @@ class ShadowHandOverEnvCfg(DirectMARLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( render_interval=decimation, + dt=1 / 120, physics=PhysxCfg( - dt=1 / 120, - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), bounce_threshold_velocity=0.2, ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py index 5755c154bca8..c57b1472933b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py @@ -303,11 +303,8 @@ class GearAssemblyEnvCfg(ManagerBasedRLEnvCfg): terminations: TerminationsCfg = TerminationsCfg() events: EventCfg = EventCfg() sim: SimulationCfg = SimulationCfg( - physics=PhysxCfg( - # Important to prevent collisionStackSize buffer overflow in contact-rich environments. - gpu_collision_stack_size=2**30, - gpu_max_rigid_contact_count=2**23, - gpu_max_rigid_patch_count=2**23, + physics=PhysxCfg( # Important to prevent collisionStackSize buffer overflow in contact-rich environments. + gpu_collision_stack_size=2**30, gpu_max_rigid_contact_count=2**23, gpu_max_rigid_patch_count=2**23 ), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py index f8246fa8fd5c..413da4858236 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py @@ -20,7 +20,6 @@ from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim.simulation_cfg import SimulationCfg -from isaaclab.sim.spawners.materials.physics_materials_cfg import RigidBodyMaterialCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import AdditiveGaussianNoiseCfg as Gnoise @@ -318,10 +317,6 @@ class InHandObjectEnvCfg(ManagerBasedRLEnvCfg): # Simulation settings sim: SimulationCfg = SimulationCfg( physics=PhysxCfg( - physics_material=RigidBodyMaterialCfg( - static_friction=1.0, - dynamic_friction=1.0, - ), bounce_threshold_velocity=0.2, gpu_max_rigid_contact_count=2**20, gpu_max_rigid_patch_count=2**23, From 489de3d3f5474eb024ce4b45f441c02560c113e1 Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Tue, 10 Feb 2026 16:20:33 -0800 Subject: [PATCH 4/7] match ordering of parameters from develop --- scripts/benchmarks/benchmark_view_comparison.py | 2 +- scripts/demos/bin_packing.py | 2 +- scripts/demos/bipeds.py | 2 +- scripts/demos/deformables.py | 2 +- scripts/demos/hands.py | 2 +- scripts/demos/markers.py | 2 +- scripts/demos/multi_asset.py | 2 +- scripts/demos/procedural_terrain.py | 2 +- scripts/demos/quadcopter.py | 2 +- scripts/demos/sensors/cameras.py | 2 +- scripts/demos/sensors/contact_sensor.py | 2 +- scripts/demos/sensors/frame_transformer_sensor.py | 2 +- scripts/demos/sensors/imu_sensor.py | 2 +- scripts/demos/sensors/multi_mesh_raycaster.py | 2 +- scripts/demos/sensors/multi_mesh_raycaster_camera.py | 2 +- scripts/demos/sensors/raycaster_sensor.py | 2 +- scripts/tutorials/00_sim/launch_app.py | 2 +- scripts/tutorials/00_sim/spawn_prims.py | 2 +- scripts/tutorials/04_sensors/add_sensors_on_robot.py | 2 +- scripts/tutorials/04_sensors/run_frame_transformer.py | 2 +- scripts/tutorials/05_controllers/run_diff_ik.py | 2 +- scripts/tutorials/05_controllers/run_osc.py | 2 +- 22 files changed, 22 insertions(+), 22 deletions(-) diff --git a/scripts/benchmarks/benchmark_view_comparison.py b/scripts/benchmarks/benchmark_view_comparison.py index 88b6a9eda3b5..8f2b60c49077 100644 --- a/scripts/benchmarks/benchmark_view_comparison.py +++ b/scripts/benchmarks/benchmark_view_comparison.py @@ -96,7 +96,7 @@ def benchmark_view(view_type: str, num_iterations: int) -> tuple[dict[str, float sim_utils.create_new_stage() # Create simulation context start_time = time.perf_counter() - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device, use_fabric=(view_type == "xform_fabric")) sim = sim_utils.SimulationContext(sim_cfg) stage = sim_utils.get_current_stage() diff --git a/scripts/demos/bin_packing.py b/scripts/demos/bin_packing.py index b227e5b8b085..e23dc0ddcdec 100644 --- a/scripts/demos/bin_packing.py +++ b/scripts/demos/bin_packing.py @@ -327,7 +327,7 @@ def main() -> None: None: The function drives the simulation for its side-effects. """ # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view((2.5, 0.0, 4.0), (0.0, 0.0, 2.0)) diff --git a/scripts/demos/bipeds.py b/scripts/demos/bipeds.py index bc557b745e68..91421c105ff6 100644 --- a/scripts/demos/bipeds.py +++ b/scripts/demos/bipeds.py @@ -114,7 +114,7 @@ def run_simulator(sim: sim_utils.SimulationContext, robots: list[Articulation], def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.0, 0.0, 2.25], target=[0.0, 0.0, 1.0]) diff --git a/scripts/demos/deformables.py b/scripts/demos/deformables.py index 0ee4095dbf2c..9b9a962c26d5 100644 --- a/scripts/demos/deformables.py +++ b/scripts/demos/deformables.py @@ -178,7 +178,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Deformab def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([4.0, 4.0, 3.0], [0.5, 0.5, 0.0]) diff --git a/scripts/demos/hands.py b/scripts/demos/hands.py index 195e87ae8399..a0fa04e0fbfd 100644 --- a/scripts/demos/hands.py +++ b/scripts/demos/hands.py @@ -143,7 +143,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, Articula def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[0.0, -0.5, 1.5], target=[0.0, -0.2, 0.5]) diff --git a/scripts/demos/markers.py b/scripts/demos/markers.py index 527474280e7f..6152dcf5226f 100644 --- a/scripts/demos/markers.py +++ b/scripts/demos/markers.py @@ -94,7 +94,7 @@ def define_markers() -> VisualizationMarkers: def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([0.0, 18.0, 12.0], [0.0, 3.0, 0.0]) diff --git a/scripts/demos/multi_asset.py b/scripts/demos/multi_asset.py index 4dc503df9536..d104eb161d38 100644 --- a/scripts/demos/multi_asset.py +++ b/scripts/demos/multi_asset.py @@ -275,7 +275,7 @@ def run_simulator(sim: SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 0.0, 4.0], [0.0, 0.0, 2.0]) diff --git a/scripts/demos/procedural_terrain.py b/scripts/demos/procedural_terrain.py index 093b1145f201..f0a2fb4e2ef7 100644 --- a/scripts/demos/procedural_terrain.py +++ b/scripts/demos/procedural_terrain.py @@ -154,7 +154,7 @@ def run_simulator(sim: sim_utils.SimulationContext, entities: dict[str, AssetBas def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[5.0, 5.0, 5.0], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/quadcopter.py b/scripts/demos/quadcopter.py index e1e0ddbbc7f4..3dcc7b3eb562 100644 --- a/scripts/demos/quadcopter.py +++ b/scripts/demos/quadcopter.py @@ -47,7 +47,7 @@ def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[0.5, 0.5, 1.0], target=[0.0, 0.0, 0.5]) diff --git a/scripts/demos/sensors/cameras.py b/scripts/demos/sensors/cameras.py index 1edf3cab17f7..83214f7e4cf2 100644 --- a/scripts/demos/sensors/cameras.py +++ b/scripts/demos/sensors/cameras.py @@ -280,7 +280,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005, use_fabric=not args_cli.disable_fabric) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device, use_fabric=not args_cli.disable_fabric) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/contact_sensor.py b/scripts/demos/sensors/contact_sensor.py index cef0f531b523..0ee672ec16a6 100644 --- a/scripts/demos/sensors/contact_sensor.py +++ b/scripts/demos/sensors/contact_sensor.py @@ -154,7 +154,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/frame_transformer_sensor.py b/scripts/demos/sensors/frame_transformer_sensor.py index 643e8c10c2c2..8827b23cea71 100644 --- a/scripts/demos/sensors/frame_transformer_sensor.py +++ b/scripts/demos/sensors/frame_transformer_sensor.py @@ -148,7 +148,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/imu_sensor.py b/scripts/demos/sensors/imu_sensor.py index e022b51d79d1..af649fd94a97 100644 --- a/scripts/demos/sensors/imu_sensor.py +++ b/scripts/demos/sensors/imu_sensor.py @@ -121,7 +121,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/multi_mesh_raycaster.py b/scripts/demos/sensors/multi_mesh_raycaster.py index 1e285e17fd86..07b36573501b 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster.py +++ b/scripts/demos/sensors/multi_mesh_raycaster.py @@ -277,7 +277,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/multi_mesh_raycaster_camera.py b/scripts/demos/sensors/multi_mesh_raycaster_camera.py index dd13ab0901aa..8ef3a188f3d1 100644 --- a/scripts/demos/sensors/multi_mesh_raycaster_camera.py +++ b/scripts/demos/sensors/multi_mesh_raycaster_camera.py @@ -303,7 +303,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/demos/sensors/raycaster_sensor.py b/scripts/demos/sensors/raycaster_sensor.py index 753c077b3f46..02c55222e836 100644 --- a/scripts/demos/sensors/raycaster_sensor.py +++ b/scripts/demos/sensors/raycaster_sensor.py @@ -139,7 +139,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/00_sim/launch_app.py b/scripts/tutorials/00_sim/launch_app.py index 3a3c1cab4fd4..1a689ecedc75 100644 --- a/scripts/tutorials/00_sim/launch_app.py +++ b/scripts/tutorials/00_sim/launch_app.py @@ -71,7 +71,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) diff --git a/scripts/tutorials/00_sim/spawn_prims.py b/scripts/tutorials/00_sim/spawn_prims.py index 6c8046dc77a1..c32a2d588d01 100644 --- a/scripts/tutorials/00_sim/spawn_prims.py +++ b/scripts/tutorials/00_sim/spawn_prims.py @@ -91,7 +91,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.0, 0.0, 2.5], [-0.5, 0.0, 0.5]) diff --git a/scripts/tutorials/04_sensors/add_sensors_on_robot.py b/scripts/tutorials/04_sensors/add_sensors_on_robot.py index 5854e526673e..5cc6de6778b6 100644 --- a/scripts/tutorials/04_sensors/add_sensors_on_robot.py +++ b/scripts/tutorials/04_sensors/add_sensors_on_robot.py @@ -157,7 +157,7 @@ def main(): """Main function.""" # Initialize the simulation context - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/04_sensors/run_frame_transformer.py b/scripts/tutorials/04_sensors/run_frame_transformer.py index f4d64f94edf4..d6d12665ada9 100644 --- a/scripts/tutorials/04_sensors/run_frame_transformer.py +++ b/scripts/tutorials/04_sensors/run_frame_transformer.py @@ -165,7 +165,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene_entities: dict): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.005) + sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device) sim = SimulationContext(sim_cfg) # Set main camera sim.set_camera_view(eye=[2.5, 2.5, 2.5], target=[0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/05_controllers/run_diff_ik.py b/scripts/tutorials/05_controllers/run_diff_ik.py index 3f3da9ffe204..c79ae802d646 100644 --- a/scripts/tutorials/05_controllers/run_diff_ik.py +++ b/scripts/tutorials/05_controllers/run_diff_ik.py @@ -190,7 +190,7 @@ def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene): def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) diff --git a/scripts/tutorials/05_controllers/run_osc.py b/scripts/tutorials/05_controllers/run_osc.py index e8de66dc2d98..705dec63bc71 100644 --- a/scripts/tutorials/05_controllers/run_osc.py +++ b/scripts/tutorials/05_controllers/run_osc.py @@ -462,7 +462,7 @@ def convert_to_task_frame(osc: OperationalSpaceController, command: torch.tensor def main(): """Main function.""" # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=args_cli.device, dt=0.01) + sim_cfg = sim_utils.SimulationCfg(dt=0.01, device=args_cli.device) sim = sim_utils.SimulationContext(sim_cfg) # Set main camera sim.set_camera_view([2.5, 2.5, 2.5], [0.0, 0.0, 0.0]) From 2bbf1bf560595450d531f5d86f39205a53b4284d Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Tue, 10 Feb 2026 16:46:51 -0800 Subject: [PATCH 5/7] more fixes --- source/isaaclab/isaaclab/envs/direct_rl_env.py | 6 +++--- source/isaaclab/isaaclab/envs/manager_based_env.py | 4 ++-- source/isaaclab/test/envs/test_env_rendering_logic.py | 6 +++--- source/isaaclab/test/managers/test_observation_manager.py | 2 +- source/isaaclab/test/sensors/test_tiled_camera.py | 2 +- .../test/sim/test_build_simulation_context_headless.py | 2 +- .../test/sim/test_build_simulation_context_nonheadless.py | 2 +- source/isaaclab/test/sim/test_views_xform_prim.py | 2 +- source/isaaclab_physx/test/sensors/test_contact_sensor.py | 6 +++--- source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py | 2 +- .../isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py | 2 +- .../isaaclab_tasks/direct/automate/assembly_env_cfg.py | 1 + .../isaaclab_tasks/direct/automate/disassembly_env_cfg.py | 1 + .../direct/cart_double_pendulum/cart_double_pendulum_env.py | 2 +- .../isaaclab_tasks/direct/factory/factory_env_cfg.py | 1 + .../direct/franka_cabinet/franka_cabinet_env.py | 2 +- .../direct/humanoid_amp/humanoid_amp_env_cfg.py | 2 +- .../isaaclab_tasks/direct/quadcopter/quadcopter_env.py | 2 +- .../direct/shadow_hand/shadow_hand_env_cfg.py | 4 ++-- .../direct/shadow_hand_over/shadow_hand_over_env_cfg.py | 2 +- .../isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py | 2 +- .../manager_based/classic/cartpole/cartpole_env_cfg.py | 2 +- .../manager_based/classic/humanoid/humanoid_env_cfg.py | 2 +- .../config/arl_robot_1/no_obstacle_env_cfg.py | 2 +- .../arl_robot_1/track_position_state_based_env_cfg.py | 2 +- .../pick_place/fixed_base_upper_body_ik_g1_env_cfg.py | 2 +- .../pick_place/locomanipulation_g1_env_cfg.py | 2 +- .../locomotion/velocity/config/digit/rough_env_cfg.py | 6 +++--- .../locomotion/velocity/config/spot/flat_env_cfg.py | 4 ++-- .../manager_based/locomotion/velocity/velocity_env_cfg.py | 6 +++--- .../manager_based/manipulation/cabinet/cabinet_env_cfg.py | 2 +- .../cabinet/config/openarm/cabinet_openarm_env_cfg.py | 2 +- .../deploy/gear_assembly/gear_assembly_env_cfg.py | 2 +- .../manipulation/deploy/reach/reach_env_cfg.py | 2 +- .../manager_based/manipulation/inhand/inhand_env_cfg.py | 2 +- .../lift/config/openarm/lift_openarm_env_cfg.py | 2 +- .../manager_based/manipulation/lift/lift_env_cfg.py | 2 +- .../pick_place/exhaustpipe_gr1t2_base_env_cfg.py | 2 +- .../manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py | 2 +- .../manipulation/pick_place/pickplace_gr1t2_env_cfg.py | 2 +- .../pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py | 2 +- .../pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py | 2 +- .../place/config/agibot/place_toy2box_rmp_rel_env_cfg.py | 2 +- .../config/agibot/place_upright_mug_rmp_rel_env_cfg.py | 2 +- .../config/openarm/bimanual/reach_openarm_bi_env_cfg.py | 2 +- .../config/openarm/unimanual/reach_openarm_uni_env_cfg.py | 2 +- .../manager_based/manipulation/reach/reach_env_cfg.py | 2 +- .../stack/config/galbot/stack_rmp_rel_env_cfg.py | 4 ++-- .../stack/config/ur10_gripper/stack_joint_pos_env_cfg.py | 2 +- .../manager_based/manipulation/stack/stack_env_cfg.py | 2 +- .../manipulation/stack/stack_instance_randomize_env_cfg.py | 2 +- .../navigation/config/anymal_c/navigation_env_cfg.py | 6 +++--- 52 files changed, 68 insertions(+), 65 deletions(-) diff --git a/source/isaaclab/isaaclab/envs/direct_rl_env.py b/source/isaaclab/isaaclab/envs/direct_rl_env.py index 17d29f7ebd8c..c73571ccfa20 100644 --- a/source/isaaclab/isaaclab/envs/direct_rl_env.py +++ b/source/isaaclab/isaaclab/envs/direct_rl_env.py @@ -258,7 +258,7 @@ def physics_dt(self) -> float: This is the lowest time-decimation at which the simulation is happening. """ - return self.cfg.sim.physics.dt + return self.cfg.sim.dt @property def step_dt(self) -> float: @@ -266,7 +266,7 @@ def step_dt(self) -> float: This is the time-step at which the environment steps forward. """ - return self.cfg.sim.physics.dt * self.cfg.decimation + return self.cfg.sim.dt * self.cfg.decimation @property def device(self): @@ -281,7 +281,7 @@ def max_episode_length_s(self) -> float: @property def max_episode_length(self): """The maximum episode length in steps adjusted from s.""" - return math.ceil(self.max_episode_length_s / (self.cfg.sim.physics.dt * self.cfg.decimation)) + return math.ceil(self.max_episode_length_s / (self.cfg.sim.dt * self.cfg.decimation)) """ Operations. diff --git a/source/isaaclab/isaaclab/envs/manager_based_env.py b/source/isaaclab/isaaclab/envs/manager_based_env.py index 4162b46ad77b..7843f1e47ef2 100644 --- a/source/isaaclab/isaaclab/envs/manager_based_env.py +++ b/source/isaaclab/isaaclab/envs/manager_based_env.py @@ -228,7 +228,7 @@ def physics_dt(self) -> float: This is the lowest time-decimation at which the simulation is happening. """ - return self.cfg.sim.physics.dt + return self.cfg.sim.dt @property def step_dt(self) -> float: @@ -236,7 +236,7 @@ def step_dt(self) -> float: This is the time-step at which the environment steps forward. """ - return self.cfg.sim.physics.dt * self.cfg.decimation + return self.cfg.sim.dt * self.cfg.decimation @property def device(self): diff --git a/source/isaaclab/test/envs/test_env_rendering_logic.py b/source/isaaclab/test/envs/test_env_rendering_logic.py index 9c407893f349..9728884c952e 100644 --- a/source/isaaclab/test/envs/test_env_rendering_logic.py +++ b/source/isaaclab/test/envs/test_env_rendering_logic.py @@ -48,7 +48,7 @@ class EnvCfg(ManagerBasedEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(render_interval=render_interval, dt=0.005) + sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -65,7 +65,7 @@ class EnvCfg(ManagerBasedRLEnvCfg): decimation: int = 4 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(render_interval=render_interval, dt=0.005) + sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) actions: EmptyManagerCfg = EmptyManagerCfg() observations: EmptyManagerCfg = EmptyManagerCfg() @@ -86,7 +86,7 @@ class EnvCfg(DirectRLEnvCfg): action_space: int = 0 observation_space: int = 0 episode_length_s: float = 100.0 - sim: SimulationCfg = SimulationCfg(render_interval=render_interval, dt=0.005) + sim: SimulationCfg = SimulationCfg(dt=0.005, render_interval=render_interval) scene: InteractiveSceneCfg = InteractiveSceneCfg(num_envs=1, env_spacing=1.0) class Env(DirectRLEnv): diff --git a/source/isaaclab/test/managers/test_observation_manager.py b/source/isaaclab/test/managers/test_observation_manager.py index 1ab6489c23ef..86e77c571a42 100644 --- a/source/isaaclab/test/managers/test_observation_manager.py +++ b/source/isaaclab/test/managers/test_observation_manager.py @@ -107,7 +107,7 @@ def setup_env(): num_envs = 20 device = "cuda:0" # set up sim - sim_cfg = sim_utils.SimulationCfg(device=device, dt=dt) + sim_cfg = sim_utils.SimulationCfg(dt=dt, device=device) sim = sim_utils.SimulationContext(sim_cfg) # create dummy environment env = namedtuple("ManagerBasedEnv", ["num_envs", "device", "data", "dt", "sim"])( diff --git a/source/isaaclab/test/sensors/test_tiled_camera.py b/source/isaaclab/test/sensors/test_tiled_camera.py index f9c6fb5194fa..c37969eb0856 100644 --- a/source/isaaclab/test/sensors/test_tiled_camera.py +++ b/source/isaaclab/test/sensors/test_tiled_camera.py @@ -50,7 +50,7 @@ def setup_camera(device) -> tuple[sim_utils.SimulationContext, TiledCameraCfg, f # Simulation time-step dt = 0.01 # Load kit helper - sim_cfg = sim_utils.SimulationCfg(device=device, dt=dt) + sim_cfg = sim_utils.SimulationCfg(dt=dt, device=device) sim: sim_utils.SimulationContext = sim_utils.SimulationContext(sim_cfg) # populate scene _populate_scene() diff --git a/source/isaaclab/test/sim/test_build_simulation_context_headless.py b/source/isaaclab/test/sim/test_build_simulation_context_headless.py index ed1ba3c788f0..7b114d35be9b 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_headless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_headless.py @@ -83,8 +83,8 @@ def test_build_simulation_context_cfg(): device = "cuda:0" cfg = SimulationCfg( - device=device, gravity=gravity, + device=device, dt=dt, ) diff --git a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py index 3d1913366753..6ac9b2445b8d 100644 --- a/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py +++ b/source/isaaclab/test/sim/test_build_simulation_context_nonheadless.py @@ -78,8 +78,8 @@ def test_build_simulation_context_cfg(): device = "cuda:0" cfg = SimulationCfg( - device=device, gravity=gravity, + device=device, dt=dt, ) diff --git a/source/isaaclab/test/sim/test_views_xform_prim.py b/source/isaaclab/test/sim/test_views_xform_prim.py index ee321cd3a5b7..9323379fc5db 100644 --- a/source/isaaclab/test/sim/test_views_xform_prim.py +++ b/source/isaaclab/test/sim/test_views_xform_prim.py @@ -74,7 +74,7 @@ def _prim_type_for_backend(backend: str) -> str: def _create_view(pattern: str, device: str, backend: str) -> XformPrimView: """Create an XformPrimView for the requested backend.""" if backend == "fabric": - sim_utils.SimulationContext(sim_utils.SimulationCfg(device=device, dt=0.01, use_fabric=True)) + sim_utils.SimulationContext(sim_utils.SimulationCfg(dt=0.01, device=device, use_fabric=True)) return XformPrimView(pattern, device=device) diff --git a/source/isaaclab_physx/test/sensors/test_contact_sensor.py b/source/isaaclab_physx/test/sensors/test_contact_sensor.py index b296f286a0e5..a8b8d6f354bf 100644 --- a/source/isaaclab_physx/test/sensors/test_contact_sensor.py +++ b/source/isaaclab_physx/test/sensors/test_contact_sensor.py @@ -452,7 +452,7 @@ def test_friction_reporting(setup_simulation, grav_dir): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(device=device, dt=sim_dt, gravity=grav_dir) + sim_cfg = SimulationCfg(dt=sim_dt, device=device, gravity=grav_dir) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None @@ -505,7 +505,7 @@ def test_invalid_prim_paths_config(setup_simulation): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(device=device, dt=sim_dt) + sim_cfg = SimulationCfg(dt=sim_dt, device=device) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None @@ -539,7 +539,7 @@ def test_invalid_max_contact_points_config(setup_simulation): sim_dt, _, _, _, carb_settings_iface = setup_simulation carb_settings_iface.set_bool("/physics/disableContactProcessing", True) device = "cuda:0" - sim_cfg = SimulationCfg(device=device, dt=sim_dt) + sim_cfg = SimulationCfg(dt=sim_dt, device=device) with build_simulation_context(sim_cfg=sim_cfg, add_lighting=False) as sim: sim._app_control_on_stop_handle = None diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py index 0a27e5e66e6d..39ae57b29677 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/ant/ant_env.py @@ -29,7 +29,7 @@ class AntEnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, dt=1 / 120) + sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) terrain = TerrainImporterCfg( prim_path="/World/ground", terrain_type="plane", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py index 95140addeb52..1617d877ad83 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/anymal_c/anymal_c_env_cfg.py @@ -62,8 +62,8 @@ class AnymalCFlatEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - render_interval=decimation, dt=1 / 200, + render_interval=decimation, ) terrain = TerrainImporterCfg( prim_path="/World/ground", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py index c94a301f5373..7fae88707c5c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/assembly_env_cfg.py @@ -108,6 +108,7 @@ class AssemblyEnvCfg(DirectRLEnvCfg): sim: SimulationCfg = SimulationCfg( device="cuda:0", dt=1 / 120, + gravity=(0.0, 0.0, -9.81), physics=PhysxCfg( solver_type=1, max_position_iteration_count=192, # Important to avoid interpenetration. diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py index d0187424e16d..a2b7fbe49133 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/automate/disassembly_env_cfg.py @@ -109,6 +109,7 @@ class DisassemblyEnvCfg(DirectRLEnvCfg): sim: SimulationCfg = SimulationCfg( device="cuda:0", dt=1 / 120, + gravity=(0.0, 0.0, -9.81), physics=PhysxCfg( solver_type=1, max_position_iteration_count=192, # Important to avoid interpenetration. diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py index c87d1ea172a3..e0464a7201c8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/cart_double_pendulum/cart_double_pendulum_env.py @@ -33,7 +33,7 @@ class CartDoublePendulumEnvCfg(DirectMARLEnvCfg): state_space = -1 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, dt=1 / 120) + sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) # robot robot_cfg: ArticulationCfg = CART_DOUBLE_PENDULUM_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py index dba5bff23b33..028184ff7ba7 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/factory/factory_env_cfg.py @@ -99,6 +99,7 @@ class FactoryEnvCfg(DirectRLEnvCfg): sim: SimulationCfg = SimulationCfg( device="cuda:0", dt=1 / 120, + gravity=(0.0, 0.0, -9.81), physics=PhysxCfg( solver_type=1, max_position_iteration_count=192, # Important to avoid interpenetration. diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py index 90241077800e..9b91b9823829 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/franka_cabinet/franka_cabinet_env.py @@ -33,8 +33,8 @@ class FrankaCabinetEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - render_interval=decimation, dt=1 / 120, + render_interval=decimation, ) # scene diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py index faaf038f4340..324717dd6c18 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/humanoid_amp/humanoid_amp_env_cfg.py @@ -52,8 +52,8 @@ class HumanoidAmpEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - render_interval=decimation, dt=1 / 60, + render_interval=decimation, physics=PhysxCfg(gpu_found_lost_pairs_capacity=2**23, gpu_total_aggregate_pairs_capacity=2**23), ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py index 16de87d0b816..d507d3c9f5e0 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/quadcopter/quadcopter_env.py @@ -60,8 +60,8 @@ class QuadcopterEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - render_interval=decimation, dt=1 / 100, + render_interval=decimation, ) terrain = TerrainImporterCfg( prim_path="/World/ground", diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py index fcc250786e90..86431e01d3a4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py @@ -127,8 +127,8 @@ class ShadowHandEnvCfg(DirectRLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - render_interval=decimation, dt=1 / 120, + render_interval=decimation, physics=PhysxCfg( bounce_threshold_velocity=0.2, ), @@ -238,8 +238,8 @@ class ShadowHandOpenAIEnvCfg(ShadowHandEnvCfg): obs_type = "openai" # simulation sim: SimulationCfg = SimulationCfg( - render_interval=decimation, dt=1 / 60, + render_interval=decimation, physics=PhysxCfg( bounce_threshold_velocity=0.2, gpu_max_rigid_contact_count=2**23, diff --git a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py index 5cd9fee50e54..83a56dd1c3ae 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/direct/shadow_hand_over/shadow_hand_over_env_cfg.py @@ -124,8 +124,8 @@ class ShadowHandOverEnvCfg(DirectMARLEnvCfg): # simulation sim: SimulationCfg = SimulationCfg( - render_interval=decimation, dt=1 / 120, + render_interval=decimation, physics=PhysxCfg( bounce_threshold_velocity=0.2, ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py index d10f600a8042..9af4725066db 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/ant/ant_env_cfg.py @@ -175,7 +175,7 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 16.0 # simulation settings - self.sim.physics.dt = 1 / 120.0 + self.sim.dt = 1 / 120.0 self.sim.render_interval = self.decimation self.sim.physics.bounce_threshold_velocity = 0.2 # default friction material diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py index c5d486de0a79..788920af058c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/cartpole/cartpole_env_cfg.py @@ -177,5 +177,5 @@ def __post_init__(self) -> None: # viewer settings self.viewer.eye = (8.0, 0.0, 5.0) # simulation settings - self.sim.physics.dt = 1 / 120 + self.sim.dt = 1 / 120 self.sim.render_interval = self.decimation diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py index 5995b425702f..29f632d18c9e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/classic/humanoid/humanoid_env_cfg.py @@ -212,7 +212,7 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 16.0 # simulation settings - self.sim.physics.dt = 1 / 120.0 + self.sim.dt = 1 / 120.0 self.sim.render_interval = self.decimation self.sim.physics.bounce_threshold_velocity = 0.2 # default friction material diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py index c4403c9565e1..92a11d824420 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/no_obstacle_env_cfg.py @@ -21,7 +21,7 @@ def __post_init__(self): super().__post_init__() # switch robot to arl_robot_1 self.scene.robot = ARL_ROBOT_1_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") - self.scene.robot.actuators["thrusters"].dt = self.sim.physics.dt + self.scene.robot.actuators["thrusters"].dt = self.sim.dt @configclass diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py index b07795abeca8..44597e00d277 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py @@ -218,7 +218,7 @@ def __post_init__(self): self.decimation = 10 self.episode_length_s = 5.0 # simulation settings - self.sim.physics.dt = 0.01 + self.sim.dt = 0.01 self.sim.render_interval = self.decimation self.sim.physics.physics_material = sim_utils.RigidBodyMaterialCfg( friction_combine_mode="multiply", diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py index e235d1be63f5..d229bca9ab7f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/fixed_base_upper_body_ik_g1_env_cfg.py @@ -187,7 +187,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 1 / 200 # 200Hz + self.sim.dt = 1 / 200 # 200Hz self.sim.render_interval = 2 # Set the URDF and mesh paths for the IK controller diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py index 5626ea8d8da8..3c63aea542bd 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomanipulation/pick_place/locomanipulation_g1_env_cfg.py @@ -204,7 +204,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 1 / 200 # 200Hz + self.sim.dt = 1 / 200 # 200Hz self.sim.render_interval = 2 # Set the URDF and mesh paths for the IK controller diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py index 81b64be322c4..792e6f639479 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/digit/rough_env_cfg.py @@ -218,14 +218,14 @@ class DigitRoughEnvCfg(LocomotionVelocityRoughEnvCfg): def __post_init__(self): super().__post_init__() self.decimation = 4 - self.sim.physics.dt = 0.005 + self.sim.dt = 0.005 # Scene self.scene.robot = DIGIT_V4_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torso_base" self.scene.contact_forces.history_length = self.decimation - self.scene.contact_forces.update_period = self.sim.physics.dt - self.scene.height_scanner.update_period = self.decimation * self.sim.physics.dt + self.scene.contact_forces.update_period = self.sim.dt + self.scene.height_scanner.update_period = self.decimation * self.sim.dt # Events: self.events.add_base_mass.params["asset_cfg"] = SceneEntityCfg("robot", body_names="torso_base") diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py index 8b183f383989..b2ee4fef4334 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py @@ -318,7 +318,7 @@ def __post_init__(self): self.decimation = 10 # 50 Hz self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 0.002 # 500 Hz + self.sim.dt = 0.002 # 500 Hz self.sim.render_interval = self.decimation self.sim.physics.physics_material.static_friction = 1.0 self.sim.physics.physics_material.dynamic_friction = 1.0 @@ -326,7 +326,7 @@ def __post_init__(self): self.sim.physics.physics_material.restitution_combine_mode = "multiply" # update sensor update periods # we tick all the sensors based on the smallest update period (physics update period) - self.scene.contact_forces.update_period = self.sim.physics.dt + self.scene.contact_forces.update_period = self.sim.dt # switch robot to Spot-d self.scene.robot = SPOT_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py index 9920ed7b3b03..52fb4c7d7443 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py @@ -308,16 +308,16 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 0.005 + self.sim.dt = 0.005 self.sim.render_interval = self.decimation self.sim.physics.physics_material = self.scene.terrain.physics_material self.sim.physics.gpu_max_rigid_patch_count = 10 * 2**15 # update sensor update periods # we tick all the sensors based on the smallest update period (physics update period) if self.scene.height_scanner is not None: - self.scene.height_scanner.update_period = self.decimation * self.sim.physics.dt + self.scene.height_scanner.update_period = self.decimation * self.sim.dt if self.scene.contact_forces is not None: - self.scene.contact_forces.update_period = self.sim.physics.dt + self.scene.contact_forces.update_period = self.sim.dt # check if terrain levels curriculum is enabled - if so, enable curriculum for terrain generator # this generates terrains with increasing difficulty and is useful for training diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py index d231be8bcfb4..fa2e60c715ec 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_env_cfg.py @@ -271,7 +271,7 @@ def __post_init__(self): self.viewer.eye = (-2.0, 2.0, 2.0) self.viewer.lookat = (0.8, 0.0, 0.5) # simulation settings - self.sim.physics.dt = 1 / 60 # 60Hz + self.sim.dt = 1 / 60 # 60Hz self.sim.render_interval = self.decimation self.sim.physics.bounce_threshold_velocity = 0.01 self.sim.physics.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py index 942cadfb3a56..4281a75dcfc7 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py @@ -276,7 +276,7 @@ def __post_init__(self): self.viewer.eye = (-2.0, 2.0, 2.0) self.viewer.lookat = (0.8, 0.0, 0.5) # simulation settings - self.sim.physics.dt = 1 / 60 # 60Hz + self.sim.dt = 1 / 60 # 60Hz self.sim.render_interval = self.decimation self.sim.physics.bounce_threshold_velocity = 0.01 self.sim.physics.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py index c57b1472933b..6a3fc7f080f4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/gear_assembly/gear_assembly_env_cfg.py @@ -316,7 +316,7 @@ def __post_init__(self): # simulation settings self.decimation = 4 self.sim.render_interval = self.decimation - self.sim.physics.dt = 1.0 / 120.0 + self.sim.dt = 1.0 / 120.0 self.gear_offsets = { "gear_small": [0.076125, 0.0, 0.0], diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py index e48e27152f2d..90b65a0f96c2 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/deploy/reach/reach_env_cfg.py @@ -212,4 +212,4 @@ def __post_init__(self): self.episode_length_s = 12.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.physics.dt = 1.0 / 120.0 + self.sim.dt = 1.0 / 120.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py index 413da4858236..006b5384fa0c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py @@ -337,7 +337,7 @@ def __post_init__(self): self.decimation = 4 self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 1.0 / 120.0 + self.sim.dt = 1.0 / 120.0 self.sim.render_interval = self.decimation # change viewer settings self.viewer.eye = (2.0, 2.0, 2.0) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py index b8a44b3bd71e..176fb04ed4f1 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py @@ -233,7 +233,7 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 5.0 # simulation settings - self.sim.physics.dt = 0.01 # 100Hz + self.sim.dt = 0.01 # 100Hz self.sim.render_interval = self.decimation self.sim.physics.bounce_threshold_velocity = 0.01 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py index 1207e0d3aaaf..fce116c6e40c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_env_cfg.py @@ -214,7 +214,7 @@ def __post_init__(self): self.decimation = 2 self.episode_length_s = 5.0 # simulation settings - self.sim.physics.dt = 0.01 # 100Hz + self.sim.dt = 0.01 # 100Hz self.sim.render_interval = self.decimation self.sim.physics.bounce_threshold_velocity = 0.01 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py index 6eeef3c4d755..57c534039e26 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/exhaustpipe_gr1t2_base_env_cfg.py @@ -325,7 +325,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 1 / 100 + self.sim.dt = 1 / 100 self.sim.render_interval = 2 # Set settings for camera rendering diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py index 044bc28cad30..8440dfe4b8cd 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/nutpour_gr1t2_base_env_cfg.py @@ -360,7 +360,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 1 / 100 + self.sim.dt = 1 / 100 self.sim.render_interval = 2 # Set settings for camera rendering diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py index b199b93b25c8..9e7944d6d1c1 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_env_cfg.py @@ -377,7 +377,7 @@ def __post_init__(self): self.decimation = 6 self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 1 / 120 # 120Hz + self.sim.dt = 1 / 120 # 120Hz self.sim.render_interval = 2 # Convert USD to URDF and change revolute joints to fixed diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py index 37f382bb6737..7bb286506425 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_gr1t2_waist_enabled_env_cfg.py @@ -51,7 +51,7 @@ def __post_init__(self): self.decimation = 6 self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 1 / 120 # 120Hz + self.sim.dt = 1 / 120 # 120Hz self.sim.render_interval = 2 # Add waist joint to pink_ik_cfg diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py index b67b0a00d9b4..0877c2d3b2a1 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/pick_place/pickplace_unitree_g1_inspire_hand_env_cfg.py @@ -368,7 +368,7 @@ def __post_init__(self): self.decimation = 6 self.episode_length_s = 20.0 # simulation settings - self.sim.physics.dt = 1 / 120 # 120Hz + self.sim.dt = 1 / 120 # 120Hz self.sim.render_interval = 2 # Convert USD to URDF and change revolute joints to fixed diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py index 25709496f23f..30617b71b6c3 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_toy2box_rmp_rel_env_cfg.py @@ -339,7 +339,7 @@ def __post_init__(self): ) # Set the simulation parameters - self.sim.physics.dt = 1 / 60 + self.sim.dt = 1 / 60 self.sim.render_interval = 6 self.decimation = 3 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py index acf35eafa138..29206a8f486e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/place/config/agibot/place_upright_mug_rmp_rel_env_cfg.py @@ -276,7 +276,7 @@ def __post_init__(self): ) # Set the simulation parameters - self.sim.physics.dt = 1 / 60 + self.sim.dt = 1 / 60 self.sim.render_interval = 6 self.decimation = 3 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py index 656a6e9e7440..7ccdfa0f851b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py @@ -332,4 +332,4 @@ def __post_init__(self): self.episode_length_s = 24.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.physics.dt = 1.0 / 60.0 + self.sim.dt = 1.0 / 60.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py index c126cf3434bd..11305e7d1c06 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py @@ -245,4 +245,4 @@ def __post_init__(self): self.episode_length_s = 12.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.physics.dt = 1.0 / 60.0 + self.sim.dt = 1.0 / 60.0 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py index e53cc4ca9286..e1f88e2400c3 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_env_cfg.py @@ -209,7 +209,7 @@ def __post_init__(self): self.episode_length_s = 12.0 self.viewer.eye = (3.5, 3.5, 3.5) # simulation settings - self.sim.physics.dt = 1.0 / 60.0 + self.sim.dt = 1.0 / 60.0 self.teleop_devices = DevicesCfg( devices={ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py index 809fca4e50ce..53ccef2c8f71 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/galbot/stack_rmp_rel_env_cfg.py @@ -60,7 +60,7 @@ def __post_init__(self): ) # Set the simulation parameters - self.sim.physics.dt = 1 / 60 + self.sim.dt = 1 / 60 self.sim.render_interval = 6 self.decimation = 3 @@ -126,7 +126,7 @@ def __post_init__(self): use_relative_mode=self.use_relative_mode, ) # Set the simulation parameters - self.sim.physics.dt = 1 / 120 + self.sim.dt = 1 / 120 self.sim.render_interval = 6 self.decimation = 6 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py index 718b95fc1671..296b95e103a5 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/config/ur10_gripper/stack_joint_pos_env_cfg.py @@ -132,7 +132,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 30.0 # simulation settings - self.sim.physics.dt = 0.01 # 100Hz + self.sim.dt = 0.01 # 100Hz self.sim.render_interval = 5 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py index 8efcf500ea4a..b486002eb5fe 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_env_cfg.py @@ -189,7 +189,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 30.0 # simulation settings - self.sim.physics.dt = 0.01 # 100Hz + self.sim.dt = 0.01 # 100Hz self.sim.render_interval = 2 self.sim.physics.bounce_threshold_velocity = 0.01 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py index 2000ba4ce9dd..ef62a8990fac 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/stack/stack_instance_randomize_env_cfg.py @@ -125,7 +125,7 @@ def __post_init__(self): self.decimation = 5 self.episode_length_s = 30.0 # simulation settings - self.sim.physics.dt = 0.01 # 100Hz + self.sim.dt = 0.01 # 100Hz self.sim.render_interval = self.decimation self.sim.physics.bounce_threshold_velocity = 0.01 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py index b0091dcd7fd5..96b60705bb50 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_env_cfg.py @@ -135,17 +135,17 @@ class NavigationEnvCfg(ManagerBasedRLEnvCfg): def __post_init__(self): """Post initialization.""" - self.sim.physics.dt = LOW_LEVEL_ENV_CFG.sim.physics.dt + self.sim.dt = LOW_LEVEL_ENV_CFG.sim.dt self.sim.render_interval = LOW_LEVEL_ENV_CFG.decimation self.decimation = LOW_LEVEL_ENV_CFG.decimation * 10 self.episode_length_s = self.commands.pose_command.resampling_time_range[1] if self.scene.height_scanner is not None: self.scene.height_scanner.update_period = ( - self.actions.pre_trained_policy_action.low_level_decimation * self.sim.physics.dt + self.actions.pre_trained_policy_action.low_level_decimation * self.sim.dt ) if self.scene.contact_forces is not None: - self.scene.contact_forces.update_period = self.sim.physics.dt + self.scene.contact_forces.update_period = self.sim.dt class NavigationEnvCfg_PLAY(NavigationEnvCfg): From 3c995307953b835cf900164278d9117f6be9f5ad Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Tue, 10 Feb 2026 16:49:44 -0800 Subject: [PATCH 6/7] more fixes --- .../arl_robot_1/track_position_state_based_env_cfg.py | 2 +- .../locomotion/velocity/config/spot/flat_env_cfg.py | 8 ++++---- .../manager_based/locomotion/velocity/velocity_env_cfg.py | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py index 44597e00d277..09d796ae71f4 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/track_position_state_based/config/arl_robot_1/track_position_state_based_env_cfg.py @@ -220,7 +220,7 @@ def __post_init__(self): # simulation settings self.sim.dt = 0.01 self.sim.render_interval = self.decimation - self.sim.physics.physics_material = sim_utils.RigidBodyMaterialCfg( + self.sim.physics_material = sim_utils.RigidBodyMaterialCfg( friction_combine_mode="multiply", restitution_combine_mode="multiply", static_friction=1.0, diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py index b2ee4fef4334..6bf334e24536 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/spot/flat_env_cfg.py @@ -320,10 +320,10 @@ def __post_init__(self): # simulation settings self.sim.dt = 0.002 # 500 Hz self.sim.render_interval = self.decimation - self.sim.physics.physics_material.static_friction = 1.0 - self.sim.physics.physics_material.dynamic_friction = 1.0 - self.sim.physics.physics_material.friction_combine_mode = "multiply" - self.sim.physics.physics_material.restitution_combine_mode = "multiply" + self.sim.physics_material.static_friction = 1.0 + self.sim.physics_material.dynamic_friction = 1.0 + self.sim.physics_material.friction_combine_mode = "multiply" + self.sim.physics_material.restitution_combine_mode = "multiply" # update sensor update periods # we tick all the sensors based on the smallest update period (physics update period) self.scene.contact_forces.update_period = self.sim.dt diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py index 52fb4c7d7443..9bda223396d8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/velocity_env_cfg.py @@ -310,7 +310,7 @@ def __post_init__(self): # simulation settings self.sim.dt = 0.005 self.sim.render_interval = self.decimation - self.sim.physics.physics_material = self.scene.terrain.physics_material + self.sim.physics_material = self.scene.terrain.physics_material self.sim.physics.gpu_max_rigid_patch_count = 10 * 2**15 # update sensor update periods # we tick all the sensors based on the smallest update period (physics update period) From 8f6553722ed3b9299a6a1a82e6229b317e2f4375 Mon Sep 17 00:00:00 2001 From: Kelly Guo Date: Tue, 10 Feb 2026 16:56:27 -0800 Subject: [PATCH 7/7] more fixes --- .../manager_based/manipulation/inhand/inhand_env_cfg.py | 5 +++++ tools/template/templates/tasks/direct_multi-agent/env_cfg | 3 +-- tools/template/templates/tasks/direct_single-agent/env_cfg | 3 +-- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py index 006b5384fa0c..09f5a6bb2346 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/inhand/inhand_env_cfg.py @@ -20,6 +20,7 @@ from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim.simulation_cfg import SimulationCfg +from isaaclab.sim.spawners.materials import RigidBodyMaterialCfg from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import AdditiveGaussianNoiseCfg as Gnoise @@ -316,6 +317,10 @@ class InHandObjectEnvCfg(ManagerBasedRLEnvCfg): scene: InHandObjectSceneCfg = InHandObjectSceneCfg(num_envs=8192, env_spacing=0.6) # Simulation settings sim: SimulationCfg = SimulationCfg( + physics_material=RigidBodyMaterialCfg( + static_friction=1.0, + dynamic_friction=1.0, + ), physics=PhysxCfg( bounce_threshold_velocity=0.2, gpu_max_rigid_contact_count=2**20, diff --git a/tools/template/templates/tasks/direct_multi-agent/env_cfg b/tools/template/templates/tasks/direct_multi-agent/env_cfg index 5cd810204137..3b207209b736 100644 --- a/tools/template/templates/tasks/direct_multi-agent/env_cfg +++ b/tools/template/templates/tasks/direct_multi-agent/env_cfg @@ -7,7 +7,6 @@ from isaaclab_assets.robots.cart_double_pendulum import CART_DOUBLE_PENDULUM_CFG from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectMARLEnvCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.utils import configclass @@ -25,7 +24,7 @@ class {{ task.classname }}EnvCfg(DirectMARLEnvCfg): state_space = -1 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) # robot(s) robot_cfg: ArticulationCfg = CART_DOUBLE_PENDULUM_CFG.replace(prim_path="/World/envs/env_.*/Robot") diff --git a/tools/template/templates/tasks/direct_single-agent/env_cfg b/tools/template/templates/tasks/direct_single-agent/env_cfg index 8a794ff1af94..10588cd3e845 100644 --- a/tools/template/templates/tasks/direct_single-agent/env_cfg +++ b/tools/template/templates/tasks/direct_single-agent/env_cfg @@ -7,7 +7,6 @@ from isaaclab_assets.robots.cartpole import CARTPOLE_CFG from isaaclab.assets import ArticulationCfg from isaaclab.envs import DirectRLEnvCfg -from isaaclab_physx.physics.physx_manager_cfg import PhysxManagerCfg from isaaclab.scene import InteractiveSceneCfg from isaaclab.sim import SimulationCfg from isaaclab.utils import configclass @@ -24,7 +23,7 @@ class {{ task.classname }}EnvCfg(DirectRLEnvCfg): state_space = 0 # simulation - sim: SimulationCfg = SimulationCfg(render_interval=decimation, physics_manager_cfg=PhysxManagerCfg(dt=1 / 120)) + sim: SimulationCfg = SimulationCfg(dt=1 / 120, render_interval=decimation) # robot(s) robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(prim_path="/World/envs/env_.*/Robot")