Skip to content

Conversation

njawale42
Copy link

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
@@ -188,6 +188,10 @@ where creativity and technology intersect. Your contributions can make a meaning
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
Author

Choose a reason for hiding this comment

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

Corrected! Thanks Gav!

class PreStepSubtaskStartsObservationsRecorder(RecorderTerm):
"""Recorder term that records the subtask start observations in each step."""

def record_pre_step(self):

Choose a reason for hiding this comment

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

Missing return type

Copy link
Author

Choose a reason for hiding this comment

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

Done

# Cleanup of motion planners and their visualizers
if motion_planners is not None:
for env_id, planner in motion_planners.items():
if hasattr(planner, "plan_visualizer") and planner.plan_visualizer is not None:

Choose a reason for hiding this comment

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

Could instead do:

Suggested change
if hasattr(planner, "plan_visualizer") and planner.plan_visualizer is not None:
if getattr(planner, "plan_visualizer", None) is not None:

Copy link
Author

Choose a reason for hiding this comment

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

Added

@@ -30,6 +31,7 @@ def __init__(
eef_pose=None,
object_poses=None,
subtask_term_signals=None,
subtask_start_signals=None,

Choose a reason for hiding this comment

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

Add types?

Copy link
Author

Choose a reason for hiding this comment

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

Type hints for other args were declared in the function docstring as opposed to signature. Just following the same style.

eef_subtask_boundaries[i - 1][1] + prev_max_offset_range
< eef_subtask_boundaries[i][1] + self.subtask_term_offset_ranges[eef_name][i][0]
), (
"subtask sanity check violation in demo with subtask {} end ind {}, subtask {} max offset {},"

Choose a reason for hiding this comment

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

Use f-strings

Copy link
Author

Choose a reason for hiding this comment

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

Done


self._monitor_active = True

def monitor_parent_process():

Choose a reason for hiding this comment

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

Suggested change
def monitor_parent_process():
def monitor_parent_process() -> None

Copy link
Author

Choose a reason for hiding this comment

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

Added in the recent commit

self._monitor_thread = threading.Thread(target=monitor_parent_process, daemon=True)
self._monitor_thread.start()

def _kill_rerun_processes(self):

Choose a reason for hiding this comment

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

Suggested change
def _kill_rerun_processes(self):
def _kill_rerun_processes(self) -> None

Copy link
Author

Choose a reason for hiding this comment

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

Added in the recent commit

def cube_stack_test_env():
"""Create the environment and motion planner once for the test suite and yield them."""
random.seed(SEED)
torch.manual_seed(SEED)

Choose a reason for hiding this comment

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

Check that you don't need to also set the numpy seed

Copy link
Author

Choose a reason for hiding this comment

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

Don't think so, will get back to this later

marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1)
goal_pose_visualizer = VisualizationMarkers(marker_cfg)

yield {

Choose a reason for hiding this comment

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

Add a Generator return type?

Copy link
Author

Choose a reason for hiding this comment

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

Done

"""Test suite for the Curobo motion planner, focusing on obstacle avoidance."""

@pytest.fixture(autouse=True)
def setup(self, curobo_test_env):

Choose a reason for hiding this comment

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

Return types here and elsewhere in TestCuroboPlanner

Copy link
Author

Choose a reason for hiding this comment

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

Added in the recent commit

@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.

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.

4 participants