Release Notes#

v2.0.0#

Overview#

Isaac Lab 2.0 brings some exciting new features, including a new addition to the Imitation Learning workflow with the Isaac Lab Mimic extension. Isaac Lab Mimic provides the ability to automatically generate additional trajectories based on just a few human collected demonstrations, allowing for larger training datasets with less human effort. This work is based on the MimicGenv work for Scalable Robot Learning using Human Demonstrations.

Additionally, we introduced a new set of AMP tasks based on Adversarial Motion Priors, training humanoid robots to walk, run, and dance 👯

Along with Isaac Lab 2.0, Isaac Sim 4.5 brings several new and breaking changes, including a full refactor of the Isaac Sim extensions, an improved URDF importer, an update to the PyTorch dependency to version 2.5.1, and many fixes for tiled rendering that now supports multiple tiled cameras at different resolutions.

To follow the refactoring in Isaac Sim, we made similar refactoring and restructuring changes to Isaac Lab. These breaking changes will no longer be compatible with previous Isaac Sim versions. Please make sure to update to Isaac Sim 4.5 when using the Isaac Lab 2.0 release.

Please refer to Migration Guide for a detailed list of breaking changes and guides for updating your codebase.

Full Changelog: https://github.com/isaac-sim/IsaacLab/compare/v1.4.0…v2.0.0

New Features#

  • Adds humanoid AMP tasks for direct workflow by @Toni-SM

  • Adds Isaac Lab Mimic based on MimicGen data generation for Imitation Learning by @peterd-NV @nvcyc @ashwinvkNV @karsten-nvidia

  • Adds consolidated demo script for showcasing recording and mimic dataset generation in real-time in one simulation script by @nvcyc

  • Adds Franka stacking environment for GR00T mimic by @peterd-NV @nvcyc

  • Adds option to filter collisions and real-time playback by @kellyguo11

Improvements#

  • Adds body tracking option to ViewerCfg by @KyleM73 in isaac-sim/IsaacLab#1620

  • Updates pip installation documentation to clarify options by @steple in isaac-sim/IsaacLab#1621

  • Adds dict conversion test for ActuatorBase configs by @mschweig in isaac-sim/IsaacLab#1608

  • Adds documentation and demo script for IMU sensor by @mpgussert in isaac-sim/IsaacLab#1694

  • Removes deprecation for root_state_w properties and setters by @jtigue-bdai in isaac-sim/IsaacLab#1695

  • Adds a tutorial for policy inference in a prebuilt USD scene by @oahmednv

  • Adds unit tests for multi tiled cameras by @matthewtrepte

  • Updates render setting defaults for better quality by @kellyguo11

  • Adds flag to wait for texture loading completion when reset by @oahmednv

  • Adds pre-trained checkpoints and tools for generating and uploading checkpoints by @nv-cupright

  • Adds new denoiser optimization flags for rendering by @kellyguo11

  • Updates torch to 2.5.1 by @kellyguo11

Bug Fixes#

  • Fixes JointAction not preserving order when using all joints by @T-K-233 in isaac-sim/IsaacLab#1587

  • Fixes event term for pushing root by setting velocity by @Mayankm96 in isaac-sim/IsaacLab#1584

  • Fixes error in Articulation where default_joint_stiffness and default_joint_damping is not correctly set if actuator is instance of ImplicitActuator by @zoctipus in isaac-sim/IsaacLab#1580

  • Fixes MARL workflows for recording videos during training/inferencing by @Rishi-V in isaac-sim/IsaacLab#1596

  • Fixes the joint_parameter_lookup type in RemotizedPDActuatorCfg to support list format by @fan-ziqi in isaac-sim/IsaacLab#1626

  • Fixes action reset of pre_trained_policy_action by @nicolaloi in isaac-sim/IsaacLab#1623

  • Fixes issue where the indices were not created correctly. by @AntoineRichard in isaac-sim/IsaacLab#1660

  • Fixes errors in tools and tutorial scripts by @kellyguo11 in isaac-sim/IsaacLab#1669

  • Fixes rigid object’s root com velocities timestamp check by @ori-gadot in isaac-sim/IsaacLab#1674

  • Fixes infinite loop in repeated_objects_terrain: respawn only wrong object samples by @nicolaloi in isaac-sim/IsaacLab#1612

  • Corrects calculation of target height adjustment based on sensor data by @fan-ziqi in isaac-sim/IsaacLab#1710

  • Clarifies Ray Documentation and Fixes Minor Issues by @garylvov in isaac-sim/IsaacLab#1717

  • Fixes external force buffers to set to zero when no forces/torques are applied by @matthewtrepte

