Skip to content

Conversation

@njawale42
Copy link
Contributor

@njawale42 njawale42 commented Aug 28, 2025

Description

This PR introduces the SkillGen framework to Isaac Lab, integrating GPU motion planning with skill-segmented data generation. It enables efficient, high-quality dataset creation with robust collision handling, visualization, and reproducibility.

Note:

  • Please look at the cuRobo usage license here
  • Please look at updated isaacsim license here

Technical Implementation:

Annotation Framework:

  • Manual subtask start annotations to cleanly separate skill execution from motion-planning segments
  • Consistent trajectory segmentation for downstream dataset consumers

Motion Planning:

  • Base Motion Planner (Extensible):

    • Introduces a reusable planner interface for uniform integration:
      • source/isaaclab_mimic/isaaclab_mimic/motion_planners/base_motion_planner.py
    • Defines a minimal, consistent API for planners:
      • update_world_and_plan_motion(...), get_planned_poses(...), etc.
    • The cuRobo planner inherits from this base class.
    • New planners can be added by subclassing the base class and implementing the same API, enabling drop-in replacement without changes to the SkillGen pipeline.
  • CuRobo Planner (GPU-accelerated, collision-aware):

    • Multi-phase planning: approach → contact → retreat
    • Dynamic object attach/detach and contact-aware sphere management
    • Real-time world synchronization between Isaac Lab and cuRobo
    • Configurable collision filtering for contact phases
    • Tests:
      • source/isaaclab_mimic/isaaclab_mimic/motion_planners/curobo/test/test_curobo_planner_cube_stack.py
      • source/isaaclab_mimic/isaaclab_mimic/motion_planners/curobo/test/test_curobo_planner_franka.py
      • source/isaaclab_mimic/test/test_generate_dataset_skillgen.py

Data Generation Pipeline:

  • Automated dataset generation with precise skill-based segmentation
  • Integrates with existing observation/action spaces
  • Supports multi-env parallel collection with cuRobo-backed planning

Visualization and Debugging:

  • Rerun-based 3D visualization for trajectory/collision inspection
  • Real-time sphere visualization for collision boundaries and contact phases

Dependencies:

  • cuRobo: motion planning and collision checking
  • Rerun: 3D visualization and debugging

Integration:

This extends the existing mimic pipeline and remains backward compatible. It integrates into the manager-based environment structure and existing observation/action interfaces without breaking current users.

Type of change

  • New feature (non-breaking change which adds functionality)
  • This change requires a documentation update

Screenshot

SkillGen Data Generation

Cube Stacking SkillGen Data Generation Bin Cube Stacking SkillGen Data Generation (Using Vanilla Cube Stacking Source Demos)
Cube Stacking Data Generation Bin Cube Stacking Data Generation

Bin Cube Stacking Behavior Cloned Policy

bin_cube_stack_bc_policy

Rerun Integration

rerun_skillgen

Motion Planner Tests

Obstacle Avoidance (cuRobo) Cube Stack End-to-End (cuRobo)
Obstacle Avoidance cuRobo Cube Stack End-to-End cuRobo

Checklist

  • I have run the pre-commit checks with ./isaaclab.sh --format
  • I have made corresponding changes to the documentation
  • My changes generate no new warnings
  • I have added tests that prove my fix is effective or that my feature works
  • I have updated the changelog and the corresponding version in the extension's config/extension.toml file
  • I have added my name to the CONTRIBUTORS.md or my name already exists there

