Skip to content

Commit 0a0689f

Browse files
committed
Documentation updates, minor code updates
1 parent 5d66dca commit 0a0689f

File tree

3 files changed

+55
-70
lines changed

3 files changed

+55
-70
lines changed

docs/source/overview/imitation-learning/skillgen.rst

Lines changed: 45 additions & 56 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
.. _skillgen:
22

3-
SkillGen
4-
========
3+
SkillGen for Automated Demonstration Generation
4+
===============================================
55

6-
SkillGen is an advanced demonstration generation system that enhances Isaac Lab Mimic by integrating cuRobo motion planning. It generates high-quality, adaptive, collision-free robot demonstrations by combining human-provided subtask segments with automated motion planning.
6+
SkillGen is an advanced demonstration generation system that enhances Isaac Lab Mimic by integrating motion planning. It generates high-quality, adaptive, collision-free robot demonstrations by combining human-provided subtask segments with automated motion planning.
77

88
What is SkillGen?
99
~~~~~~~~~~~~~~~~~
@@ -134,35 +134,37 @@ Download and Setup
134134

135135
A major advantage of SkillGen is that the same annotated dataset can be reused across multiple related tasks (e.g., basic stacking and adaptive bin stacking). This avoids collecting and annotating new data per variant.
136136

137-
.. note::
137+
.. admonition:: {Optional for the tasks in this tutorial} Collect a fresh dataset (source + annotated)
138138

139-
**SkillGen-specific data collection and annotation**
139+
If you want to collect a fresh source dataset and then create an annotated dataset for SkillGen, follow these commands. The user is expected to have knowledge of the Isaac Lab Mimic workflow.
140140

141-
* Using the provided annotated dataset is the fastest path to get started with SkillGen
142-
* If you create your own dataset, SkillGen requires manual annotation of both subtask start and termination boundaries (no auto-annotation)
143-
* Start boundary signals are mandatory for SkillGen; use ``--annotate_subtask_start_signals`` during annotation or data generation will fail
144-
* Keep your subtask definitions (``object_ref``, ``subtask_term_signal``) consistent with the SkillGen environment config
141+
**Important pointers before you begin**
145142

146-
Record demonstrations (any teleop device is supported; replace ``spacemouse`` if needed):
143+
* Using the provided annotated dataset is the fastest path to get started with SkillGen tasks in this tutorial.
144+
* If you create your own dataset, SkillGen requires manual annotation of both subtask start and termination boundaries (no auto-annotation).
145+
* Start boundary signals are mandatory for SkillGen; use ``--annotate_subtask_start_signals`` during annotation or data generation will fail.
146+
* Keep your subtask definitions (``object_ref``, ``subtask_term_signal``) consistent with the SkillGen environment config.
147147

148-
.. code:: bash
148+
**Record demonstrations** (any teleop device is supported; replace ``spacemouse`` if needed):
149149

150-
./isaaclab.sh -p scripts/tools/record_demos.py \
151-
--task Isaac-Stack-Cube-Franka-IK-Rel-Skillgen-v0 \
152-
--teleop_device spacemouse \
153-
--dataset_file ./datasets/dataset_skillgen.hdf5 \
154-
--num_demos 10
150+
.. code:: bash
155151
156-
Annotate demonstrations for SkillGen (writes both term and start boundaries):
152+
./isaaclab.sh -p scripts/tools/record_demos.py \
153+
--task Isaac-Stack-Cube-Franka-IK-Rel-Skillgen-v0 \
154+
--teleop_device spacemouse \
155+
--dataset_file ./datasets/dataset_skillgen.hdf5 \
156+
--num_demos 10
157157
158-
.. code:: bash
158+
**Annotate demonstrations for SkillGen** (writes both term and start boundaries):
159159