Breaking Changes#

  • Updates the URDF and MJCF importers for Isaac Sim 4.5 by @Dhoeller19

  • Renames Isaac Lab extensions and folders by @kellyguo11

  • Restructures extension folders and removes old imitation learning scripts by @kellyguo11

Migration Guide#

Renaming of Isaac Sim Extensions#

Previously, Isaac Sim extensions have been following the convention of omni.isaac.*, such as omni.isaac.core. In Isaac Sim 4.5, Isaac Sim extensions have been renamed to use the prefix isaacsim, replacing omni.isaac. In addition, many extensions have been renamed and split into multiple extensions to prepare for a more modular framework that can be customized by users through the use of app templates.

Notably, the following commonly used Isaac Sim extensions in Isaac Lab are renamed as follow:

  • omni.isaac.cloner –> isaacsim.core.cloner

  • omni.isaac.core.prims –> isaacsim.core.prims

  • omni.isaac.core.simulation_context –> isaacsim.core.api.simulation_context

  • omni.isaac.core.utils –> isaacsim.core.utils

  • omni.isaac.core.world –> isaacsim.core.api.world

  • omni.isaac.kit.SimulationApp –> isaacsim.SimulationApp

  • omni.isaac.ui –> isaacsim.gui.components

Renaming of the URDF and MJCF Importers#

Starting from Isaac Sim 4.5, the URDF and MJCF importers have been renamed to be more consistent with the other extensions in Isaac Sim. The importers are available on isaac-sim GitHub as open source projects.

Due to the extension name change, the Python module names have also been changed:

  • URDF Importer: isaacsim.asset.importer.urdf (previously omni.importer.urdf)

  • MJCF Importer: isaacsim.asset.importer.mjcf (previously omni.importer.mjcf)

From the Isaac Sim UI, both URDF and MJCF importers can now be accessed directly from the File > Import menu when selecting a corresponding .urdf or .xml file in the file browser.

Changes in URDF Importer#

Isaac Sim 4.5 brings some updates to the URDF Importer, with a fresh UI to allow for better configurations when importing robots from URDF. As a result, the Isaac Lab URDF Converter has also been updated to reflect these changes. The UrdfConverterCfg includes some new settings, such as PDGainsCfg and NaturalFrequencyGainsCfg classes for configuring the gains of the drives.

One breaking change to note is that the UrdfConverterCfg.JointDriveCfg.gains attribute must be of class type PDGainsCfg or NaturalFrequencyGainsCfg.

The stiffness of the PDGainsCfg must be specified, as such:

The natural_frequency must be specified for NaturalFrequencyGainsCfg.

Renaming of omni.isaac.core Classes#

Isaac Sim 4.5 introduced some naming changes to the core prim classes that are commonly used in Isaac Lab. These affect the single and View variations of the prim classes, including Articulation, RigidPrim, XFormPrim, and others. Single-object classes are now prefixed with Single, such as SingleArticulation, while tensorized View classes now have the View suffix removed.