@kellyguo11 kellyguo11 requested a review from peterd-NV August 28, 2025 19:46
@njawale42 njawale42 requested review from peterd-NV and removed request for peterd-NV August 28, 2025 19:59
README.md Outdated
The Isaac Lab framework is released under [BSD-3 License](LICENSE). The `isaaclab_mimic` extension and its corresponding standalone scripts are released under [Apache 2.0](LICENSE-mimic). The license files of its dependencies and assets are present in the [`docs/licenses`](docs/licenses) directory.
Note that Isaac Lab requires Isaac Sim, which includes components under proprietary licensing terms. Please see the [Isaac Sim license](https://github.com/isaac-sim/IsaacSim/blob/main/LICENSE) for information on Isaac Sim licensing.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This should just point to the docs/licenses/dependencies/isaacsim-license.txt license file, which should be updated with the contents of https://github.com/isaac-sim/IsaacSim/blob/main/LICENSE

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Corrected! Thanks Gav!

@njawale42 njawale42 requested a review from nv-caelan August 28, 2025 22:36
Copy link
Contributor

@peterd-NV peterd-NV left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Tested/verified skillgen/prior mimic workflows working as expected. My prior review was completed in IsaacLab-Internal repo and all comments have been addressed in this public PR.

@njawale42
Copy link
Contributor Author

@nv-caelan FYI I included most of your suggested changes in my commits (did not apply directly through github).

@kellyguo11 kellyguo11 changed the title SkillGen in Isaac Lab for 2.3 Release Adds SkillGen framework to Isaac Lab with cuRobo support Sep 3, 2025
Copy link
Contributor

@kellyguo11 kellyguo11 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is there any documentation / tutorial available for this? including installation steps and how to set it up to use skillgen, what it does, how it works, the visualizer...

from dataclasses import dataclass
from typing import Any

from curobo.cuda_robot_model.cuda_robot_model import CudaRobotModelState
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

will curobo be a hard dependency for all mimic workflows? will this cause any issues if curobo is not installed?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

With use_skillgen=False, normal Mimic runs unchanged: generate_dataset.py doesn’t import or construct the cuRobo planner, so no cuRobo code is touched. Will make sure to test this with and without cuRobo once.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

sounds good, please verify if things still run without curobo dependency installed

import weakref
from typing import TYPE_CHECKING, Any, Optional

import rerun as rr
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

does this need to be added as a dependency?

Copy link
Contributor Author

@njawale42 njawale42 Sep 4, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, however this file is only initialized if visualize_plan is set to True in curobo config for the particular task. So this will only be used then and people can run this without rerun if they set the flag to false.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

are we going to include it in setup.py? or ask users to install it independently?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

up to us, i think that since we ask users to install curobo independently from source, we can also add pip install for rerun conditional on this flag in the documentation. what do you think?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

if it's not needed for other workflows, we can ask users to install it. let's also add a check in the code if it wasn't install and hint users to install the dependencies needed

Copy link
Contributor Author

@njawale42 njawale42 Sep 7, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, will add a try-except while importing rerun in plan_visualizer.py and raise an ImportError if it isn't installed.

id="Isaac-Stack-Cube-Franka-IK-Rel-Skillgen-v0",
entry_point="isaaclab_mimic.envs:FrankaCubeStackIKRelMimicEnv",
kwargs={
"env_cfg_entry_point": franka_stack_ik_rel_skillgen_env_cfg.FrankaCubeStackIKRelSkillgenEnvCfg,
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not for this PR maybe, but we should be moving toward using string typed entry_point registration rather than import.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is there anything preventing us from using the same mechanism as the RL entry points in this PR?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I can take this up in a separate PR as well (can be tried for all mimic workflows)

Copy link
Collaborator

@ooctipus ooctipus left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am not super familiar with mimic flow and the my first pass looks good, it will be nice if have mimic folks provide more detail view.

My have only 2 comments:

  1. it will be great if we don't touch os env_variable.
  2. to me mimic_env_cfg and manager_based_rl_mimic_env seems to diverge further and further, and maybe more appropriate to go isaaclab_mimic.envs since there is also envs folder there. You will have more separation of concern and flexibility to tailor for mimic related env workflow and entrypoint in the end.

Copy link

@nv-caelan nv-caelan left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM, thanks for addressing my comments!

@@ -1,13 +1,188 @@
Copyright (c) 2022, NVIDIA CORPORATION. All rights reserved.
The Isaac Sim software in this repository is covered under the Apache 2.0
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can we please move this license change into a separate MR as it has nothing to do with CuRobo.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I added these as per @gavrielstate 's instructions.
@kellyguo11 for viz

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I agree would be good to have a separate PR. let me just create a new PR for the licensing updates.

eef_pose=None,
object_poses=None,
subtask_term_signals=None,
subtask_start_signals=None,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe this is coming from legacy code but we want type-hinting to live on function level and not docstrings. Please check here for style-guide: https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html#type-hinting

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We can change these (since I see such type hinting in quite a lot of scripts) in a separate MR?

@kellyguo11 kellyguo11 merged commit 994979c into isaac-sim:main Sep 9, 2025
6 checks passed
george-nehma pushed a commit to george-nehma/IsaacLab-Dreamerv3 that referenced this pull request Oct 24, 2025
)

## Description

This PR introduces the SkillGen framework to Isaac Lab, integrating GPU
motion planning with skill-segmented data generation. It enables
efficient, high-quality dataset creation with robust collision handling,
visualization, and reproducibility.

**Note:** 
- Please look at the cuRobo usage license
![here](docs/licenses/dependencies/cuRobo-license.txt)
- Please look at updated isaacsim license
![here](docs/licenses/dependencies/isaacsim-license.txt)

### Technical Implementation:

**Annotation Framework:**
- Manual subtask start annotations to cleanly separate skill execution
from motion-planning segments
- Consistent trajectory segmentation for downstream dataset consumers

**Motion Planning:**
- **Base Motion Planner (Extensible):**
   - Introduces a reusable planner interface for uniform integration:
-
`source/isaaclab_mimic/isaaclab_mimic/motion_planners/base_motion_planner.py`
   - Defines a minimal, consistent API for planners:
- `update_world_and_plan_motion(...)`, `get_planned_poses(...)`, etc.
   - The cuRobo planner inherits from this base class.
- New planners can be added by subclassing the base class and
implementing the same API, enabling drop-in replacement without changes
to the SkillGen pipeline.
 
- **CuRobo Planner** (GPU-accelerated, collision-aware):
  - Multi-phase planning: approach → contact → retreat
  - Dynamic object attach/detach and contact-aware sphere management
  - Real-time world synchronization between Isaac Lab and cuRobo
  - Configurable collision filtering for contact phases
  - **Tests**:
-
`source/isaaclab_mimic/isaaclab_mimic/motion_planners/curobo/test/test_curobo_planner_cube_stack.py`
-
`source/isaaclab_mimic/isaaclab_mimic/motion_planners/curobo/test/test_curobo_planner_franka.py`
    - `source/isaaclab_mimic/test/test_generate_dataset_skillgen.py`

**Data Generation Pipeline:**
- Automated dataset generation with precise skill-based segmentation
- Integrates with existing observation/action spaces
- Supports multi-env parallel collection with cuRobo-backed planning

**Visualization and Debugging:**
- Rerun-based 3D visualization for trajectory/collision inspection
- Real-time sphere visualization for collision boundaries and contact
phases

### Dependencies:
- **cuRobo**: motion planning and collision checking
- **Rerun**: 3D visualization and debugging

### Integration:
This extends the existing mimic pipeline and remains backward
compatible. It integrates into the manager-based environment structure
and existing observation/action interfaces without breaking current
users.

## Type of change
- [x] New feature (non-breaking change which adds functionality)
- [x] This change requires a documentation update

## Screenshot

### SkillGen Data Generation

<table>
  <tr>
<td align="center"><strong>Cube Stacking SkillGen Data
Generation</strong></td>
<td align="center"><strong>Bin Cube Stacking SkillGen Data Generation
(Using Vanilla Cube Stacking Source Demos)</strong></td>
  </tr>
  <tr>
    <td>
<img
src="https://github.com/user-attachments/assets/de240b89-e670-4035-84ae-4101a4f70dae"
           alt="Cube Stacking Data Generation"
           style="width: 480px; height: 270px; object-fit: contain;">
    </td>
    <td>
<img
src="https://github.com/user-attachments/assets/dd94e0a6-ad1b-4366-80c4-7ff96cabeb3e"
           alt="Bin Cube Stacking Data Generation"
           style="width: 480px; height: 270px; object-fit: contain;">
    </td>
  </tr>
</table>

### Bin Cube Stacking Behavior Cloned Policy

![bin_cube_stack_bc_policy](https://github.com/user-attachments/assets/d577d726-d623-4b27-90e5-a047cd67e4f9)

### Rerun Integration

![rerun_skillgen](https://github.com/user-attachments/assets/9c469bc4-d3f6-465a-8ca6-0ddfd85c6ad0)

### Motion Planner Tests

<table>
  <tr>
    <td align="center"><strong>Obstacle Avoidance (cuRobo)</strong></td>
<td align="center"><strong>Cube Stack End-to-End (cuRobo)</strong></td>
  </tr>
  <tr>
    <td>
<img
src="https://github.com/user-attachments/assets/a022342f-4c4e-42ea-a48c-cb1ea65c94db"
           alt="Obstacle Avoidance cuRobo"
           style="width: 480px; height: 270px; object-fit: contain;">
    </td>
    <td>
<img
src="https://github.com/user-attachments/assets/7e6290b6-8322-4702-ae2f-f363a87badde"
           alt="Cube Stack End-to-End cuRobo"
           style="width: 480px; height: 270px; object-fit: contain;">
    </td>
  </tr>
</table>

## Checklist

- [x] I have run the [`pre-commit` checks](https://pre-commit.com/) with
`./isaaclab.sh --format`
- [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [x] I have added tests that prove my fix is effective or that my
feature works
- [x] I have updated the changelog and the corresponding version in the
extension's `config/extension.toml` file
- [x] I have added my name to the `CONTRIBUTORS.md` or my name already
exists there

---------

Signed-off-by: Kelly Guo <[email protected]>
Co-authored-by: Kelly Guo <[email protected]>
Co-authored-by: Pascal Roth <[email protected]>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

8 participants