Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
61d72d4
Fixes broken links in docs
kellyguo11 Oct 29, 2025
4626c61
Adds automated job for checking valid links
kellyguo11 Oct 29, 2025
b78acb6
update job
kellyguo11 Oct 29, 2025
fed6dce
format
kellyguo11 Oct 29, 2025
07cb1f8
fix tests
kellyguo11 Oct 31, 2025
8f4a1a3
add windows build
kellyguo11 Oct 31, 2025
73c3a23
update conftest for windows
kellyguo11 Oct 31, 2025
8ed8391
update install
kellyguo11 Oct 31, 2025
1f4ac3e
update numpy version
kellyguo11 Oct 31, 2025
5a61d2e
update pip installs
kellyguo11 Oct 31, 2025
6ab26d1
test
kellyguo11 Oct 31, 2025
51eaef2
install isaac sim
kellyguo11 Oct 31, 2025
9b89408
update install
kellyguo11 Oct 31, 2025
85875e9
skip some tests on windows
kellyguo11 Oct 31, 2025
a69a7b8
fix linter
kellyguo11 Oct 31, 2025
340fd16
skip some tests on windows
kellyguo11 Nov 3, 2025
a301ced
add whitelist annotator
kellyguo11 Nov 8, 2025
a0dd24f
format
kellyguo11 Nov 8, 2025
eb9fd07
Merge branch 'main' into fix/windows-ci-tests
kellyguo11 Nov 12, 2025
dbe229a
Set WINDOWS_PLATFORM environment variable to true
kellyguo11 Nov 14, 2025
4352b12
fix conftest
kellyguo11 Nov 14, 2025
301dd7c
Adds a test label filter
nv-apoddubny Nov 14, 2025
e690ede
Fixes Missing Directory Error
nv-apoddubny Nov 14, 2025
ba70e7b
Fixes windows test execution command
nv-apoddubny Nov 21, 2025
59a7b06
Adds debugging info to the conftest
nv-apoddubny Nov 21, 2025
350ab8b
Adds debugging info for failing win tests
nv-apoddubny Nov 21, 2025
62d71c4
Added more debugging
nv-apoddubny Nov 25, 2025
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 .github/ISSUE_TEMPLATE/question.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,4 +18,4 @@ Describe the versions that you are currently using:

<!-- Please complete the following description. -->
- Isaac Lab Version: [e.g. 2.3.0]
- Isaac Sim Version: [e.g. 5.1, this can be obtained by `cat ${ISAACSIM_PATH}/VERSION`]
- Isaac Sim Version: [e.g. 6.0, this can be obtained by `cat ${ISAACSIM_PATH}/VERSION`]
371 changes: 370 additions & 1 deletion .github/workflows/build.yml

Large diffs are not rendered by default.