The exact renamings of the classes are as follow:

  • Articulation –> SingleArticulation

  • ArticulationView –> Articulation

  • ClothPrim –> SingleClothPrim

  • ClothPrimView –> ClothPrim

  • DeformablePrim –> SingleDeformablePrim

  • DeformablePrimView –> DeformablePrim

  • GeometryPrim –> SingleGeometryPrim

  • GeometryPrimView –> GeometryPrim

  • ParticleSystem –> SingleParticleSystem

  • ParticleSystemView –> ParticleSystem

  • RigidPrim –> SingleRigidPrim

  • RigidPrimView –> RigidPrim

  • XFormPrim –> SingleXFormPrim

  • XFormPrimView –> XFormPrim

Renaming of Isaac Lab Extensions and Folders#

Corresponding to Isaac Sim 4.5 changes, we have also made some updates to the Isaac Lab directories and extensions. All extensions that were previously under source/extensions are now under the source/ directory directly. The source/apps and source/standalone folders have been moved to the root directory and are now called apps/ and scripts/.

Isaac Lab extensions have been renamed to:

  • omni.isaac.lab –> isaaclab

  • omni.isaac.lab_assets –> isaaclab_assets

  • omni.isaac.lab_tasks –> isaaclab_tasks

In addition, we have split up the previous source/standalone/workflows directory into scripts/imitation_learning and scripts/reinforcement_learning directories. The RSL RL, Stable-Baselines, RL_Games, SKRL, and Ray directories are under scripts/reinforcement_learning, while Robomimic and the new Isaac Lab Mimic directories are under scripts/imitation_learning.

To assist with the renaming of Isaac Lab extensions in your project, we have provided a simple script that will traverse through the source and docs directories in your local Isaac Lab project and replace any instance of the renamed directories and imports. Please use the script at your own risk as it will overwrite source files directly.

Restructuring of Isaac Lab Extensions#

With the introduction of isaaclab_mimic, designed for supporting data generation workflows for imitation learning, we have also split out the previous wrappers folder under isaaclab_tasks to its own module, named isaaclab_rl. This new extension will contain reinforcement learning specific wrappers for the various RL libraries supported by Isaac Lab.

The new isaaclab_mimic extension will also replace the previous imitation learning scripts under the robomimic folder. We have removed the old scripts for data collection and dataset preparation in favor of the new mimic workflow. For users who prefer to use the previous scripts, they will be available in previous release branches.

Additionally, we have also restructured the isaaclab_assets extension to be split into robots and sensors subdirectories. This allows for clearer separation between the pre-defined configurations provided in the extension. For any existing imports such as from omni.isaac.lab_assets.anymal import ANYMAL_C_CFG, please replace it with from isaaclab.robots.anymal import ANYMAL_C_CFG.

New Contributors#

v1.4.0#

Overview#

Due to a great amount of amazing updates, we are putting out one more Isaac Lab release based off of Isaac Sim 4.2. This release contains many great new additions and bug fixes, including several new environments, distributed training and hyperparameter support with Ray, new live plot feature for Manager-based environments, and more.

We will now spend more focus on the next Isaac Lab release geared towards the new Isaac Sim 4.5 release coming soon. The upcoming release will contain breaking changes in both Isaac Lab and Isaac Sim and breaks backwards compatibility, but will come with many great fixes and improvements.

Full Changelog: https://github.com/isaac-sim/IsaacLab/compare/v1.3.0…v1.4.0

New Features#

Improvements#

Bug Fixes#

Breaking Changes#

New Contributors#

v1.3.0#

Overview#

This release will be a final release based on Isaac Sim 4.2 before the transition to Isaac Sim 4.5, which will likely contain breaking changes and no longer backwards compatible with Isaac Sim 4.2 and earlier. In this release, we introduce many features, improvements, and bug fixes, including IMU sensors, support for various types of gymnasium spaces, manager-based perception environments, and more.

Full Changelog: https://github.com/isaac-sim/IsaacLab/compare/v1.2.0…v1.3.0

New Features#

Improvements#

Bug Fixes#

New Contributors#

v1.2.0#

Overview#