160-
./isaaclab.sh -p scripts/imitation_learning/isaaclab_mimic/annotate_demos.py \
161-
--device cpu \
162-
--task Isaac-Stack-Cube-Franka-IK-Rel-Skillgen-v0 \
163-
--input_file ./datasets/dataset_skillgen.hdf5 \
164-
--output_file ./datasets/annotated_dataset_skillgen.hdf5 \
165-
--annotate_subtask_start_signals
160+
.. code:: bash
161+
162+
./isaaclab.sh -p scripts/imitation_learning/isaaclab_mimic/annotate_demos.py \
163+
--device cpu \
164+
--task Isaac-Stack-Cube-Franka-IK-Rel-Skillgen-v0 \
165+
--input_file ./datasets/dataset_skillgen.hdf5 \
166+
--output_file ./datasets/annotated_dataset_skillgen.hdf5 \
167+
--annotate_subtask_start_signals
166168
167169
Understanding Dataset Annotation
168170
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
@@ -178,28 +180,18 @@ Subtasks in SkillGen
178180
* ``subtask_term_signal``: the binary termination signal name (transitions 0 to 1 when the subtask completes)
179181
* ``subtask_start_signal``: the binary start signal name (transitions 0 to 1 when the subtask begins; required for SkillGen)
180182

181-
The localization process performs:
183+
The subtask localization process performs:
182184

183185
* detection of signal transition points (0 to 1) to identify subtask boundaries ``[t_start, t_end]``;
184186
* extraction of the subtask segment between boundaries;
185187
* computation of end-effector trajectories and key poses in an object- or task-relative frame (using ``object_ref`` if provided);
186-
* optional time-normalization of progress and extraction of gripper/contact mode signals.
187188

188189
This converts absolute, scene-specific motions into object-relative skill segments that can be adapted to new object placements and scene configurations during data generation.
189190

190191
Manual Annotation Workflow
191192
^^^^^^^^^^^^^^^^^^^^^^^^^^
192193
Contrary to the Isaac Lab Mimic workflow, SkillGen requires manual annotation of subtask start and termination boundaries. For example, for grasping a cube, the start signal is right before the gripper closes and the termination signal is right after the object is grasped. You can adjust the start and termination signals to fit your subtask definition.
193194

194-
.. code:: bash
195-
196-
./isaaclab.sh -p scripts/imitation_learning/isaaclab_mimic/annotate_demos.py \
197-
--device cpu \
198-
--task Isaac-Stack-Cube-Franka-IK-Rel-Mimic-v0 \
199-
--input_file ./datasets/raw_dataset.hdf5 \
200-
--output_file ./datasets/annotated_dataset_skillgen.hdf5 \
201-
--annotate_subtask_start_signals
202-
203195
.. tip::
204196

205197
**Manual Annotation Controls:**
@@ -214,7 +206,7 @@ Contrary to the Isaac Lab Mimic workflow, SkillGen requires manual annotation of
214206
Data Generation with SkillGen
215207
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
216208

217-
SkillGen transforms annotated demonstrations into diverse, high-quality datasets using advanced motion planning.
209+
SkillGen transforms annotated demonstrations into diverse, high-quality datasets using motion planning.
218210

219211
How SkillGen Works
220212
^^^^^^^^^^^^^^^^^^
@@ -238,8 +230,6 @@ Key parameters for SkillGen data generation:
238230
* ``--device``: Computation device (cpu/cuda). Use cpu for stable physics
239231
* ``--headless``: Disable visualization for faster generation
240232

241-
Note: cuRobo planner interface and configurations are described in :ref:`cuRobo-interface-features`.
242-
243233
Task 1: Basic Cube Stacking
244234
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
245235

@@ -286,10 +276,10 @@ Once satisfied with small-scale results, generate a full training dataset:
286276
287277
.. note::
288278