4 changes: 2 additions & 2 deletions isaaclab.bat
Original file line number Diff line number Diff line change
Expand Up @@ -364,7 +364,7 @@ if "%arg%"=="-i" (
call :ensure_cuda_torch

for /d %%d in ("%ISAACLAB_PATH%\source\*") do (
set ext_folder="%%d"
set "ext_folder=%%d"
call :install_isaaclab_extension
)
rem install the python packages for supported reinforcement learning frameworks
Expand Down Expand Up @@ -400,7 +400,7 @@ if "%arg%"=="-i" (
call :ensure_cuda_torch

for /d %%d in ("%ISAACLAB_PATH%\source\*") do (
set ext_folder="%%d"
set "ext_folder=%%d"
call :install_isaaclab_extension
)
rem install the python packages for supported reinforcement learning frameworks
Expand Down
2 changes: 2 additions & 0 deletions pytest.ini
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
[pytest]
markers =
isaacsim_ci: mark test to run in isaacsim ci
windows: mark test to run on windows platforms
arm: mark test to run on ARM platforms
40 changes: 32 additions & 8 deletions scripts/tools/test/test_cosmos_prompt_gen.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
def temp_templates_file():
"""Create temporary templates file."""
temp_file = tempfile.NamedTemporaryFile(suffix=".json", delete=False)
temp_file.close() # Close file handle before opening with json

# Create test templates
test_templates = {
Expand All @@ -34,16 +35,31 @@ def temp_templates_file():

yield temp_file.name
# Cleanup
os.remove(temp_file.name)
try:
os.remove(temp_file.name)
except PermissionError:
# On Windows, wait a bit and retry
import time

time.sleep(0.1)
os.remove(temp_file.name)


@pytest.fixture
def temp_output_file():
"""Create temporary output file."""
temp_file = tempfile.NamedTemporaryFile(suffix=".txt", delete=False)
temp_file.close() # Close file handle immediately
yield temp_file.name
# Cleanup
os.remove(temp_file.name)
try:
os.remove(temp_file.name)
except PermissionError:
# On Windows, wait a bit and retry
import time

time.sleep(0.1)
os.remove(temp_file.name)


class TestCosmosPromptGen:
Expand Down Expand Up @@ -72,14 +88,22 @@ def test_generate_prompt_invalid_file(self):
def test_generate_prompt_invalid_json(self):
"""Test generating a prompt with invalid JSON file."""
# Create a temporary file with invalid JSON
with tempfile.NamedTemporaryFile(suffix=".json", delete=False) as temp_file:
temp_file.write(b"invalid json content")
temp_file.flush()
temp_file = tempfile.NamedTemporaryFile(suffix=".json", delete=False)
temp_file.write(b"invalid json content")
temp_file.flush()
temp_file.close() # Close file handle before cleanup

try:
with pytest.raises(ValueError):
generate_prompt(temp_file.name)
finally:
try:
with pytest.raises(ValueError):
generate_prompt(temp_file.name)
finally:
os.remove(temp_file.name)
except PermissionError:
# On Windows, wait a bit and retry
import time

time.sleep(0.1)
os.remove(temp_file.name)

def test_main_function_single_prompt(self, temp_templates_file, temp_output_file):
Expand Down
11 changes: 10 additions & 1 deletion scripts/tools/test/test_hdf5_to_mp4.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
def temp_hdf5_file():
"""Create temporary HDF5 file with test data."""
temp_file = tempfile.NamedTemporaryFile(suffix=".h5", delete=False)
temp_file.close() # Close file handle before opening with h5py

with h5py.File(temp_file.name, "w") as h5f:
# Create test data structure
for demo_id in range(2): # Create 2 demos
Expand All @@ -42,7 +44,14 @@ def temp_hdf5_file():

yield temp_file.name
# Cleanup
os.remove(temp_file.name)
try:
os.remove(temp_file.name)
except PermissionError:
# On Windows, wait a bit and retry
import time

time.sleep(0.1)
os.remove(temp_file.name)


@pytest.fixture
Expand Down
27 changes: 24 additions & 3 deletions scripts/tools/test/test_mp4_to_hdf5.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
def temp_hdf5_file():
"""Create temporary HDF5 file with test data."""
temp_file = tempfile.NamedTemporaryFile(suffix=".h5", delete=False)
temp_file.close() # Close file handle before opening with h5py

with h5py.File(temp_file.name, "w") as h5f:
# Create test data structure for 2 demos
for demo_id in range(2):
Expand Down Expand Up @@ -49,7 +51,14 @@ def temp_hdf5_file():

yield temp_file.name
# Cleanup
os.remove(temp_file.name)
try:
os.remove(temp_file.name)
except PermissionError:
# On Windows, wait a bit and retry
import time

time.sleep(0.1)
os.remove(temp_file.name)


@pytest.fixture(scope="class")
Expand Down Expand Up @@ -84,9 +93,17 @@ def temp_videos_dir():
def temp_output_file():
"""Create temporary output file."""
temp_file = tempfile.NamedTemporaryFile(suffix=".h5", delete=False)
temp_file.close() # Close file handle immediately
yield temp_file.name
# Cleanup
os.remove(temp_file.name)
try:
os.remove(temp_file.name)
except PermissionError:
# On Windows, wait a bit and retry
import time

time.sleep(0.1)
os.remove(temp_file.name)


class TestMP4ToHDF5:
Expand Down Expand Up @@ -159,7 +176,9 @@ def test_main_function(self, temp_hdf5_file, temp_videos_dir, temp_output_file):
main()

# Check if output file was created with correct data
with h5py.File(temp_output_file, "r") as f:
# Use explicit close() to ensure file is closed on Windows before cleanup
f = h5py.File(temp_output_file, "r")
try:
# Check if original demos were copied
assert "data/demo_0" in f
assert "data/demo_1" in f
Expand All @@ -176,6 +195,8 @@ def test_main_function(self, temp_hdf5_file, temp_videos_dir, temp_output_file):
assert f"data/demo_{demo_id}/obs/gripper_pos" in f
assert f"data/demo_{demo_id}/obs/table_cam" in f
assert f"data/demo_{demo_id}/obs/wrist_cam" in f
finally:
f.close()
finally:
# Restore original argv
sys.argv = original_argv
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
import os
import pathlib
import random
import tempfile
from datetime import datetime

from isaaclab.sim.converters.asset_converter_base_cfg import AssetConverterBaseCfg
Expand Down Expand Up @@ -64,9 +65,9 @@ def __init__(self, cfg: AssetConverterBaseCfg):

# resolve USD directory name
if cfg.usd_dir is None:
# a folder in "/tmp/IsaacLab" by the name: usd_{date}_{time}_{random}
# a folder in the system temp directory by the name: IsaacLab/usd_{date}_{time}_{random}
time_tag = datetime.now().strftime("%Y%m%d_%H%M%S")
self._usd_dir = f"/tmp/IsaacLab/usd_{time_tag}_{random.randrange(10000)}"
self._usd_dir = os.path.join(tempfile.gettempdir(), "IsaacLab", f"usd_{time_tag}_{random.randrange(10000)}")
else:
self._usd_dir = cfg.usd_dir

Expand Down
3 changes: 3 additions & 0 deletions source/isaaclab/test/app/test_non_headless_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,9 @@
from isaaclab.scene import InteractiveScene, InteractiveSceneCfg
from isaaclab.utils import configclass

# Add markers for Windows and ARM platform support
pytestmark = [pytest.mark.windows, pytest.mark.arm]


@configclass
class SensorsSceneCfg(InteractiveSceneCfg):
Expand Down
4 changes: 4 additions & 0 deletions source/isaaclab/test/assets/test_articulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,10 @@
from isaaclab_assets import ANYMAL_C_CFG, FRANKA_PANDA_CFG, SHADOW_HAND_CFG # isort:skip


# Add markers for Windows and ARM platform support
pytestmark = [pytest.mark.windows, pytest.mark.arm]


def generate_articulation_cfg(
articulation_type: str,
stiffness: float | None = 10.0,
Expand Down
3 changes: 3 additions & 0 deletions source/isaaclab/test/assets/test_deformable_object.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,9 @@
from isaaclab.assets import DeformableObject, DeformableObjectCfg
from isaaclab.sim import build_simulation_context

# Add markers for Windows and ARM platform support
pytestmark = [pytest.mark.windows, pytest.mark.arm]


def generate_cubes_scene(
num_cubes: int = 1,
Expand Down
3 changes: 3 additions & 0 deletions source/isaaclab/test/assets/test_rigid_object.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,9 @@
random_orientation,
)

# Add markers for Windows and ARM platform support
pytestmark = [pytest.mark.windows, pytest.mark.arm]


def generate_cubes_scene(
num_cubes: int = 1,
Expand Down
3 changes: 3 additions & 0 deletions source/isaaclab/test/assets/test_rigid_object_collection.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,9 @@
subtract_frame_transforms,
)

# Add markers for Windows and ARM platform support
pytestmark = [pytest.mark.windows, pytest.mark.arm]


def generate_cubes_scene(
num_envs: int = 1,
Expand Down
4 changes: 4 additions & 0 deletions source/isaaclab/test/assets/test_surface_gripper.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,10 @@
# from isaacsim.robot.surface_gripper import GripperView


# Add markers for Windows and ARM platform support
pytestmark = [pytest.mark.windows, pytest.mark.arm]


def generate_surface_gripper_cfgs(
kinematic_enabled: bool = False,
max_grip_distance: float = 0.1,
Expand Down
13 changes: 10 additions & 3 deletions source/isaaclab/test/controllers/test_local_frame_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,11 @@
# pinocchio is required by the Pink IK controller
import sys

import pytest

# Skip all tests in this module on Windows - MUST be before any other imports
pytestmark = pytest.mark.skipif(sys.platform == "win32", reason="Test not supported on Windows")

if sys.platform != "win32":
import pinocchio # noqa: F401

Expand All @@ -19,11 +24,13 @@
import numpy as np
from pathlib import Path

import pinocchio as pin
import pytest

from isaaclab.controllers.pink_ik.local_frame_task import LocalFrameTask
from isaaclab.controllers.pink_ik.pink_kinematics_configuration import PinkKinematicsConfiguration
if sys.platform != "win32":
import pinocchio as pin

from isaaclab.controllers.pink_ik.local_frame_task import LocalFrameTask
from isaaclab.controllers.pink_ik.pink_kinematics_configuration import PinkKinematicsConfiguration

# class TestLocalFrameTask:
# """Test suite for LocalFrameTask class."""
Expand Down
18 changes: 11 additions & 7 deletions source/isaaclab/test/controllers/test_null_space_posture_task.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,14 @@
# pinocchio is required by the Pink IK controller
import sys

import pytest

# Skip all tests in this module on Windows - MUST be before any other imports
pytestmark = pytest.mark.skipif(sys.platform == "win32", reason="Test not supported on Windows")

if sys.platform != "win32":
import pinocchio # noqa: F401
import pinocchio as pin # noqa: F401
else:
import pinocchio # noqa: F401
import pinocchio as pin # noqa: F401

from isaaclab.app import AppLauncher

Expand All @@ -24,11 +26,13 @@
import numpy as np

import pytest
from pink.configuration import Configuration
from pink.tasks import FrameTask
from pinocchio.robot_wrapper import RobotWrapper

from isaaclab.controllers.pink_ik.null_space_posture_task import NullSpacePostureTask
if sys.platform != "win32":
from pink.configuration import Configuration
from pink.tasks import FrameTask
from pinocchio.robot_wrapper import RobotWrapper

from isaaclab.controllers.pink_ik.null_space_posture_task import NullSpacePostureTask


class TestNullSpacePostureTaskSimplifiedRobot:
Expand Down
16 changes: 12 additions & 4 deletions source/isaaclab/test/controllers/test_pink_ik.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,11 @@
# pinocchio is required by the Pink IK controller
import sys

import pytest

# Skip all tests in this module on Windows - MUST be before any other imports
pytestmark = pytest.mark.skipif(sys.platform == "win32", reason="Test not supported on Windows")

if sys.platform != "win32":
import pinocchio # noqa: F401

Expand All @@ -28,16 +33,19 @@

import omni.usd
import pytest
from pink.configuration import Configuration
from pink.tasks import FrameTask

from isaaclab.utils.math import axis_angle_from_quat, matrix_from_quat, quat_from_matrix, quat_inv

import isaaclab_tasks # noqa: F401
import isaaclab_tasks.manager_based.locomanipulation.pick_place # noqa: F401
import isaaclab_tasks.manager_based.manipulation.pick_place # noqa: F401
from isaaclab_tasks.utils.parse_cfg import parse_env_cfg

if sys.platform != "win32":
from pink.configuration import Configuration
from pink.tasks import FrameTask

import isaaclab_tasks.manager_based.locomanipulation.pick_place # noqa: F401
import isaaclab_tasks.manager_based.manipulation.pick_place # noqa: F401


def load_test_config(env_name):
"""Load test configuration based on environment type."""
Expand Down
Loading
Loading