Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion source/isaaclab/isaaclab/sim/_impl/newton_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -291,7 +291,7 @@ def step(cls) -> None:

if NewtonManager._cfg.debug_mode:
convergence_data = NewtonManager.get_solver_convergence_steps()
# print(f"solver niter: {convergence_data}")
print(f"solver niter: {convergence_data}")
if convergence_data["max"] == NewtonManager._solver.mjw_model.opt.iterations:
print("solver didn't converge!", convergence_data["max"])

Expand Down
12 changes: 12 additions & 0 deletions source/isaaclab/isaaclab/sim/simulation_context.py
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,7 @@ def __init__(self, cfg: SimulationCfg | None = None):
# Try to get existing stage from USD StageCache
stage_cache = UsdUtils.StageCache.Get()
if stage_cache.Size() > 0:
logger.info("USD stage found in StageCache. Getting the first stage.")
all_stages = stage_cache.GetAllStages()
if all_stages:
self._initial_stage = all_stages[0]
Expand All @@ -178,14 +179,23 @@ def __init__(self, cfg: SimulationCfg | None = None):
else:
# No stage exists, try omni.usd as fallback
try:
logger.info("No USD stage found in StageCache. Using omni.usd as fallback.")
import omni.usd

self._initial_stage = omni.usd.get_context().get_stage()
if self._initial_stage is None:
logger.warning("No USD stage found using omni.usd. Creating a new stage in memory.")
self._initial_stage = create_new_stage_in_memory()
except (ImportError, AttributeError):
# if we need to create a new stage outside of omni.usd, we have to do it in memory with USD core APIs
logger.info("No USD stage found. Creating a new stage in memory.")
self._initial_stage = create_new_stage_in_memory()
stage_cache.Insert(self._initial_stage)
# raise RuntimeError("No USD stage is currently open. Please create a stage first.")

if self._initial_stage is None:
raise RuntimeError("No USD stage found. Please create a stage first.")

# Store stage reference for easy access
self.stage = self._initial_stage