289-
* Use ``--device cuda`` for faster generation if you have a compatible GPU
290-
* Use ``--headless`` to disable visualization for faster generation.
291-
* Adjust ``--num_envs`` based on your GPU memory (start with 5, increase gradually). The performance gain is not very significant when num_envs is greater than 1.
292-
* Generation time: ~30-60 minutes for 1000 demonstrations on modern GPUs
279+
* Use ``--headless`` to disable visualization for faster generation. Rerun visualization can be enabled by setting ``visualize_plan = True`` in the cuRobo planner configuration with ``--headless`` enabled as well for debugging.
280+
* Adjust ``--num_envs`` based on your GPU memory (start with 1, increase gradually). The performance gain is not very significant when num_envs is greater than 1. A value of 5 seems to be a sweet spot for most GPUs to balance performance and memory usage between cuRobo instances and simulation environments.
281+
* Generation time: ~90 to 120 minutes for one environment for 1000 demonstrations on modern GPUs. Time depends on the GPU, the number of environments, and the success rate of the demonstrations (which depends on quality of the annotated dataset).
282+
* cuRobo planner interface and configurations are described in :ref:`cuRobo-interface-features`.
293283

294284
Task 2: Adaptive Cube Stacking in a Bin
295285
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
@@ -330,7 +320,7 @@ Generate the complete adaptive stacking dataset:
330320
331321
.. warning::
332322

333-
Adaptive tasks typically have lower success rates due to increased complexity. The time taken to generate the dataset is also longer due to lower success rates than vanilla cube stacking and difficult planning problems.
323+
Adaptive tasks typically have lower success rates and higher data generation time due to increased complexity. The time taken to generate the dataset is also longer due to lower success rates than vanilla cube stacking and difficult planning problems.
334324

335325

336326
Learning Policies from SkillGen Data
@@ -428,9 +418,9 @@ cuRobo Planner (GPU, collision-aware)
428418

429419
* Tests:
430420

431-
* ``motion_planners/curobo/test/test_curobo_planner_cube_stack.py``
432-
* ``motion_planners/curobo/test/test_curobo_planner_franka.py``
433-
* ``isaaclab_mimic/test/test_generate_dataset_skillgen.py``
421+
* ``source/isaaclab_mimic/test/test_curobo_planner_cube_stack.py``
422+
* ``source/isaaclab_mimic/test/test_curobo_planner_franka.py``
423+
* ``source/isaaclab_mimic/test/test_generate_dataset_skillgen.py``
434424

435425
These tests can also serve as a reference for how to use cuRobo as a standalone motion planner.
436426

@@ -443,24 +433,23 @@ Generation Pipeline Integration
443433

444434
When ``--use_skillgen`` is enabled in ``generate_dataset.py``, the following pipeline is executed:
445435

446-
1. Randomize subtask boundaries
447-
Randomize per-demo start and termination indices for each subtask using task-configured offset ranges.
436+
1. **Randomize subtask boundaries**: Randomize per-demo start and termination indices for each subtask using task-configured offset ranges.
448437

449-
2. Build per-subtask trajectories
438+
2. **Build per-subtask trajectories**:
450439
For each end-effector and subtask:
440+
451441
- Select a source demonstration segment (strategy-driven; respects coordination/sequential constraints)
452442
- Transform the segment to the current scene (object-relative or coordination delta; optional first-pose interpolation)
453443
- Wrap the transformed segment into a waypoint trajectory
454444

455-
3. Transition between subtasks
456-
- If ``use_skillgen``: before executing the next subtask, plan a collision-aware transition with cuRobo to the subtask’s first waypoint (world sync, optional attach/detach), execute the planned waypoints, then resume the subtask trajectory
457-
- Otherwise: interpolate and merge directly into the subtask trajectory
445+
3. **Transition between subtasks**:
446+
- Plan a collision-aware transition with cuRobo to the subtask's first waypoint (world sync, optional attach/detach), execute the planned waypoints, then resume the subtask trajectory
458447

459-
4. Execute with constraints
460-
Execute waypoints step-by-step across end-effectors while enforcing subtask constraints (sequential, coordination with synchronous steps); optionally update planner visualization if enabled
448+
4. **Execute with constraints**:
449+
- Execute waypoints step-by-step across end-effectors while enforcing subtask constraints (sequential, coordination with synchronous steps); optionally update planner visualization if enabled
461450

