Releases: isaac-sim/IsaacLab
v2.3.0
What's Changed
The Isaac Lab 2.3.0 release, built on Isaac Sim 5.1, delivers enhancements across dexterous manipulation, teleoperation, and learning workflows. It introduces new dexterous environments with advanced training capabilities, expands surface gripper and teleoperation support for a wider range of robots and devices, and integrates SkillGen with the Mimic imitation learning pipeline to enable GPU-accelerated motion planning and skill-based data generation with cuRobo integration.
Key highlights of this release include:
- Dexterous RL (DexSuite): Introduction of two new dexterous manipulation environments using the Kuka arm and Allegro hand setup, with addition of support for Automatic Domain Randomization (ADR) and PBT (Population-Based Training).
- Surface gripper updates: Surface gripper has been extended to support Manager-based workflows, including the addition of
SurfaceGripperActionandSurfaceGripperActionCfg, along with several new environments demonstrating teleoperation examples with surface grippers and the RMPFlow controller. New robots and variations are introduced, including Franka and UR10 with robotiq grippers and suction cups, and Galbot and Agibot robots. - Mimic - SkillGen: SkillGen support has been added for the Mimic Imitation Learning pipeline, introducing cuRobo integration, integrating GPU motion planning with skill-segmented data generation. Note that cuRobo has proprietary licensing terms, please review the cuRobo license carefully before use.
- Mimic - Locomanipulation: Added a new G1 humanoid environment combining RL-based locomotion with IK-based manipulation. A full robot navigation stack is integrated to augment demonstrations with randomization of tabletop pick/place locations, destination and ground obstacles. By segmenting tasks into pick-navigate-place phases, this method enables generation of large-scale loco-manipulation datasets from manipulation-only demonstrations.
- Teleoperation: Upper body inverse kinematics controller is improved by adding a null space posture task that helps enable waist movement on humanoid tasks while regularizing redundant degrees-of-freedom to a preferred upright posture. Additionally, support for Vive and Manus Glove are introduced, providing more options for teleoperation devices.
Full Changelog: v2.2.1...v2.3.0
🔆 Highlighted Features
Dex environments
We have added a new DexSuite, including dexterous Lift and Reorient environments following DextrAH and DexPBT. These environments also demonstrate usage of Automatic Domain Randomization (ADR) and PBT (Population-Based Training)
cube.mp4
rod.mp4
Isaac Lab Mimic - Locomanipulation
We have added a new locomanipulation G1 environment with upper and lower body controllers that enables demonstrations by controlling the arms and fingers, and locomotion by controlling the pelvis instantaneous velocities and height (vx, vy, wz, h). Additionally, the pink-based inverse kinematics controller now supports null-space posture regularization to enable waist DOFs and extend the humanoid robots reach.
Release.Note.-.G1.Locomanipulation.Pick.Place.mp4
We have also extended these in-place locomanipulation tasks with integrated navigation and demonstration augmentation, enabling large-scale pick-navigate-place dataset generation from manipulation-only demonstrations.
locomanipulation-navigation.mp4
💡Isaac Sim 5.1 Updates
- Introduced support for DGX Spark, including multi-architecture Docker images with support for ARM platforms.
- PhysX now offers a new joint parameter tuning tutorial for robotic grippers, along with a new feature for solving articulation collision contacts last to improve on gripper penetration issues, especially for cases with sub-optimally tuned joints.
- Surface grippers has been optimized for better performance. Although support continues to be CPU-only, performance has improved by several orders of magnitude compared to previous releases.
- Windows 10 support ended on October 14, 2025. Microsoft will no longer provide free security, feature, or technical updates for Windows 10. As a result, we will be dropping support for Windows 10 in future releases of Isaac Sim and Lab to ensure the security and functionality of our software.
✨ New Features
Core
- Supports rl games wrapper with dictionary observation by @ooctipus in #3340
- Adds surface gripper support in manager-based workflow by @rebeccazhang0707 in #3174
- Adds two new robots with grippers by @rebeccazhang0707 in #3229
- Adds new Collision Mesh Schema properties by @hapatel-bdai in #2249
- Adds PBT algorithm to rl games by @ooctipus in #3399
Mimic and Teleoperation
- Adds SkillGen framework to Isaac Lab with cuRobo support by @njawale42 in #3303
- Adds locomanipulation data generation via. disjoint navigation by @jaybdub in #3259
- Adds support for manus and vive by @cathyliyuanchen in #3357
- Adds notification widgets at IK error status and Teleop task completion by @lotusl-code in #3356
Environments
- Adds dexterous lift and reorientation manipulation environments by @ooctipus in #3378
- Adds task Reach-UR10e, an end-effector tracking environment by @ashwinvkNV in #3147
- Adds a configuration example for Student-Teacher Distillation by @ClemensSchwarke in #3100
- Adds Locomanipulation Environment with G1 for Mimic workflow by @michaellin6 in #3150
- Adds teleop support for Unitree G1 with Inspire 5-finger hand, take PickPlace task as an example by @yami007007 in #3242
- Adds galbot stack cube tasks, with left_arm_gripper and right_arm_suction, using RMPFlow controller by @rebeccazhang0707 in #3210
- Adds AVP teleop support for Galbot stack tasks by @rwiltz in #3669
- Adds camera to G1 Steering Wheel environment by @jaybdub in #3549
Infrastructure
- Adds YAML Resource Specification To Ray Integration by @binw666 in #2847
- Installs cuda13 on arm builds for Spark by @kellyguo11 in #3396
- Adds arm64 platform for Pink IK setup by @michaellin6 in #3686
- Updates torch installation version to 2.9 for Linux-aarch, and updates opset version from 11 to 18. by @ooctipus in #3706
🔧 Improvements
Core and Infrastructure
- Adds changes for rsl_rl 3.0.1 by @ClemensSchwarke in #2962
- Simplifies cross platform installation setup.py by @ooctipus in #3294
- Updated image build logic and details by @nv-apoddubny in #3649
- Applies the pre-merge CI failure control to the tasks by @nv-apoddubny in #3457
- Updates Isaac Sim 5.1 staging server to production by @kellyguo11 in #3691
- Removes scikit-learn dependency by @ooctipus in #3799
- Removes extra calls to write simulation after reset_idx by @ooctipus in #3446
- Exposes render parameter
/rtx/domeLight/upperLowerStrategyfor dome light by @shauryadNv in #3694 - Adds onnxscript dependency to isaaclab_rl module by @ooctipus in #3722
- Configures mesh collision schemas in
convert_mesh.pyby @zehao-wang in #3558
Mimic and Teleoperation
- Improves recorder performance and add additional recording capability by @peterd-NV in #3302
- Optimizes Kit XR Teleop CPU time by @hougantc-nvda in #3487
- Improves dataset file names and low success rate for trained model on g1 locomanipulation dataset by @michaellin6 in #3503
- Updates the teleop_se3 and record_demos scripts with more helpful description for teleop_device parameter by @rwiltz in #3642
🐛 Bug Fixes
Core
- Fixes missing visible attribute in spawn_ground_plane by @kellyguo11 in #3304
- Moves parameter
platform_heightto the correct mesh terrain configuration by @Mayankm96 in #3316 - Fixes invalid callbacks for debug vis when simulation is restarted by @kellyguo11 in https://github.com/isaac-sim/Isa...
v2.2.1
👀 Overview
This is a minor patch release with some improvements and bug fixes.
Full Changelog: v2.2.0...v2.2.1
✨ New Features
- Adds contact point location reporting to ContactSensor by @jtigue-bdai in #2842
- Adds environments actions/observations descriptors for export by @AntoineRichard in #2730
- Adds RSL-RL symmetry example for cartpole and ANYmal locomotion by @Mayankm96 in #3057
🔧 Improvements
Core API
- Enhances Pink IK controller with null-space posture control and improv… by @michaellin6 in #3149
- Adds periodic logging when checking USD path on Nucleus server by @matthewtrepte in #3221
- Disallows string value written in sb3_ppo_cfg.yaml get evaluated in process_sb3_cfg by @ooctipus in #3110
Infrastructure
- Application Settings
- Disables rate limit for headless and headless rendering app by @matthewtrepte, @kellyguo11 in #3219, #3089
- Disables
rtx.indirrectDiffuse.enabledin render preset balanced and performance modes by @matthewtrepte in #3240 - Sets profiler backend to NVTX by default by @soowanpNV, @rwiltz in #3238, #3255
- Dependencies
- Adds hf-xet license by @hhansen-bdai in #3116
- Fixes new typing-inspection dependency license by @kellyguo11 in #3237
- Testing & Benchmarking
- Adds basic validation tests for scale-based randomization ranges by @louislelay in #3058
- Adds
SensorBasetests by @jtigue-bdai in #3160
- Repository Utilities
- Adds improved readout from install_deps.py by @hhansen-bdai in #3104
- Fixs isaaclab.sh to detect isaacsim_version accurately 4.5 or >= 5.0 by @ooctipus in #3139
- Disables verbose printing in conftest.py by @ooctipus in #3291
- Updates pytest flags to add for isaacsim integration testsing by @ben-johnston-nv in #3247
- Updates CodeOwners to be more fine-grained by @pascal-roth in #3090
- Fixes minor issues in CI by @nv-apoddubny in #3120
🐛 Bug Fixes
Core API
- Asset Interfaces
- Fixes setting friction coefficients into physx in the articulation classes by @ossamaAhmed in #3243
- Sets joint_friction_coeff only for selected physx_env_ids by @ashwinvkNV in #3119
- Manager Interfaces
- MDP Terms
- Fixes termination term effort limit check logic by @moribots in #3163
- Broadcasts environment ids inside
mdp.randomize_rigid_body_comby @Foruck in #3164 - Fixes IndexError in reset_joints_by_scale and reset_joints_by_offset by @Creampelt in #2949
- Fixes
terrain_out_of_boundsto return tensor instead of bool by @fan-ziqi in #3180
Infrastructure
- Fixes distributed training hanging issue by @kellyguo11 in #3273
- Disables generate internal template when detecting isaaclab install via pip by @ooctipus in #3225
- Fixes typo in isaaclab.bat by @ooctipus in #3272
- Updates app pathing for user-provided rendering preset mode by @matthewtrepte in #3148
📜 Documentation
- Adds documentation for Newton integration by @mpgussert in #3271
- Adapts FAQ section in docs with Isaac Sim open-sourcing by @Mayankm96 in #3105
- Changes checkpoint path in rsl-rl to an absolute path in documentation by @fan-ziqi in #3151
- Fix MuJoCo link in docs by @fan-ziqi in #3181
- Adds client version direction to XR document by @lotusl-code in #3246
- Fixes broken link in doc by @kellyguo11 in #3274
- Fix typo in list_envs.py script path by @fbeltrao in #3282
- Fixes Franka blueprint env ID in docs by @louislelay in #3213
- Fixes template docs and restructure imitation learning docs by @pascal-roth in #3283
💔 Breaking Changes
- Improves termination manager logging to report aggregated percentage of environments done due to each term by @ooctipus in #3107
🤗 New Contributors
- @hhansen-bdai made their first contribution in #3116
- @ashwinvkNV made their first contribution in #3119
- @Creampelt made their first contribution in #2949
- @soowanpNV made their first contribution in #3238
- @moribots made their first contribution in #3163
- @CSCSX made their first contribution in #3134
- @ossamaAhmed made their first contribution in #3243
- @Foruck made their first contribution in #3164
- @lotusl-code made their first contribution in #3246
- @ben-johnston-nv made their first contribution in #3247
- @rwiltz made their first contribution in #3255
- @michaellin6 made their first contribution in #3149
- @fbeltrao made their first contribution in #3282
v2.2.0
👀 Overview
Isaac Lab 2.2 brings major upgrades across simulation capabilities, tooling, and developer experience. It expands support for advanced physics features, new environments, and improved testing and documentation workflows. This release includes full compatibility with Isaac Sim 5.0 as well as backwards compatibility with Isaac Sim 4.5.
Key highlights of this release include:
- Enhanced Physics Support: Updated joint friction modeling using the latest PhysX APIs, added support for spatial tendons, and improved surface gripper interactions.
- New Environments for Imitation Learning: Introduction of two new GR1 mimic environments, with domain randomization and visual robustness evaluation, and improved pick-and-place tasks.
- New Contact-Rich Manipulation Tasks: Integration of FORGE and AutoMate tasks for learning fine-grained contact interactions in simulation.
- Teleoperation Improvements: Teleoperation tools have been enhanced with configurable parameters and CloudXR runtime updates, including head tracking and hand tracking.
- Performance & Usability Improvements: Includes support for Stage in Memory and Cloning in Fabric for faster scene creation, new OVD recorder for large-scene GPU-based animation recording, and FSD (Fabric Scene Delegate) for improved rendering speed.
- Improved Documentation: The documentation has been extended and updated to cover new features, resolve common issues, and streamline setup, including updates to teleop system requirements, VS Code integration, and Python environment management.
Full Changelog: v2.1.1...v2.2.0
🔆 Highlighted Features
FORGE environments
As introduced in the FORGE paper, these environments focus on multi-stage assembly tasks that require force-aware manipulation. For more details, please check the PR #2968.
forge.mp4
AutoMate environments
The Automate effort creates a large assembly dataset for training policies over a wide range of assemblies. All 100 assembly parts and their respective environments are now a part of the environment suite. For more information, please check the PR #2507
automate.mp4
Isaac Lab Evaluation Tasks
To simulate and evaluate manipulation policies (such as the Isaac GR00T N1 model), new industrial manipulation tasks using a humanoid robot are now available as a part of the IsaacLabEvalTasks effort. For more information, please check the repository: https://github.com/isaac-sim/IsaacLabEvalTasks
isaaclabevaltasks.mp4
💡Isaac Sim 5.0 Updates
- Fixes rendering issues on Blackwell GPUs that previously resulted in overly noisy renders
- Updates Python version from 3.10 to 3.11
- Updates PyTorch version to torch 2.7.0+cu128, which will include Blackwell support
- Drops official support for Ubuntu 20.04, we now officially support Ubuntu 22.04 and 24.04 Linux platforms
- Isaac Sim 5.0 no longer sets
/app/player/useFixedTimeStepping=Falseby default. We now do this in Isaac Lab. isaaclab.sim.spawners.PhysicsMaterialCfg.improve_patch_frictionis now removed. The simulation will always behave as if this attribute is set to true.- Native Livestreaming support has been removed.
LIVESTREAM=1can now be used for WebRTC streaming over public networks and
LIVESTREAM=2for private and local networks with WebRTC streaming. - Some assets in Isaac Sim have been reworked and restructured. Notably, the following asset paths were updated:
Robots/Ant/ant_instanceable.usd-->Robots/IsaacSim/Ant/ant_instanceable.usdRobots/Humanoid/humanoid_instanceable.usd-->Robots/IsaacSim/Humanoid/humanoid_instanceable.usdRobots/ANYbotics/anymal_instanceable.usd-->Robots/ANYbotics/anymal_c/anymal_c.usdRobots/ANYbotics/anymal_c.usd-->Robots/ANYbotics/anymal_c/anymal_c.usdRobots/Franka/franka.usd-->Robots/FrankaRobotics/FrankaPanda/franka.usdRobots/AllegroHand/allegro_hand_instanceable.usd-->Robots/WonikRobotics/AllegroHand/allegro_hand_instanceable.usdRobots/Crazyflie/cf2x.usd-->Robots/Bitcraze/Crazyflie/cf2x.usdRobots/RethinkRobotics/sawyer_instanceable.usd-->Robots/RethinkRobotics/Sawyer/sawyer_instanceable.usdRobots/ShadowHand/shadow_hand_instanceable.usd-->Robots/ShadowRobot/ShadowHand/shadow_hand_instanceable.usd
✨ New Features
- Adds FORGE tasks for contact-rich manipulation with force sensing to IsaacLab by @noseworm in #2968
- Adds two new GR1 environments for IsaacLab Mimic by @peterd-NV
- Adds stack environment, scripts for Cosmos, and visual robustness evaluation by @shauryadNv
- Updates Joint Friction Parameters to Isaac Sim 5.0 PhysX APIs by @ossamaAhmed in 87130f2
- Adds support for spatial tendons by @ossamaAhmed in 7a176fa
- Adds support and example for SurfaceGrippers by @AntoineRichard in 14a3a7a
- Adds support for stage in memory by @matthewtrepte in 33bcf66
- Adds OVD animation recording feature by @matthewtrepte
🔧 Improvements
- Enables FSD for faster rendering by @nv-mm
- Sets rtx.indirectDiffuse.enabled to True for performance & balanced rendering presets by @matthewtrepte
- Changes runner for post-merge pipeline on self-hosted runners by @nv-apoddubny
- Fixes and improvements for CI pipeline by @nv-apoddubny
- Adds flaky annotation for tests by @kellyguo11
- Updates Mimic test cases to pytest format by @peterd-NV
- Updates cosmos test files to use pytest by @shauryadNv
- Updates onnx and protobuf version due to vulnerabilities by @kellyguo11
- Updates minimum skrl version to 1.4.3 by @Toni-SM in #3053
- Updates to Isaac Sim 5.0 by @kellyguo11
- Updates docker CloudXR runtime version by @lotusl-code
- Removes xr rendering mode by @rwiltz
- Migrates OpenXRDevice from isaacsim.xr.openxr to omni.xr.kitxr by @rwiltz
- Implements teleop config parameters and device factory by @rwiltz
- Updates pick place env to use steering wheel asset by @peterd-NV
- Adds a CLI argument to set epochs for Robomimic training script by @peterd-NV
🐛 Bug Fixes
- Fixes operational space unit test to avoid pi rotation error by @ooctipus
- Fixes GLIBC errors with importing torch before AppLauncher by @kellyguo11 in c80e2af
- Fixes rendering preset by @matthewtrepte in cc0dab6
- Fixes callbacks with stage in memory and organize environment tests by @matthewtrepte in 4dd6a1e
- Fixes XR and external camera bug with async rendering by @rwiltz in c80e2af
- Disables selection for rl_games when marl is selected for template generator by @ooctipus
- Adds check for .gitignore when generating template by @kellyguo11
- Fixes camera obs errors in stack instance randomize envs by @peterd-NV
- Fixes parsing for play envs by @matthewtrepte
- Fixes issues with consecutive python exe calls in isaaclab.bat by @kellyguo11
- Fixes spacemouse add callback function by @peterd-NV in 72f05a2
- Fixes humanoid training with new velocity_limit_sim by @AntoineRichard
📄 Documentation
- Adds note to mimic cosmos pipeline doc for eval by @shauryadNv
- Updates teleop docs for 2.2 release by @rwiltz
- Fixes outdated dofbot path in tutorial scripts by @mpgussert
- Updates docs for VS Code IntelliSense setup and JAX installation by @Toni-SM
- Updates Jax doc to overwrite version < 0.6.0 for torch by @kellyguo11
- Adds docs for fabric cloning & stage in memory by @matthewtrepte
- Updates driver requirements to point to our official technical docs by @mpgussert
- Adds warning for ovd recording warning logs spam by @matthewtrepte
- Adds documentation to specify HOVER version and known GLIBCXX error by @kellyguo11
- Updates teleop system requirements doc by @lotusl-code
- Add network requirements to cloudxr teleop doc by @lotusl-code
v2.1.1
👀 Overview
This release has been in development over the past few months and includes a significant number of updates, enhancements, and new features across the entire codebase. Given the volume of changes, we've grouped them into relevant categories to improve readability. This version is compatible with NVIDIA Isaac Sim 4.5.
We appreciate the community’s patience and contributions in ensuring quality and stability throughout. We're aiming for more frequent patch releases moving forward to improve the developer experience.
Note: This minor release does not include a Docker image or pip package.
Full Changelog: v2.1.0...v2.1.1
✨ New Features
- Asset Interfaces
- Adds
positionargument to set external forces and torques at different locations on the rigid body by @AntoineRichard in #1680 - Adds
body_incoming_joint_wrench_bto ArticulationData field by @jtigue-bdai in #2128 - Allows selecting articulation root prim explicitly by @lgulich in #2228
- Adds
- Sensor Interfaces
- Draws connection lines for FrameTransformer visualization by @Mayankm96 in #1754
- Uses visualization marker for connecting lines inside FrameTransformer by @bikcrum in #2526
- MDP Terms
- Adds
body_pose_wandbody_projected_gravity_bobservations by @jtigue-bdai in #2212 - Adds joint effort observation by @jtigue-bdai in #2211
- Adds CoM randomization term to manager-based events by @shendredm in #1714
- Adds time-based mdp (observation) functions by @TheIndoorDad in #2332
- Adds curriculum mdp term to modify any environment parameters by @ooctipus in #2777
- Adds
- New Example Tasks
🔧 Improvements
Core API
- Actuator Interfaces
- Fixes implicit actuator limits configs for assets by @ooctipus in #2952
- Updates actuator configs for Franka arm by @reeceomahoney in #2492
- Asset Interfaces
- Optimizes getters of data inside asset classes by @Mayankm96 in #2118
- Adds method to set the visibility of the Asset's prims by @Mayankm96 in #1752
- Sensor Interfaces
- Updates to ray caster ray alignment and more customizable drift sampling by @jsmith-bdai in #2556
- Extends ContactSensorData by
force_matrix_w_historyattribute by @bikcrum in #2916 - Adds IMU projected_gravity_b and IMU computation speed optimizations by @jtigue-bdai in #2512
- Manager Interfaces
- Adds serialization to observation and action managers by @jsmith-bdai in #2234
- Adds option to define the concatenation dimension in the
ObservationManagerby @pascal-roth in #2393 - Supports composite observation space with proper min max in manager based env by @ooctipus in #2811
- Changes counter update in
CommandManagerby @pascal-roth in #2393 - Integrates
NoiseModelto manager-based workflows by @ozhanozen in #2755 - Updates
NoiseModelWithAdditiveBiasto apply per-feature bias sampling by @ozhanozen in #2760 - Fixes
isaaclab.scene.reset_toto properly accept None as valid argument by @ooctipus in #2970 - Resets step reward buffer properly when weight is zero by @bikcrum in #2392
- Terrain Generation
- Allows for custom
TerrainGeneratorwithout modifications of theTerrainImporterby @pascal-roth in #2487 - Adds option for terrain border to above or below the ground by @pascal-roth in #2394
- Adds ability to set platform height independent of object height for terrain by @jtigue-bdai in #2695
- Adds absolute and relative noise to
MeshRepeatedObjectsTerrainby @jtigue-bdai in #2830
- Allows for custom
- Simulation
- Raises exceptions from initialization callbacks inside SimContext in #2166
- Applies
semantic_tagsto ground by @KumoLiu in #2410 - Sets
enable_stabilizationto false by default by @AntoineRichard in #2628 - Fixes deprecation warning for pxr.Semantics by @kellyguo11 in #2721
- Math Utilities
- Improves the implementation of
euler_xyz_from_quatby @ShaoshuSu in #2365 - Optimizes
yaw_quatimplementation by @hapatel-bdai in #2247 - Changes to
quat_applyandquat_apply_inversefor speed by @jtigue-bdai in #2129 - Changes
quat_box_minusimplementation by @jtigue-bdai in #2217 - Adds
quat_box_plusandrigid_body_twist_transformby @jtigue-bdai in #2217 - Adds math tests for transforms, rotations, and conversions by @jtigue-bdai in #2801
- Improves the implementation of
- General Utilities
- Simplifies buffer validation check for CircularBuffer by @Mayankm96 in #2617
- Modifies
update_class_from_dict()to wholesale replace flat Iterables by @ozhanozen in #2511 - Allows slicing to be processed from lists inside dictionary by @LinghengMeng @kellyguo11 in #2853
Tasks API
- Adds support for
module:taskand updates gymnasium to >=1.0 by @kellyguo11 in #2467 - Adds available RL library configs on error message if entry point is invalid by @Toni-SM in #2713
- Enables hydra for all play.py scripts by @ooctipus in #2995
- Fixes ray lazy metric reporting and hanging processes by @ozhanozen in #2346
- Adds gradient clipping parameter for distillation using RSL-RL by @alessandroassirelli98 in #2454
- Makes GRU-based RNNs exportable in RSL RL by @WT-MM in #3009
- Adds wandb native support in rl_games by @ooctipus in #2650
- Optimizes Stable-Baselines3 wrapper and additional training configs by @araffin in #2022
- Enables sb3 to load checkpoint to continue training by @ooctipus in #2954
- Supports sb3 wrapper to pre-process env's image obs-space to trigger sb3 natively supported cnn creation pipeline by @ooctipus in #2812
Infrastructure
- Dependencies
- Updates torch to 2.7.0 with cuda 12.8 blackwell support by @kellyguo11 in #2998
- Updates gymnasium to v1.2.0 by @kellyguo11 in #2852
- Fixes numpy ver to <2 for isaaclab_rl and isaaclab_tasks by @ooctipus in #2866
- Adds license file for 3rd party OSS dependencies by @kellyguo11 in #2577
- Sets robomimic version to v0.4.0 by @masoudmoghani in #2814
- Upgrades pillow dependencies for upcoming Kit 107.3.1 by @ooctipus in #2908
- Removes protobuf upper version pin by @kwlzn in #2726
- Docker
- Uses
--gpusinstead of nvidia runtime for docker by @yanziz-nvidia in #2411 - Adds optional suffix parameter for docker name by @zoemcc in #2172
- Adds support for bash history in docker by @AntoineRichard in #2659
- Uses
- Testing & Benchmarking
- Switches unittest to pytest for testing by @kellyguo11 @pascal-roth in #2459
- Adds training benchmark unit tests with input config by @matthewtrepte in #2503
- Fixes failing environment and IK tests by @kellyguo11 in #2372
- Repository Utilities
- Adds script to convert urdfs/meshes to instanceable USD in batches by @hapatel-bdai in #2248
- Adds citation link for the repository by @kellyguo11 in #2935
- Adds Internal temp...
v2.1.0
👀 Overview
This release introduces the official support for teleoperation using the Apple Vision Pro for collecting high-quality and dexterous hand data, including the addition of bi-manual teleoperation and imitation learning workflows through Isaac Lab Mimic.
We have also introduced new randomization methods for USD attributes, including the randomization of scale, color, and textures. In this release, we updated RSL RL to v2.3.1, which introduces many additional features including distributed training, student-teacher distillation, and recurrent student-teacher distillation.
Additionally, we revamped the Extension Template to include an automatic template generator tool from within the Isaac Lab repo. The extension template is a powerful method for users to develop new projects in user-hosted repos, allowing for isolation from the core Isaac Lab repo and changes. The previous IsaacLabExtensionTemplate repo showed a limited example pertaining only to the Manager-based workflow and RSL RL. In the new template generator, users can choose from any supported workflow and RL library, along with the desired RL algorithm. We will be deprecating the standalone IsaacLabExtensionTemplate in the near future.
NVIDIA has also released HOVER as an independent repo, hosting a neural whole body controller for humanoids built on top of Isaac Lab. HOVER includes sim-to-real workflows for deployment on the Unitree H1 robot, which we have also added a tutorial guide for the deployment process in the Isaac Lab documentation.
Full Changelog: v2.0.2...v2.1.0
🔆 Highlighted Features
TextureRandomization.webm
✨ New Features
- Adds new external project / internal task template generator by @Toni-SM in #2039
- Adds dummy agents to the external task template generator by @louislelay in #2221
- Adds USD-level randomization mode to event manager by @Mayankm96 in #2040
- Adds texture and scale randomization event terms by @hapatel-bdai in #2121
- Adds replicator event for randomizing colors by @Mayankm96 in #2153
- Adds interactive demo script for H1 locomotion by @kellyguo11 in #2041
- Adds blueprint environment for Franka stacking mimic by @chengronglai in #1944
- Adds action clipping to rsl-rl wrapper by @Mayankm96 in #2019
- Adds Gymnasium spaces showcase tasks by @Toni-SM in #2109
- Add configs and adapt exporter for RSL-RL distillation by @ClemensSchwarke in #2182
- Adds support for head pose for Open XR device by @rwiltz
- Adds handtracking joints and retargetting pipeline by @rwiltz
- Adds documentation for openxr device and retargeters by @rwiltz
- Adds tutorial for training & validating HOVER policy using Isaac Lab by @pulkitg01
- Adds rendering mode presets by @matthewtrepte
- Adds GR1 scene with Pink IK + Groot Mimic data generation and training by @ashwinvkNV
- Adds absolute pose franka cube stacking environment for mimic by @rwiltz
- Enables CloudXR OpenXR runtime container by @jaczhangnv
- Adds a quick start guide for quick installation and introduction by @mpgussert
🔧 Improvements
- Clarifies the default parameters in ArticulationData by @Mayankm96 in #1875
- Removes storage of meshes inside the TerrainImporter class by @Mayankm96 in #1987
- Adds more details about state in InteractiveScene by @Mayankm96 in #2119
- Mounts scripts to docker container by @Mayankm96 in #2152
- Initializes manager term classes only when sim starts by @Mayankm96 in #2117
- Updates to latest RSL-RL v2.3.0 release by @Mayankm96 in #2154
- Skips dependency installation for directories with no extension.toml by @jsmith-bdai in #2216
- Clarifies layer instructions in animation docs by @tylerlum in #2240
- Lowers the default number of environments for camera envs by @kellyguo11 in #2287
- Updates Rendering Mode guide in documentation by @matthewtrepte
- Adds task instruction UI support for mimic by @chengronglai
- Adds ExplicitAction class to track argument usage in AppLauncher by @nv-mhaselton
- Allows physics reset during simulation by @oahmednv
- Updates mimic to support multi-eef (DexMimicGen) data generation by @nvcyc
🐛 Bug Fixes
- Fixes default effort limit behavior for implicit actuators by @jtigue-bdai in #2098
- Fixes docstrings inconsistencies the code by @Bardreamaster in #2112
- Fixes missing stage recorder extension for animation recorder by @kellyguo11 in #2125
- Fixes ground height in factory environment by @louislelay in #2071
- Removes double definition of render settings by @pascal-roth in #2083
- Fixes device settings in env tutorials by @Mayankm96 in #2151
- Changes default ground color back to dark grey by @Mayankm96 in #2164
- Initializes extras dict before loading managers by @kousheekc in #2178
- Fixes typos in development.rst by @vi3itor in #2181
- Fixes SE gamepad omniverse subscription API by @PinkPanther-ny in #2173
- Fixes modify_action_space in RslRlVecEnvWrapper by @felipemohr in #2185
- Fixes distributed setup in benchmarking scripts by @kellyguo11 in #2194
- Fixes typo
RF_FOOTtoRH_FOOTin tutorials by @likecanyon in #2200 - Checks if success term exists before recording in RecorderManager by @peterd-NV in #2218
- Unsubscribes from debug vis handle when timeline is stopped by @jsmith-bdai in #2214
- Fixes wait time in
play.pyby usingenv.step_dtby @tylerlum in #2239 - Fixes 50 series installation instruction to include torchvision by @kellyguo11 in #2258
- Fixes importing MotionViewer from external scripts by @T-K-233 in #2195
- Resets cuda device after each app.update call by @kellyguo11 in #2283
- Fixes resume flag in rsl-rl cli args by @Mayankm96 in #2299
🤗 New Contributors
- @chengronglai made their first contribution in #1944
- @Bardreamaster made their first contribution in #2112
- @hapatel-bdai made their first contribution in #2121
- @kousheekc made their first contribution in #2178
- @vi3itor made their first contribution in #2181
- @PinkPanther-ny made their first contribution in #2173
- @felipemohr made their first contribution in #2185
- @likecanyon made their first contribution in #2200
- @tylerlum made their first contribution in #2239
- @ClemensSchwarke made their first contribution in #2182
v2.0.2
👀 Overview
This patch release focuses on improving actuator configuration and fixing key bugs while reverting unintended behavioral changes from v2.0.1. We strongly recommend switching to this new version if you're migrating from a pre-2.0 release of Isaac Lab.
Key Changes:
- Actuator limit handling: Introduced
velocity_limit_simandeffort_limit_simto clearly distinguish simulation solver limits from actuator model constraints. Reverted implicit actuator velocity limits to pre-v2.0 behavior - Simulation configuration update: Removed
disable_contact_processingflag to simplify behavior - Rendering configuration update: Reverted to pre-2.0 configuration to improve the quality of the render product
- Tiled camera fixes: Fixed motion vector processing and added a hotfix for retrieving semantic images from the TiledCamera
- WebRTC support: Added IP specification for live-streaming
Full Changelog: v2.0.1...v2.0.2
✨ New Features
- Adds
velocity_limit_simandeffort_limit_simto actuator by @jtigue-bdai in #1654 - Adds WebRTC livestreaming support with IP specification by @sheikh-nv in #1967
🔧 Improvements
- Adds guidelines and examples for code contribution by @Mayankm96 in #1876
- Separates joint state setters inside Articulation class by @Mayankm96 in #1751
- Implements deterministic evaluation for skrl's multi-agent algorithms by @Toni-SM in #1972
- Adds new extensions to
pyproject.tomlby @Mayankm96 in #1988 - Updates docs on Isaac Sim binary installation path and VSCode integration by @j3soon in #1970
- Removes remaining deprecation warning in RigidObject deprecation by @jtigue-bdai in #1851
- Adds security and show&tell notes to documentation by @kellyguo11 in #1830
- Updates docs for segmentation and 50 series GPUs issues by @kellyguo11 in #1943
- Adds workaround for semantic segmentation issue with tiled camera by @kellyguo11 in #1947
🐛 Bug Fixes
- Fixes offset from object obs for Franka stacking env when using parallel envs by @peterd-NV in #1839
- Adds scene update to ManagerBasedEnv, DirectRLEnv and MARL envs initialization by @jtigue-bdai in #1809, #1865
- Loads actuator networks in eval() mode to prevent gradients by @Mayankm96 in #1862
- Fixes instructions on importing ANYmal URDF in docs by @Mayankm96 in #1915
- Fixes setting of root velocities in the event term
reset_root_state_from_terrainby @syundo0730 in #1884 - Fixes
activate_contact_sensorswhen using spawner.MultiUsdFileCfg by @Mayankm96 in #1990 - Fixes misalignment in motion vectors from TiledCamera by @lhy0807 in #2012
- Sets default tensor device to CPU for Camera rot buffer by @kellyguo11 in #2002
💔 Breaking Changes
- Reverts the setting of joint velocity limits for implicit actuators by @Mayankm96 in #1873
- Removes
disable_contact_processingflag from SimulationContext by @Mayankm96 in #1861 - Reverts to old render settings in kit experience files by @pascal-roth in #1855
✈️ Migration Guide
Warning
We strongly recommend reviewing the details to fully understand the change in behavior, as it may impact the deployment of learned policies. Please open an issue on GitHub if you face any problems.
Introduction of simulation's effort and velocity limits parameters in ActuatorBaseCfg
Details
We have introduced the configuration variables velocity_limit_sim and effort_limit_sim to the isaaclab.actuators.ActuatorBaseCfg to allow users to set the simulation joint velocity and effort limits through the actuator configuration class.
Previously, we were overusing the attributes velocity_limit and effort_limit inside the actuator configuration. A series of changes in-between led to a regression from v1.4.0 to v2.0.1 release of IsaacLab. To make this clearer to understand, we note the change in their behavior in a tabular form:
| Actuator Type | Attribute | v1.4.0 Behavior | v2.0.1 Behavior |
|---|---|---|---|
| Implicit | velocity_limit |
Ignored, not set into simulation | Set into simulation |
| Implicit | effort_limit |
Set into simulation | Set into simulation |
| Explicit | velocity_limit |
Used by actuator models (e.g., DC Motor), not set into simulation | Used by actuator models (e.g., DC Motor), set into simulation |
| Explicit | effort_limit |
Used by actuator models, not set into simulation | Used by actuator models, set into simulation |
Setting the limits from the configuration into the simulation directly affects the behavior of the underlying physics engine solver. This impact is particularly noticeable when velocity limits are too restrictive, especially in joints with high stiffness, where it becomes easier to reach these limits. As a result, the change in behavior caused previously trained policies to not function correctly in IsaacLab v2.0.1.
Consequently, we have reverted back to the prior behavior and added velocity_limit_sim and effort_limit_sim attributes to make it clear that setting those parameters means changing solver's configuration. The new behavior is as follows:
| Attribute | Implicit Actuator | Explicit Actuator |
|---|---|---|
velocity_limit |
Ignored, not set into simulation | Used by the model (e.g., DC Motor), not set into simulation |
effort_limit |
Set into simulation (same as effort_limit_sim) |
Used by the models, not set into simulation |
velocity_limit_sim |
Set into simulation | Set into simulation |
effort_limit_sim |
Set into simulation (same as effort_limit) |
Set into simulation |
Users are advised to use the xxx_sim flag if they want to directly modify the solver limits.
Removal of disable_contact_processing flag in SimulationCfg
Related MRs: #1861
Details
We have now removed the disable_contact_processing flag from the SimulationCfg to not have the user worry about these intricacies of the simulator. The flag is always True by default unless a contact sensor is created (which will internally set this flag to False).
Previously, the flag disable_contact_processing led to confusion about its behavior. As the name suggests, the flag controls the contact reporting from the underlying physics engine, PhysX. Disabling this flag (note the double negation) means that PhysX collects the contact information from its solver and allows reporting them to the user. Enabling this flag means this operation is not performed and the overhead of it is avoided.
Many of our examples (for instance, the locomotion environments) were setting this flag to True which meant the contacts should not get reported. However, this issue was not noticed earlier since GPU simulation bypasses this flag, and only CPU simulation gets affected. Running the same examples on CPU device led to different behaviors because of this reason.
Existing users, who currently set this flag themselves, should receive a deprecated warning mentioning the removal of this flag and the switch to the new default behavior.
Switch to older rendering settings to improve render quality
Related MRs: #1855
Details
With the IsaacLab 2.0.0 release, we switched to new render settings aimed at improving tiled-rendering performance, but at the cost of reduced rendering quality. This change particularly affected dome lighting in the scene, which is the default in many of our examples.
As reported by several users, this change negatively impacted render quality, even in cases where it wasn’t necessary (such as when recording videos of the simulation). In response to this feedback, we have reverted to the previous render settings by default to restore the quality users expected.
For users who are looking to trade render quality for speed, we will provide guidelines in the future.
🤗 New Contributors
- @syundo0730 made their first contribution in #1884
- @Gonglitian made their first contribution in #1981
- @lhy0807 made their first contribution in #2012
v2.0.1
👀 Overview
This release contains a small set of fixes and improvements.
The main change was to maintain combability with the updated library name for RSL RL, which breaks the previous installation methods for Isaac Lab. This release provides the necessary fixes and updates in Isaac Lab to accommodate for the name change and maintain combability with installation for RSL RL.
Full Changelog: v2.0.0...v2.0.1
🔧 Improvements
- Switches to RSL-RL install from PyPI by @Mayankm96 in #1811
- Updates the script path in the document by @fan-ziqi in #1766
- Disables extension auto-reload when saving files by @kellyguo11 in #1788
- Updates documentation for v2.0.1 installation by @kellyguo11 in #1818
🐛 Bug Fixes
- Fixes timestamp of com and link buffers when writing articulation pose to sim by @Jackkert in #1765
- Fixes incorrect local documentation preview path in xdg-open command by @louislelay in #1776
- Fixes no matching distribution found for rsl-rl (unavailable) by @samibouziri in #1808
- Fixes reset of sensor drift inside the RayCaster sensor by @zoctipus in #1821
New Contributors
- @Jackkert made their first contribution in #1765
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 MimicGen 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.
Full Changelog: v1.4.1...v2.0.0
🌟 Highlights from the Isaac Sim 4.5 release:
- Support for multiple
TiledCamerainstances and varying resolutions - Improved rendering performance by up to 1.2x
- Faster startup time through optimizations in the Cloner class that improves startup time by 30%
- Enhanced OmniPVD for debugging physics simulation, enabling capturing reinforcement learning simulation workloads of up to 2000 environments
- Physics simulation performance optimizations improving throughput of up to 70%
- Physics support for dedicated cylinder and cone geometry designed for robot wheels that is fully GPU accelerated
- A new physics GPU filtering mechanism allowing co-location of reinforcement learning environments at the origin with minimal performance loss for scenes with limited collider counts
- Improvements in simulation stability for mimic joints at high joint gains
🔆 Highlighted Features
stack-mimic-dataset.mp4
amp-humanoid-walk.mp4
amp-humanoid-dance.mp4
factory-gear-insert.mp4
✨ 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 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 a 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
- Renames default conda and venv Python environment from
isaaclabtoenv_isaaclabby @Toni-SM
🐛 Bug Fixes
- Fixes external force buffers to set to zero when no forces/torques are applied by @matthewtrepte
- Fixes RSL-RL package name in
setup.pyaccording to PyPI installation by @samibouziri
💔 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
- Renames default conda and venv Python environment from
isaaclabtoenv_isaaclabby @Toni-SM
✈️ Migration Guide
Renaming of Isaac Sim Extensions
Details
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.cloneromni.isaac.core.prims-->isaacsim.core.primsomni.isaac.core.simulation_context-->isaacsim.core.api.simulation_contextomni.isaac.core.utils-->isaacsim.core.utilsomni.isaac.core.world-->isaacsim.core.api.worldomni.isaac.kit.SimulationApp-->isaacsim.SimulationAppomni.isaac.ui-->isaacsim.gui.components
Renaming of the URDF and MJCF Importers
Details
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(previouslyomni.importer.urdf) - MJCF Importer:
isaacsim.asset.importer.mjcf(previouslyomni.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
Details
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:
joint_drive=sim_utils.UrdfConverterCfg.JointDriveCfg(
gains=sim_utils.UrdfConverterCfg.JointDriveCfg.PDGainsCfg(stiffness=None, damping=None)
)The natural_frequency attribute must be specified for NaturalFrequencyGainsCfg.
Renaming of Isaac Lab Extensions and Folders
Details
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-->isaaclabomni.isaac.lab_assets-->isaaclab_assetsomni.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
Details
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.
⚠️ Known Issues
Obtaining semantic and instance segmentation from TiledCamera
We have identified a breaking feature for semantic segmentation and instance segmentation when using TiledCamera with instanceable assets. Since the Isaac Sim...
v1.4.1
👀 Overview
This release contains a set of improvements and bug fixes.
Most importantly, we reverted one of the changes from the previous release (#966) to ensure the training throughput performance remains the same.
Full Changelog: v1.4.0...v1.4.1
This is the final release compatible with Isaac Sim 4.2. The next release will target Isaac Sim 4.5, which introduces breaking changes that will make Isaac Lab incompatible with earlier versions of Isaac Sim.
✨ New Features
- Adds documentation and demo script for IMU sensor by @mpgussert in #1694
🔧 Improvements
- Removes deprecation for root_state_w properties and setters by @jtigue-bdai in #1695
- Fixes MARL workflows for recording videos during training/inferencing by @Rishi-V in #1596
- Adds body tracking option to ViewerCfg by @KyleM73 in #1620
- Fixes the
joint_parameter_lookuptype inRemotizedPDActuatorCfgto support list format by @fan-ziqi in #1626 - Updates pip installation documentation to clarify options by @steple in #1621
- Fixes docstrings in Articulation Data that report wrong return dimension by @zoctipus in #1652
- Fixes documentation error for PD Actuator by @kellyguo11 in #1668
- Clarifies ray documentation and fixes minor issues by @garylvov in #1717
- Updates code snippets in documentation to reference scripts by @mpgussert in #1693
- Adds dict conversion test for ActuatorBase configs by @mschweig in #1608
🐛 Bug Fixes
- Fixes JointAction not preserving order when using all joints by @T-K-233 in #1587
- Fixes event term for pushing root by setting velocity by @Mayankm96 in #1584
- Fixes error in Articulation where
default_joint_stiffnessanddefault_joint_dampingare not correctly set for implicit actuator by @zoctipus in #1580 - Fixes action reset of
pre_trained_policy_actionin navigation environment by @nicolaloi in #1623 - Fixes rigid object's root com velocities timestamp check by @ori-gadot in #1674
- Adds interval resampling on event manager's reset call by @Mayankm96 in #1750
- Corrects calculation of target height adjustment based on sensor data by @fan-ziqi in #1710
- Fixes infinite loop in
repeated_objects_terrainmethod by @nicolaloi in #1612 - Fixes issue where the indices were not created correctly for articulation setters by @AntoineRichard in #1660
🤗 New Contributors
- @T-K-233 made their first contribution in #1587
- @steple made their first contribution in #1616
- @Rishi-V made their first contribution in #1596
- @nicolaloi made their first contribution in #1623
- @mschweig made their first contribution in #1608
- @AntoineRichard made their first contribution in #1660
- @ori-gadot made their first contribution in #1674
- @garylvov made their first contribution in #1717
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: v1.3.0...v1.4.0
✨ New Features
- Adds Factory contact-rich manipulation tasks to IsaacLab by @noseworm in #1520
- Adds a Franka stacking ManagerBasedRLEnv by @peterd-NV in #1494
- Adds recorder manager in manager-based environments by @nvcyc in #1336
- Adds Ray Workflow: Multiple Run Support, Distributed Hyperparameter Tuning, and Consistent Setup Across Local/Cloud by @glvov-bdai in #1301
- Adds
OperationSpaceControllerto docs and tests and implement corresponding action/action_cfg classes by @ozhanozen in #913 - Adds null-space control option within
OperationSpaceControllerby @ozhanozen in #1557 - Adds observation term history support to Observation Manager by @jtigue-bdai in #1439
- Adds live plots to managers by @pascal-roth in #893
🔧 Improvements
- Adds documentation and example scripts for sensors by @mpgussert in #1443
- Removes duplicated
TerminationsCfgcode in G1 and H1 RoughEnvCfg by @fan-ziqi in #1484 - Adds option to change the clipping behavior for all Cameras and unifies the default by @pascal-roth in #891
- Adds check that no articulation root API is applied on rigid bodies by @lgulich in #1358
- Adds RayCaster rough terrain base height to reward by @Andy-xiong6 in #1525
- Adds position threshold check for state transitions by @DorsaRoh in #1544
- Adds clip range for JointAction by @fan-ziqi in #1476
🐛 Bug Fixes
- Fixes noise_model initialized in direct_marl_env by @NoneJou072 in #1480
- Fixes entry_point and kwargs in isaaclab_tasks README by @fan-ziqi in #1485
- Fixes syntax for checking if pre-commit is installed in isaaclab.sh by @louislelay in #1422
- Corrects fisheye camera projection types in spawner configuration by @command-z-z in #1361
- Fixes actuator velocity limits propagation down the articulation root_physx_view by @jtigue-bdai in #1509
- Computes Jacobian in the root frame inside the
DifferentialInverseKinematicsActionclass by @zoctipus in #967 - Adds transform for mesh_prim of ray caster sensor by @clearsky-mio in #1448
- Fixes configclass dict conversion for torch tensors by @lgulich in #1530
- Fixes error in apply_actions method in
NonHolonomicActionaction term. by @KyleM73 in #1513 - Fixes outdated sensor data after reset by @kellyguo11 in #1276
- Fixes order of logging metrics and sampling commands in command manager by @Mayankm96 in #1352
💔 Breaking Changes
- Refactors pose and velocities to link frame and COM frame APIs by @jtigue-bdai in #966
🤗 New Contributors
- @nvcyc made their first contribution in #1336
- @peterd-NV made their first contribution in #1494
- @NoneJou072 made their first contribution in #1480
- @clearsky-mio made their first contribution in #1448
- @Andy-xiong6 made their first contribution in #1525
- @noseworm made their first contribution in #1520