Expand Down Expand Up @@ -1331,6 +1341,8 @@ def clear_instance(cls):
cls._instance.close_visualizers()
# clear stage references
if hasattr(cls._instance, "_initial_stage"):
stage_cache = UsdUtils.StageCache.Get()
stage_cache.Erase(cls._instance._initial_stage)
cls._instance._initial_stage = None
if hasattr(cls._instance, "stage"):
cls._instance.stage = None
Expand Down
2 changes: 0 additions & 2 deletions source/isaaclab_assets/isaaclab_assets/robots/anymal.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@
saturation_effort=120.0,
effort_limit=80.0,
effort_limit_sim=80.0,
friction=0.001,
velocity_limit=7.5,
stiffness={".*": 40.0},
damping={".*": 5.0},
Expand All @@ -46,7 +45,6 @@
network_file=f"{ISAACLAB_NUCLEUS_DIR}/ActuatorNets/ANYbotics/anydrive_3_lstm_jit.pt",
saturation_effort=120.0,
effort_limit_sim=120.0,
friction=0.001,
effort_limit=80.0,
velocity_limit=7.5,
)
Expand Down
3 changes: 0 additions & 3 deletions source/isaaclab_assets/isaaclab_assets/robots/unitree.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,12 +74,9 @@
joint_names_expr=[".*_hip_joint", ".*_thigh_joint", ".*_calf_joint"],
effort_limit=33.5,
saturation_effort=33.5,
# effort_limit_sim=33.5,
velocity_limit=21.0,
stiffness=25.0,
damping=0.5,
# friction=1e-3,
# armature=1e-3,
),
},
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class AllegroHandEnvCfg(DirectRLEnvCfg):
cone="elliptic",
update_data_interval=2,
iterations=100,
ls_iterations=15,
ls_iterations=25,
ls_parallel=True,
# save_to_mjcf="AllegroHand.xml",
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class UnitreeA1FlatEnvCfg(UnitreeA1RoughEnvCfg):
solver_cfg=MJWarpSolverCfg(
njmax=50,
nconmax=30,
ls_iterations=10,
ls_iterations=40,
cone="elliptic",
impratio=100,
ls_parallel=True,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class AnymalBFlatEnvCfg(AnymalBRoughEnvCfg):
solver_cfg=MJWarpSolverCfg(
njmax=50,
nconmax=15,
ls_iterations=15,
ls_iterations=40,
cone="elliptic",
impratio=100,
ls_parallel=True,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class AnymalCFlatEnvCfg(AnymalCRoughEnvCfg):
solver_cfg=MJWarpSolverCfg(
njmax=50,
nconmax=15,
ls_iterations=15,
ls_iterations=40,
cone="elliptic",
impratio=100,
ls_parallel=True,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,28 +11,28 @@
# Register Gym environments.
##

gym.register(
id="Isaac-Velocity-Rough-Anymal-D-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)


gym.register(
id="Isaac-Velocity-Rough-Anymal-D-Play-v0",
entry_point="isaaclab.envs:ManagerBasedRLEnv",
disable_env_checker=True,
kwargs={
"env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg_PLAY",
"rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg",
"skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
},
)
# gym.register(
# id="Isaac-Velocity-Rough-Anymal-D-v0",
# entry_point="isaaclab.envs:ManagerBasedRLEnv",
# disable_env_checker=True,
# kwargs={
# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg",
# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg",
# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
# },
# )


# gym.register(
# id="Isaac-Velocity-Rough-Anymal-D-Play-v0",
# entry_point="isaaclab.envs:ManagerBasedRLEnv",
# disable_env_checker=True,
# kwargs={
# "env_cfg_entry_point": f"{__name__}.rough_env_cfg:AnymalDRoughEnvCfg_PLAY",
# "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:AnymalDRoughPPORunnerCfg",
# "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
# },
# )


gym.register(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ class AnymalDFlatEnvCfg(AnymalDRoughEnvCfg):
solver_cfg=MJWarpSolverCfg(
njmax=60,
nconmax=25,
ls_iterations=15,
ls_iterations=40,
cone="elliptic",
impratio=100.0,
ls_parallel=True,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,9 @@
#
# SPDX-License-Identifier: BSD-3-Clause

from isaaclab.sim import SimulationCfg
from isaaclab.sim._impl.newton_manager_cfg import NewtonCfg
from isaaclab.sim._impl.solvers_cfg import MJWarpSolverCfg
from isaaclab.utils import configclass

from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg
Expand All @@ -15,6 +18,22 @@

@configclass
class AnymalDRoughEnvCfg(LocomotionVelocityRoughEnvCfg):
sim: SimulationCfg = SimulationCfg(
newton_cfg=NewtonCfg(
solver_cfg=MJWarpSolverCfg(
njmax=60,
nconmax=25,
ls_iterations=40,
cone="elliptic",
impratio=100.0,
ls_parallel=True,
use_mujoco_contacts=False,
),
num_substeps=1,
debug_mode=False,
)
)

def __post_init__(self):
# post init of parent
super().__post_init__()
Expand Down
31 changes: 4 additions & 27 deletions source/isaaclab_tasks/test/test_environments.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,29 +8,18 @@
# Omniverse logger
import logging

from isaaclab.app import AppLauncher

# # Import pinocchio in the main script to force the use of the dependencies installed by IsaacLab and not the one installed by Isaac Sim
# # pinocchio is required by the Pink IK controller
# if sys.platform != "win32":
# import pinocchio # noqa: F401


# launch the simulator
app_launcher = AppLauncher(headless=True, enable_cameras=True)
simulation_app = app_launcher.app


"""Rest everything follows."""

import gymnasium as gym
import os
import torch

import carb
import omni.usd
import pytest
from isaacsim.core.version import get_version

from isaaclab.envs import ManagerBasedRLEnvCfg
from isaaclab.envs.utils.spaces import sample_space
Expand All @@ -46,19 +35,18 @@
def setup_environment():
# disable interactive mode for wandb for automate environments
os.environ["WANDB_DISABLED"] = "true"
os.environ["LAUNCH_OV_APP"] = "0"
# acquire all Isaac environments names
registered_tasks = list()
for task_spec in gym.registry.values():
# skip camera environments.
if "RGB" in task_spec.id or "Depth" in task_spec.id or "Vision" in task_spec.id:
continue
# TODO: Factory environments causes test to fail if run together with other envs
if "Isaac" in task_spec.id and not task_spec.id.endswith("Play-v0") and "Factory" not in task_spec.id:
registered_tasks.append(task_spec.id)
# sort environments by name
registered_tasks.sort()
# this flag is necessary to prevent a bug where the simulation gets stuck randomly when running the
# test on many environments.
carb_settings_iface = carb.settings.get_settings()
carb_settings_iface.set_bool("/physics/cooking/ujitsoCollisionCooking", False)

return registered_tasks


Expand All @@ -73,11 +61,6 @@ def test_environments(task_name, num_envs, device):
def _run_environments(task_name, device, num_envs, num_steps, create_stage_in_memory):
"""Run all environments and check environments return valid signals."""

# skip test if stage in memory is not supported
isaac_sim_version = float(".".join(get_version()[2]))
if isaac_sim_version < 5 and create_stage_in_memory:
pytest.skip("Stage in memory is not supported in this version of Isaac Sim")

# skip vision tests because replicator has issues with numpy > 2
if "RGB" in task_name or "Depth" in task_name or "Vision" in task_name:
return
Expand Down Expand Up @@ -112,12 +95,6 @@ def _check_random_actions(
):
"""Run random actions and check environments returned signals are valid."""

if not create_stage_in_memory:
# create a new context stage
omni.usd.get_context().new_stage()

# reset the rtx sensors carb setting to False
carb.settings.get_settings().set_bool("/isaaclab/render/rtx_sensors", False)
try:
# parse configuration
env_cfg: ManagerBasedRLEnvCfg = parse_env_cfg(task_name, device=device, num_envs=num_envs)
Expand Down
28 changes: 0 additions & 28 deletions source/isaaclab_tasks/test/test_environments_standalone.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,26 +19,16 @@

import logging

from isaaclab.app import AppLauncher

# Launch in pure headless mode without Omniverse
# Setting headless=True and enable_cameras=False triggers standalone mode
app_launcher = AppLauncher(headless=True, enable_cameras=False)
simulation_app = app_launcher.app # Will be None in standalone mode


"""Rest everything follows."""

import gymnasium as gym
import os
import torch

import pytest
from pxr import UsdUtils

from isaaclab.envs import ManagerBasedRLEnvCfg
from isaaclab.envs.utils.spaces import sample_space
from isaaclab.sim.utils import create_new_stage_in_memory

import isaaclab_tasks # noqa: F401
from isaaclab_tasks.utils.parse_cfg import parse_env_cfg
Expand All @@ -47,21 +37,6 @@
logger = logging.getLogger(__name__)


def _reset_stage_for_next_test():
"""Clear the USD stage cache and create a fresh stage for the next test.

This is necessary because in standalone mode, we don't have the Omniverse
USD context to manage stage lifecycle. We need to manually clear the stage
cache and create a new stage.
"""
# Clear all stages from the cache
stage_cache = UsdUtils.StageCache.Get()
stage_cache.Clear()

# Create a fresh stage in memory for the next test
create_new_stage_in_memory()


# Keywords indicating vision/camera-based environments that require Omniverse
VISION_KEYWORDS = ["RGB", "Depth", "Vision", "Camera", "Visuomotor", "Theia"]

Expand Down Expand Up @@ -140,9 +115,6 @@ def _run_environments(task_name, device, num_envs, num_steps):
def _check_random_actions(task_name: str, device: str, num_envs: int, num_steps: int = 1000):
"""Run random actions and check environments returned signals are valid."""

# Reset stage for each new environment test
_reset_stage_for_next_test()

env = None
try:
# parse configuration
Expand Down
8 changes: 0 additions & 8 deletions source/isaaclab_tasks/test/test_hydra.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,6 @@
"""Launch Isaac Sim Simulator first."""

import sys

from isaaclab.app import AppLauncher

# launch the simulator
app_launcher = AppLauncher(headless=True)
simulation_app = app_launcher.app


"""Rest everything follows."""

import functools
Expand Down
Loading
Loading