Skip to content

Commit 3dbc13e

Browse files
[SkillGen] Migrates SkillGen to Lab 3.0 (#4724)
# Description <!-- Thank you for your interest in sending a pull request. Please make sure to check the contribution guidelines. Link: https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html 💡 Please try to keep PRs small and focused. Large PRs are harder to review and merge. --> Fix cuRobo quaternion handling to use correct convention and update Warp API calls for compatibility. Fix Rerun visualization code in cuRobo planner. Add `--visualizer kit` argument to SkillGen documentation for all non-headless commands. ## Type of change <!-- As you go through the list, delete the ones that are not applicable. --> - Bug fix (non-breaking change which fixes an issue) - Documentation update ## Checklist - [x] I have read and understood the [contribution guidelines](https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html) - [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 - [ ] 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 --------- Co-authored-by: Kelly Guo <kellyg@nvidia.com>
1 parent 2e68d2f commit 3dbc13e

File tree

7 files changed

+79
-47
lines changed

7 files changed

+79
-47
lines changed

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

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -135,7 +135,7 @@ The dataset contains:
135135
Download and Setup
136136
^^^^^^^^^^^^^^^^^^
137137

138-
1. Download the pre-annotated dataset by clicking `here <https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/5.0/Isaac/IsaacLab/Mimic/franka_stack_datasets/annotated_dataset_skillgen.hdf5>`__.
138+
1. Download the pre-annotated dataset by clicking `here <https://omniverse-content-staging.s3-us-west-2.amazonaws.com/Assets/Isaac/6.0/Isaac/IsaacLab/Mimic/franka_stack_datasets/annotated_dataset_skillgen.hdf5>`__.
139139

140140
2. Prepare the datasets directory and move the downloaded file:
141141

@@ -173,7 +173,8 @@ Download and Setup
173173
--task Isaac-Stack-Cube-Franka-IK-Rel-Skillgen-v0 \
174174
--teleop_device spacemouse \
175175
--dataset_file ./datasets/dataset_skillgen.hdf5 \
176-
--num_demos 10
176+
--num_demos 10 \
177+
--visualizer kit
177178
178179
**Annotate demonstrations for SkillGen** (writes both term and start boundaries):
179180

@@ -184,7 +185,8 @@ Download and Setup
184185
--task Isaac-Stack-Cube-Franka-IK-Rel-Skillgen-v0 \
185186
--input_file ./datasets/dataset_skillgen.hdf5 \
186187
--output_file ./datasets/annotated_dataset_skillgen.hdf5 \
187-
--annotate_subtask_start_signals
188+
--annotate_subtask_start_signals \
189+
--visualizer kit
188190
189191
Understanding Dataset Annotation
190192
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
@@ -283,7 +285,7 @@ Start with a small dataset to verify everything works:
283285
--input_file ./datasets/annotated_dataset_skillgen.hdf5 \
284286
--output_file ./datasets/generated_dataset_small_skillgen_cube_stack.hdf5 \
285287
--task Isaac-Stack-Cube-Franka-IK-Rel-Skillgen-v0 \
286-
--use_skillgen
288+
--use_skillgen --visualizer kit
287289
288290
Full-Scale Generation
289291
^^^^^^^^^^^^^^^^^^^^^
@@ -337,7 +339,7 @@ Test the adaptive stacking setup:
337339
--input_file ./datasets/annotated_dataset_skillgen.hdf5 \
338340
--output_file ./datasets/generated_dataset_small_skillgen_bin_cube_stack.hdf5 \
339341
--task Isaac-Stack-Cube-Bin-Franka-IK-Rel-Mimic-v0 \
340-
--use_skillgen
342+
--use_skillgen --visualizer kit
341343
342344
Full-Scale Generation
343345
^^^^^^^^^^^^^^^^^^^^^
@@ -419,7 +421,8 @@ Test your trained policies:
419421
--device cpu \
420422
--task Isaac-Stack-Cube-Franka-IK-Rel-Skillgen-v0 \
421423
--num_rollouts 50 \
422-
--checkpoint /path/to/model_checkpoint.pth
424+
--checkpoint /path/to/model_checkpoint.pth \
425+
--visualizer kit
423426
424427
.. code:: bash
425428
@@ -428,7 +431,8 @@ Test your trained policies:
428431
--device cpu \
429432
--task Isaac-Stack-Cube-Bin-Franka-IK-Rel-Mimic-v0 \
430433
--num_rollouts 50 \
431-
--checkpoint /path/to/model_checkpoint.pth
434+
--checkpoint /path/to/model_checkpoint.pth \
435+
--visualizer kit
432436
433437
.. note::
434438

source/isaaclab_mimic/config/extension.toml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
[package]
22

33
# Semantic Versioning is used: https://semver.org/
4-
version = "1.2.0"
4+
version = "1.2.1"
55

66
# Description
77
category = "isaaclab"

source/isaaclab_mimic/docs/CHANGELOG.rst

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,17 @@
11
Changelog
22
---------
33

4+
1.2.1 (2026-02-25)
5+
~~~~~~~~~~~~~~~~~~~
6+
7+
Fixed
8+
^^^^^
9+
10+
* Fixed cuRobo planner quaternion handling and Warp API compatibility for Isaac Lab 3.0.
11+
* Fixed Rerun visualization in cuRobo plan visualizer.
12+
* Added ``--visualizer kit`` to SkillGen documentation for all non-headless commands.
13+
14+
415
1.2.0 (2026-02-23)
516
~~~~~~~~~~~~~~~~~~~
617

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

Lines changed: 39 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99

1010
import numpy as np
1111
import torch
12+
import warp as wp
1213

1314
from curobo.cuda_robot_model.cuda_robot_model import CudaRobotModelState
1415
from curobo.geom.sdf.world import CollisionCheckerType
@@ -193,7 +194,7 @@ def __init__(
193194

194195
# Use env-local base translation for multi-env rendering consistency
195196
env_origin = self.env.scene.env_origins[env_id, :3]
196-
base_translation = (self.robot.data.root_pos_w[env_id, :3] - env_origin).detach().cpu().numpy()
197+
base_translation = (wp.to_torch(self.robot.data.root_pos_w)[env_id, :3] - env_origin).detach().cpu().numpy()
197198
self.plan_visualizer = PlanVisualizer(
198199
robot_name=self.config.robot_name,
199200
recording_id=f"curobo_plan_{env_id}",
@@ -457,10 +458,12 @@ def get_attached_pose(self, link_name: str, joint_state: JointState | None = Non
457458
link_poses = {}
458459
if link_state.links_position is not None and link_state.links_quaternion is not None:
459460
for i, link in enumerate(link_state.link_names):
461+
# cuRobo kinematics returns quaternions in (w, x, y, z) format
460462
link_poses[link] = self._make_pose(
461463
position=link_state.links_position[..., i, :],
462464
quaternion=link_state.links_quaternion[..., i, :],
463465
name=link,
466+
quat_is_xyzw=False,
464467
)
465468

466469
# For attached object link, use ee_link from robot config as parent
@@ -625,22 +628,23 @@ def _sync_object_poses_with_isaaclab(self) -> None:
625628
# Get current pose from Lab (may be on CPU or CUDA depending on --device flag)
626629
obj = rigid_objects[object_name]
627630
env_origin = self.env.scene.env_origins[self.env_id]
628-
current_pos_raw = obj.data.root_pos_w[self.env_id] - env_origin
629-
current_quat_raw = obj.data.root_quat_w[self.env_id] # (w, x, y, z)
631+
current_pos_raw = wp.to_torch(obj.data.root_pos_w)[self.env_id] - env_origin
632+
current_quat_raw = wp.to_torch(obj.data.root_quat_w)[self.env_id] # (x, y, z, w)
630633

631634
# Convert to cuRobo device and extract float values for pose list
632635
current_pos = self._to_curobo_device(current_pos_raw)
633636
current_quat = self._to_curobo_device(current_quat_raw)
634637

635-
# Convert to cuRobo pose format [x, y, z, w, x, y, z]
638+
# Convert to cuRobo pose format [pos_x, pos_y, pos_z, qw, qx, qy, qz]
639+
# Isaac Lab quaternion format: (x, y, z, w) -> cuRobo format: (w, x, y, z)
636640
pose_list = [
637641
float(current_pos[0].item()),
638642
float(current_pos[1].item()),
639643
float(current_pos[2].item()),
640-
float(current_quat[0].item()),
641-
float(current_quat[1].item()),
642-
float(current_quat[2].item()),
643-
float(current_quat[3].item()),
644+
float(current_quat[3].item()), # w
645+
float(current_quat[0].item()), # x
646+
float(current_quat[1].item()), # y
647+
float(current_quat[2].item()), # z
644648
]
645649

646650
# Update object pose in cuRobo's world model
@@ -665,8 +669,8 @@ def _sync_object_poses_with_isaaclab(self) -> None:
665669
# Get current pose and update in collision checker
666670
obj = rigid_objects[object_name]
667671
env_origin = self.env.scene.env_origins[self.env_id]
668-
current_pos_raw = obj.data.root_pos_w[self.env_id] - env_origin
669-
current_quat_raw = obj.data.root_quat_w[self.env_id]
672+
current_pos_raw = wp.to_torch(obj.data.root_pos_w)[self.env_id] - env_origin
673+
current_quat_raw = wp.to_torch(obj.data.root_quat_w)[self.env_id]
670674

671675
current_pos = self._to_curobo_device(current_pos_raw)
672676
current_quat = self._to_curobo_device(current_quat_raw)
@@ -929,7 +933,7 @@ def _get_current_joint_state_for_curobo(self) -> JointState:
929933
and zero velocity/acceleration.
930934
"""
931935
# Fetch joint position (shape: [1, num_joints])
932-
joint_pos_raw: torch.Tensor = self.robot.data.joint_pos[self.env_id, :].unsqueeze(0)
936+
joint_pos_raw: torch.Tensor = wp.to_torch(self.robot.data.joint_pos)[self.env_id, :].unsqueeze(0)
933937
joint_vel_raw: torch.Tensor = torch.zeros_like(joint_pos_raw)
934938
joint_acc_raw: torch.Tensor = torch.zeros_like(joint_pos_raw)
935939

@@ -997,41 +1001,48 @@ def _make_pose(
9971001
*,
9981002
name: str | None = None,
9991003
normalize_rotation: bool = False,
1004+
quat_is_xyzw: bool = True,
10001005
) -> Pose:
10011006
"""Create a cuRobo Pose with sensible defaults and device/dtype alignment.
10021007
10031008
Auto-populates missing fields with identity values and ensures tensors are
1004-
on the cuRobo device with the correct dtype.
1009+
on the cuRobo device with the correct dtype. Handles quaternion format conversion
1010+
from Isaac Lab's (x, y, z, w) to cuRobo's (w, x, y, z) format when needed.
10051011
10061012
Args:
10071013
position: Optional position as Tensor/ndarray/list. Defaults to [0, 0, 0].
1008-
quaternion: Optional quaternion as Tensor/ndarray/list (w, x, y, z). Defaults to [1, 0, 0, 0].
1014+
quaternion: Optional quaternion as Tensor/ndarray/list. Defaults to identity quaternion.
10091015
name: Optional name of the link that this pose represents.
10101016
normalize_rotation: Whether to normalize the quaternion inside Pose.
1017+
quat_is_xyzw: If True, quaternion is in Isaac Lab format (x, y, z, w) and will be
1018+
converted to cuRobo format. If False, quaternion is already in cuRobo (w, x, y, z) format.
10111019
10121020
Returns:
10131021
Pose: A cuRobo Pose on the configured cuRobo device and dtype.
10141022
"""
1015-
# Defaults
10161023
if position is None:
10171024
position = torch.tensor([0.0, 0.0, 0.0], dtype=self.tensor_args.dtype, device=self.tensor_args.device)
10181025
if quaternion is None:
1019-
quaternion = torch.tensor(
1020-
[0.0, 0.0, 0.0, 1.0], dtype=self.tensor_args.dtype, device=self.tensor_args.device
1026+
quaternion_wxyz = torch.tensor(
1027+
[1.0, 0.0, 0.0, 0.0], dtype=self.tensor_args.dtype, device=self.tensor_args.device
10211028
)
1029+
else:
1030+
if not isinstance(quaternion, torch.Tensor):
1031+
quaternion = torch.tensor(quaternion, dtype=self.tensor_args.dtype, device=self.tensor_args.device)
1032+
else:
1033+
quaternion = self._to_curobo_device(quaternion)
1034+
1035+
if quat_is_xyzw:
1036+
quaternion_wxyz = torch.roll(quaternion, shifts=1, dims=-1)
1037+
else:
1038+
quaternion_wxyz = quaternion
10221039

1023-
# Convert to tensors if needed
10241040
if not isinstance(position, torch.Tensor):
10251041
position = torch.tensor(position, dtype=self.tensor_args.dtype, device=self.tensor_args.device)
10261042
else:
10271043
position = self._to_curobo_device(position)
10281044

1029-
if not isinstance(quaternion, torch.Tensor):
1030-
quaternion = torch.tensor(quaternion, dtype=self.tensor_args.dtype, device=self.tensor_args.device)
1031-
else:
1032-
quaternion = self._to_curobo_device(quaternion)
1033-
1034-
return Pose(position=position, quaternion=quaternion, name=name, normalize_rotation=normalize_rotation)
1045+
return Pose(position=position, quaternion=quaternion_wxyz, name=name, normalize_rotation=normalize_rotation)
10351046

10361047
def _set_active_links(self, links: list[str], active: bool) -> None:
10371048
"""Configure collision checking for specific robot links.
@@ -1563,7 +1574,7 @@ def _update_visualization_at_joint_positions(self, joint_positions: torch.Tensor
15631574
if self.frame_counter % self.sphere_update_freq != 0:
15641575
return
15651576

1566-
original_joints: torch.Tensor = self.robot.data.joint_pos[self.env_id].clone()
1577+
original_joints: torch.Tensor = wp.to_torch(self.robot.data.joint_pos)[self.env_id].clone()
15671578

15681579
try:
15691580
# Ensure joint positions are on environment device for robot commands
@@ -1690,7 +1701,7 @@ def _create_sphere_config(self, sphere_idx: int, sphere, robot_link_count: int)
16901701
opacity = 0.9 if is_attached else 0.5
16911702

16921703
# Calculate position in world frame (do not use env_origin)
1693-
root_translation = (self.robot.data.root_pos_w[self.env_id, :3]).detach().cpu().numpy()
1704+
root_translation = wp.to_torch(self.robot.data.root_pos_w)[self.env_id, :3].detach().cpu().numpy()
16941705
position = sphere.position.cpu().numpy() if hasattr(sphere.position, "cpu") else sphere.position
16951706
if not is_attached:
16961707
position = position + root_translation
@@ -1777,7 +1788,7 @@ def update_world_and_plan_motion(
17771788
gripper_closed = expected_attached_object is not None
17781789
self._set_gripper_state(gripper_closed)
17791790
current_attached = self.get_attached_objects()
1780-
gripper_pos = self.robot.data.joint_pos[env_id, -2:]
1791+
gripper_pos = wp.to_torch(self.robot.data.joint_pos)[env_id, -2:]
17811792

17821793
self.logger.debug(f"Current attached objects: {current_attached}")
17831794

@@ -1799,13 +1810,13 @@ def update_world_and_plan_motion(
17991810
if expected_attached_object in rigid_objects:
18001811
obj = rigid_objects[expected_attached_object]
18011812
origin = self.env.scene.env_origins[env_id]
1802-
obj_pos = obj.data.root_pos_w[env_id] - origin
1813+
obj_pos = wp.to_torch(obj.data.root_pos_w)[env_id] - origin
18031814
self.logger.debug(f"Isaac Lab object position: {obj_pos}")
18041815

18051816
# Debug end-effector position
18061817
ee_frame_cfg = SceneEntityCfg("ee_frame")
18071818
ee_frame = self.env.scene[ee_frame_cfg.name]
1808-
ee_pos = ee_frame.data.target_pos_w[env_id, 0, :] - origin
1819+
ee_pos = wp.to_torch(ee_frame.data.target_pos_w)[env_id, 0, :] - origin
18091820
self.logger.debug(f"End-effector position: {ee_pos}")
18101821

18111822
# Debug distance

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

Lines changed: 13 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@
2727
except ImportError:
2828
raise ImportError("Rerun is not installed!")
2929

30+
_RR_HAS_TRANSFORM_AXES = hasattr(rr, "TransformAxes3D")
31+
3032
from curobo.types.state import JointState
3133

3234
import isaaclab.utils.math as PoseUtils
@@ -628,15 +630,17 @@ def _to_rerun_mesh(mesh: "trimesh.Trimesh") -> "rr.Mesh3D":
628630

629631
# Always update transform (objects may move between calls)
630632
# NOTE: World scene objects are already in correct world coordinates, no offset needed
631-
rr.log(
632-
rr_path,
633-
rr.Transform3D(
634-
translation=tform[:3, 3],
635-
mat3x3=tform[:3, :3],
636-
axis_length=0.25,
637-
),
638-
static=False,
639-
)
633+
if _RR_HAS_TRANSFORM_AXES:
634+
# rerun >= 0.28: axis_length moved to TransformAxes3D
635+
rr.log(rr_path, rr.Transform3D(translation=tform[:3, 3], mat3x3=tform[:3, :3]), static=False)
636+
rr.log(rr_path, rr.TransformAxes3D(axis_length=0.25), static=False)
637+
else:
638+
# rerun <= 0.27: axis_length on Transform3D directly
639+
rr.log(
640+
rr_path,
641+
rr.Transform3D(translation=tform[:3, 3], mat3x3=tform[:3, :3], axis_length=0.25),
642+
static=False,
643+
)
640644

641645
# Geometry: send only once per node to avoid duplicates
642646
if rr_path not in self._logged_geometry:

source/isaaclab_mimic/test/test_curobo_planner_cube_stack.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727

2828
import gymnasium as gym
2929
import torch
30+
import warp as wp
3031

3132
import isaaclab.utils.math as math_utils
3233
from isaaclab.assets import Articulation, RigidObject
@@ -164,7 +165,7 @@ def _pose_from_xy_quat(self, xy: torch.Tensor, z: float, quat: torch.Tensor) ->
164165
def _get_cube_pos(self, cube_name: str) -> torch.Tensor:
165166
"""Return the current world position of a cube's root (x, y, z)."""
166167
obj: RigidObject = self.env.scene[cube_name]
167-
return obj.data.root_pos_w[0, :3].clone().detach()
168+
return wp.to_torch(obj.data.root_pos_w)[0, :3].clone().detach()
168169

169170
def _place_pose_over_cube(self, cube_name: str, height_offset: float) -> torch.Tensor:
170171
"""Compute a goal pose directly above the named cube using the latest pose."""

source/isaaclab_mimic/test/test_curobo_planner_franka.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020

2121
import gymnasium as gym
2222
import torch
23+
import warp as wp
2324

2425
import isaaclab.utils.assets as _al_assets
2526
import isaaclab.utils.math as math_utils
@@ -141,7 +142,7 @@ def _set_arm_positions(self, q: torch.Tensor) -> None:
141142
q_full = torch.cat([q, fingers], dim=-1)
142143
else:
143144
q_full = q
144-
self.robot.write_joint_position_to_sim(q_full)
145+
self.robot.write_joint_position_to_sim(wp.from_torch(q_full.to(self.env.device)))
145146

146147
@pytest.mark.parametrize("goal_spec, goal_id", predefined_ee_goals_and_ids)
147148
def test_plan_to_predefined_goal(self, goal_spec, goal_id) -> None:

0 commit comments

Comments
 (0)