We leverage the new release of Isaac Sim, 4.2.0, and bring RTX-based tiled rendering, support for multi-agent environments, and introduce many bug fixes and improvements.

Additionally, we have published an example for generating rewards using an LLM based on Eureka, available here isaac-sim/IsaacLabEureka.

Full Changelog: https://github.com/isaac-sim/IsaacLab/compare/v1.1.0…v1.2.0

New Features#

  • Adds RTX-based tiled rendering. This improves the overall rendering speed and quality.

  • Adds the direct workflow perceptive Shadowhand Cube Repose environment Isaac-Repose-Cube-Shadow-Vision-Direct-v0 by @kellyguo11.

  • Adds support for multi-agent environments with the Direct workflow, with support for MAPPO and IPPO in SKRL by @Toni-SM

  • Adds the direct workflow multi-agent environments Isaac-Cart-Double-Pendulum-Direct-v0 and Isaac-Shadow-Hand-Over-Direct-v0 by @Toni-SM

  • Adds throughput benchmarking scripts for the different learning workflows by @kellyguo11 in isaac-sim/IsaacLab#759

  • Adds results for the benchmarks in the documentation here for different types of hardware by @kellyguo11

  • Adds the direct workflow Allegro hand environment by @kellyguo11 in isaac-sim/IsaacLab#709

  • Adds video recording to the play scripts in RL workflows by @j3soon in isaac-sim/IsaacLab#763

  • Adds comparison tables for the supported RL libraries here by @kellyguo11

  • Add APIs for deformable asset by @masoudmoghani in isaac-sim/IsaacLab#630

  • Adds support for MJCF converter by @qqqwan in isaac-sim/IsaacLab#957

  • Adds a function to define camera configs through intrinsic matrix by @pascal-roth in isaac-sim/IsaacLab#617

  • Adds configurable modifiers to observation manager by @jtigue-bdai in isaac-sim/IsaacLab#830

  • Adds the Hydra configuration system for RL training by @Dhoeller19 in isaac-sim/IsaacLab#700

Improvements#

Bug Fixes#

  • Fixes rendering frame delays. Rendered images now faithfully represent the latest state of the physics scene. We added the flag

rerender_on_reset in the environment configs to toggle an additional render step when a reset happens. When activated, the images/observation always represent the latest state of the environment, but this also reduces performance. * Fixes wrap_to_pi function in math utilities by @Mayankm96 in isaac-sim/IsaacLab#771 * Fixes setting of pose when spawning a mesh by @masoudmoghani in isaac-sim/IsaacLab#692 * Fixes caching of the terrain using the terrain generator by @Mayankm96 in isaac-sim/IsaacLab#757 * Fixes running train scripts when rsl_rl is not installed by @Dhoeller19 in isaac-sim/IsaacLab#784, isaac-sim/IsaacLab#789 * Adds flag to recompute inertia when randomizing the mass of a rigid body by @Mayankm96 in isaac-sim/IsaacLab#989 * Fixes support for classmethod when defining a configclass by @Mayankm96 in isaac-sim/IsaacLab#901 * Fixes Sb3VecEnvWrapper to clear buffer on reset by @EricJin2002 in isaac-sim/IsaacLab#974 * Fixes venv and conda pip installation on windows by @kellyguo11 in isaac-sim/IsaacLab#970 * Sets native livestream extensions to Isaac Sim 4.1-4.0 defaults by @jtigue-bdai in isaac-sim/IsaacLab#954 * Defaults the gym video recorder fps to match episode decimation by @ozhanozen in isaac-sim/IsaacLab#894 * Fixes the event manager’s apply method by @kellyguo11 in isaac-sim/IsaacLab#936 * Updates camera docs with world units and introduces new test for intrinsics by @pascal-roth in isaac-sim/IsaacLab#886 * Adds the ability to resume training from a checkpoint with rl_games by @sizsJEon in isaac-sim/IsaacLab#797