462-
5. Record and export
463-
Accumulate states/observations/actions, set the episode success flag, and export the episode (the outer pipeline filters/consumes successes)
451+
5. **Record and export**:
452+
- Accumulate states/observations/actions, set the episode success flag, and export the episode (the outer pipeline filters/consumes successes)
464453

465454
.. note::
466455

source/isaaclab_mimic/isaaclab_mimic/motion_planners/curobo/curobo_planner.py

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,8 @@
2525
from isaaclab.assets import Articulation
2626
from isaaclab.envs.manager_based_env import ManagerBasedEnv
2727
from isaaclab.managers import SceneEntityCfg
28+
from isaaclab.sim.spawners.materials import PreviewSurfaceCfg
29+
from isaaclab.sim.spawners.meshes import MeshSphereCfg, spawn_mesh_sphere
2830

2931
from isaaclab_mimic.motion_planners.curobo.curobo_planner_cfg import CuroboPlannerCfg
3032
from isaaclab_mimic.motion_planners.motion_planner_base import MotionPlannerBase
@@ -860,11 +862,8 @@ def _detach_objects(self, link_names: set[str] | None = None) -> bool:
860862
# Find object path and re-enable it in the world
861863
object_path = object_mappings.get(object_name)
862864
if object_path:
863-
try:
864-
self.motion_gen.world_coll_checker.enable_obstacle(object_path, enable=True)
865-
self.logger.debug(f"Re-enabled obstacle {object_path}")
866-
except Exception as e:
867-
self.logger.debug(f"ERROR re-enabling obstacle {object_path}: {e}")
865+
self.motion_gen.world_coll_checker.enable_obstacle(object_path, enable=True) # type: ignore
866+
self.logger.debug(f"Re-enabled obstacle {object_path}")
868867

869868
# Collect the link that will need re-enabling
870869
detached_links.add(attachment.parent)
@@ -1585,8 +1584,6 @@ def _update_sphere_visualization(self, force_update: bool = True) -> None:
15851584
Args:
15861585
force_update: True to recreate all spheres, False to update existing positions only
15871586
"""
1588-
from isaaclab.sim.spawners.meshes import spawn_mesh_sphere
1589-
15901587
# Get current sphere data
15911588
cu_js = self._get_current_joint_state_for_curobo()
15921589
sphere_position = self._to_curobo_device(
@@ -1686,8 +1683,6 @@ def _create_sphere_config(self, sphere_idx: int, sphere, robot_link_count: int)
16861683
Returns:
16871684
Dictionary containing 'position' (world coordinates) and 'cfg' (MeshSphereCfg)
16881685
"""
1689-
from isaaclab.sim.spawners.materials import PreviewSurfaceCfg
1690-
from isaaclab.sim.spawners.meshes import MeshSphereCfg
16911686

16921687
is_attached = sphere_idx >= robot_link_count
16931688
color = (1.0, 0.5, 0.0) if is_attached else (0.0, 1.0, 0.0)

source/isaaclab_mimic/isaaclab_mimic/motion_planners/curobo/plan_visualizer.py

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,12 @@
2020
import weakref
2121
from typing import TYPE_CHECKING, Any, Optional
2222

23-
import rerun as rr
23+
# Check if rerun is installed
24+
try:
25+
import rerun as rr
26+
except ImportError:
27+
raise ImportError("Rerun is not installed!")
28+
2429
from curobo.types.state import JointState
2530

2631
import isaaclab.utils.math as PoseUtils
@@ -170,10 +175,6 @@ def signal_handler(signum, frame):
170175
signal.signal(signal.SIGINT, self._original_sigint_handler)
171176
elif signum == signal.SIGTERM:
172177
signal.signal(signal.SIGTERM, self._original_sigterm_handler)
173-
174-
# Re-raise the signal so Isaac Lab can handle it normally
175-
import os
176-
177178
os.kill(os.getpid(), signum)
178179

179180
signal.signal(signal.SIGINT, signal_handler)

0 commit comments

Comments
 (0)