Breaking Changes#

  • Simplifies device setting in SimulationCfg and AppLauncher by @Dhoeller19 in isaac-sim/IsaacLab#696

  • Fixes conflict in teleop-device command line argument in scripts by @Dhoeller19 in isaac-sim/IsaacLab#791

  • Converts container.sh into Python utilities by @hhansen-bdai in isaac-sim/IsaacLab

  • Drops support for TiledCamera for Isaac Sim 4.1

Migration Guide#

Setting the simulation device into the simulation context#

Previously, changing the simulation device to CPU required users to set other simulation parameters (such as disabling GPU physics and GPU pipelines). This made setting up the device appear complex. We now simplify the checks for device directly inside the simulation context, so users only need to specify the device through the configuration object.

Before:

sim_utils.SimulationCfg(device="cpu", use_gpu_pipeline=False, dt=0.01, physx=sim_utils.PhysxCfg(use_gpu=False))

Now:

sim_utils.SimulationCfg(device="cpu", dt=0.01, physx=sim_utils.PhysxCfg())

Setting the simulation device from CLI#

Previously, users could specify the device through the command line argument --device_id. However, this made it ambiguous when users wanted to set the device to CPU. Thus, instead of the device ID, users need to specify the device explicitly through the argument --device. The valid options for the device name are:

  • “cpu”: runs simulation on CPU

  • “cuda”: runs simulation on GPU with device ID at default index

  • “cuda:N”: runs simulation on GPU with device ID at N. For instance, “cuda:0” will use device at index “0”.

Due to the above change, the command line interaction with some of the scripts has changed.

Before:

./isaaclab.sh -p source/standalone/workflows/sb3/train.py --task Isaac-Cartpole-v0 --headless --cpu

Now:

./isaaclab.sh -p source/standalone/workflows/sb3/train.py --task Isaac-Cartpole-v0 --headless --device cpu

Renaming of teleoperation device CLI in standalone scripts#

Since --device is now an argument provided by the AppLauncher, it conflicted with the command-line argument used for specifying the teleoperation-device in some of the standalone scripts. Thus, to fix this conflict, the teleoperation-device now needs to be specified through --teleop_device argument.

Before:

./isaaclab.sh -p source/standalone/environments/teleoperation/teleop_se3_agent.py --task Isaac-Lift-Cube-Franka-IK-Rel-v0 --num_envs 1 --device keyboard

Now:

./isaaclab.sh -p source/standalone/environments/teleoperation/teleop_se3_agent.py --task Isaac-Lift-Cube-Franka-IK-Rel-v0 --num_envs 1 --teleop_device keyboard

Using Python-version of container utility script#

The prior container.sh became quite complex as it had many different use cases in one script. For instance, building a docker image for “base” or “ros2”, as well as cluster deployment. As more users wanted to have the flexibility to overlay their own docker settings, maintaining this bash script became cumbersome. Hence, we migrated its features into a Python script in this release. Additionally, we split the cluster-related utilities into their own script inside the docker/cluster directory.

We still maintain backward compatibility for container.sh. Internally, it calls the Python script container.py. We request users to use the Python script directly.

Before:

./docker/container.sh start

Now:

./docker/container.py start

Using separate directories for logging videos in RL workflows#

Previously, users could record videos during the RL training by specifying the --video flag to the train.py script. The videos would be saved inside the videos directory in the corresponding log directory of the run.

Since many users requested to also be able to record videos while inferencing the policy, recording videos have also been added to the play.py script. Since changing the prefix of the video file names is not possible, the videos from the train and play scripts are saved inside the videos/train and videos/play directories, respectively.

Drops support for the tiled camera with Isaac Sim 4.1#

Various fixes have been made to the tiled camera rendering pipeline in Isaac Sim 4.2. This made supporting the tiled camera with Isaac Sim 4.1 difficult. Hence, for the best experience, we advice switching to Isaac Sim 4.2 with this release of Isaac Lab.

New Contributors#

v1.1.0#

Overview#

With the release of Isaac Sim 4.0 and 4.1, support for Isaac Sim 2023.1.1 has been discontinued. We strongly encourage all users to upgrade to Isaac Sim 4.1 to take advantage of the latest features and improvements. For detailed information on this upgrade, please refer to the release notes available here.

Besides the above, the Isaac Lab release brings new features and improvements, as detailed below. We thank all our contributors for their continued support.

Full Changelog: https://github.com/isaac-sim/IsaacLab/compare/v1.0.0…v1.1.0

New Features#

Improvements#

Bug Fixes#

Breaking Changes#

  • Drops official support for Isaac Sim 2023.1.1

  • Removes the use of body view inside the asset classes by @Mayankm96 in isaac-sim/IsaacLab#643

  • Renames SimulationCfg.substeps to SimulationCfg.render_interval by @Dhoeller19 in isaac-sim/IsaacLab#515

Migration Guide#

Renaming of SimulationCfg.substeps#

Previously, the users set both omni.isaac.lab.sim.SimulationCfg.dt and omni.isaac.lab.sim.SimulationCfg.substeps, which marked the physics insulation time-step and sub-steps, respectively. It was unclear whether sub-steps meant the number of integration steps inside the physics time-step dt or the number of physics steps inside a rendering step.

Since in the code base, the attribute was used as the latter, it has been renamed to render_interval for clarity.

Removal of Deprecated Attributes#

As notified in previous releases, we removed the classes and attributes marked as deprecated. These are as follows:

  • The mdp.add_body_mass method in the events. Please use the mdp.randomize_rigid_body_mass instead.

  • The classes managers.RandomizationManager and managers.RandomizationTermCfg. Please use the managers.EventManager and managers.EventTermCfg classes instead.

  • The following properties in omni.isaac.lab.sensors.FrameTransformerData:
    • target_rot_source –> target_quat_w

    • target_rot_w –> target_quat_source

    • source_rot_w –> source_quat_w

  • The attribute body_physx_view from the omni.isaac.lab.assets.Articulation and omni.isaac.lab.assets.RigidObject classes. These caused confusion when used with the articulation view since the body names did not follow the same ordering.

New Contributors#

v1.0.0#

Overview#

Welcome to the first official release of Isaac Lab!

Building upon the foundation of the Orbit framework, we have integrated the RL environment designing workflow from OmniIsaacGymEnvs. This allows users to choose a suitable task-design approach for their applications.

While we maintain backward compatibility with Isaac Sim 2023.1.1, we highly recommend using Isaac Lab with Isaac Sim 4.0.0 version for the latest features and improvements.

Full Changelog: https://github.com/isaac-sim/IsaacLab/compare/v0.3.1…v1.0.0

New Features#

  • Integrated CI/CD pipeline, which is triggered on pull requests and publishes the results publicly

  • Extended support for Windows OS platforms

  • Added tiled rendered based Camera sensor implementation. This provides optimized RGB-D rendering throughputs of up to 10k frames per second.

  • Added support for multi-GPU and multi-node training for the RL-Games library

  • Integrated APIs for environment designing (direct workflow) without relying on managers

  • Added implementation of delayed PD actuator model

  • Added various new learning environments: * Cartpole balancing using images * Shadow hand cube reorientation * Boston Dynamics Spot locomotion * Unitree H1 and G1 locomotion * ANYmal-C navigation * Quadcopter target reaching

Improvements#

  • Reduced start-up time for scripts (inherited from Isaac Sim 4.0 improvements)

  • Added lazy buffer implementation for rigid object and articulation data. Instead of updating all the quantities at every step call, the lazy buffers are updated only when the user queries them

  • Added SKRL support to more environments

Breaking Changes#

For users coming from Orbit, this release brings certain breaking changes. Please check the migration guide for more information.

Migration Guide#

Please find detailed migration guides as follows:

New Contributors#