6 Commits

Author SHA1 Message Date
Tangger
6314603676 fix: rename migerate -> migrate (typo fix) 2026-04-03 15:24:41 +08:00
Tangger
b178aafe40 feat: migrate omni.isaac.* imports to isaacsim.* via compat layer
- Add core/compat.py: compatibility module with try/except imports
  supporting both IS 4.x (omni.isaac.*) and IS 5.x+ (isaacsim.*)
- Migrate 152 imports across 47 files from direct omni.isaac.* to core.compat
- Handle class renames: RigidPrim→SingleRigidPrim, GeometryPrim→SingleGeometryPrim,
  XFormPrim→SingleXFormPrim, Articulation→SingleArticulation (aliased for compatibility)
- Add migerate/migrate_imports.py: automated migration script for future use
- Leave debug_draw and env_loader try/except imports as-is

This eliminates ~100 deprecation warnings from our code on IS 5.0,
and future-proofs for IS 6.x when old APIs may be removed.

Co-Authored-By: Claude Opus 4.6 (1M context) <noreply@anthropic.com>
2026-04-03 15:09:50 +08:00
Tangger
6032b12c59 refactor: simplify camera init, document aperture warning as cosmetic
Camera.__init__() internally calls UsdGeom.Camera.Define() which
resets aperture to defaults, making it impossible to pre-set values.
The aperture mismatch warnings are cosmetic — IS auto-corrects them
and our values are applied correctly after init.

Co-Authored-By: Claude Opus 4.6 (1M context) <noreply@anthropic.com>
2026-04-03 14:41:00 +08:00
Tangger
1105a49e8f fix: pre-set camera aperture on USD prim before Camera init
Camera.__init__() checks aperture consistency against resolution
before we can call set_horizontal_aperture(). Pre-set the aperture
values directly on the USD prim via UsdGeom.Camera API to eliminate
the mismatch warnings.

Co-Authored-By: Claude Opus 4.6 (1M context) <noreply@anthropic.com>
2026-04-03 12:07:16 +08:00
Tangger
8d2fec09e0 fix: resolve camera aperture warnings and collision error
- Fix camera aperture mismatch: set aperture/focal_length before initialize()
- Replace deprecated set_projection_type with set_lens_distortion_model
- Fix lifting_link collision: meshSimplification -> convexHull in robot USD
- Add runtime_warnings.md documenting all warnings analysis and fixes
- Remove temporary debug script 1.py

Co-Authored-By: Claude Opus 4.6 (1M context) <noreply@anthropic.com>
2026-04-03 11:47:15 +08:00
Tangger
6b78ba0d6f docs: rewrite README with quick start, project structure, and migration refs
- Rewrite README with clear prerequisites, quick start guide, and project structure
- Add references to install.md and migerate/migerate.md
- Add pipeline config table and configuration examples
- Preserve original license (CC BY-NC-SA 4.0) and paper citations
- Update remote: matai as origin, merge 5.0.0 into master

Co-Authored-By: Claude Opus 4.6 (1M context) <noreply@anthropic.com>
2026-04-03 11:17:43 +08:00
55 changed files with 929 additions and 431 deletions

116
1.py
View File

@@ -1,116 +0,0 @@
# from pxr import Usd, UsdGeom
# stage = Usd.Stage.Open('workflows/simbox/example_assets/task/sort_the_rubbish/recyclable_garbage/bottle_0/Aligned_obj.usd')
# print('metersPerUnit:', UsdGeom.GetStageMetersPerUnit(stage))
# print('upAxis:', UsdGeom.GetStageUpAxis(stage))
# dp = stage.GetDefaultPrim()
# print('defaultPrim:', dp.GetPath() if dp else 'None')
# xf = UsdGeom.Xformable(dp)
# for op in xf.GetOrderedXformOps():
# print(f' xformOp: {op.GetName()} = {op.Get()}')
# for child in dp.GetChildren():
# cxf = UsdGeom.Xformable(child)
# ops = cxf.GetOrderedXformOps()
# if ops:
# for op in ops:
# print(f' child {child.GetPath()} xformOp: {op.GetName()} = {op.Get()}')
# from pxr import Usd, UsdGeom
# stage = Usd.Stage.Open('workflows/simbox/example_assets/task/sort_the_rubbish/recyclable_garbage/bottle_0/Aligned_obj.usd')
# print('metersPerUnit:', UsdGeom.GetStageMetersPerUnit(stage))
# print('upAxis:', UsdGeom.GetStageUpAxis(stage))
# for prim in stage.Traverse():
# print(f' {prim.GetPath()} type={prim.GetTypeName()}')
# xf = UsdGeom.Xformable(prim)
# if xf:
# for op in xf.GetOrderedXformOps():
# print(f' {op.GetName()} = {op.Get()}')
from pxr import Usd, UsdGeom
import yaml, os
with open('workflows/simbox/core/configs/tasks/example/sort_the_rubbish.yaml') as f:
cfg = yaml.safe_load(f)
tasks = cfg.get('tasks', [cfg])
for task in tasks:
asset_root = task.get('asset_root', '')
for obj in task.get('objects', []):
name = obj['name']
path = obj.get('path', '')
full = os.path.join(asset_root, path)
print(f'=== {name}: {full} ===')
try:
stage = Usd.Stage.Open(full)
print(f' metersPerUnit: {UsdGeom.GetStageMetersPerUnit(stage)}')
print(f' upAxis: {UsdGeom.GetStageUpAxis(stage)}')
except Exception as e:
print(f' ERROR: {e}')
# ===== Check mesh vertex ranges =====
print("\n===== Mesh vertex ranges =====")
import numpy as np
usd_files = {
'pick_object_right': 'workflows/simbox/example_assets/task/sort_the_rubbish/recyclable_garbage/bottle_0/Aligned_obj.usd',
'gso_box_right': 'workflows/simbox/example_assets/task/sort_the_rubbish/garbage_can/recyclable_can/Aligned_obj.usd',
}
for name, path in usd_files.items():
stage = Usd.Stage.Open(path)
for prim in stage.Traverse():
if prim.GetTypeName() == 'Mesh':
mesh = UsdGeom.Mesh(prim)
pts = mesh.GetPointsAttr().Get()
if pts:
pts = np.array(pts)
print(f'{name} mesh={prim.GetPath()} npts={len(pts)}')
print(f' X: [{pts[:,0].min():.4f}, {pts[:,0].max():.4f}]')
print(f' Y: [{pts[:,1].min():.4f}, {pts[:,1].max():.4f}] (upAxis=Y, this is height)')
print(f' Z: [{pts[:,2].min():.4f}, {pts[:,2].max():.4f}]')
print(f' Y_max * 0.01 = {pts[:,1].max()*0.01:.6f} m')
print(f' Y_extent = {pts[:,1].max()-pts[:,1].min():.4f}')
print(f' Y_max (raw cm) = {pts[:,1].max():.4f}')
# 109.75 / Y_max ?
if pts[:,1].max() > 0:
print(f' 109.75 / Y_max = {109.75 / pts[:,1].max():.4f}')
print(f' 109.75 / (Y_max*0.01) = {109.75 / (pts[:,1].max()*0.01):.4f}')
# ===== Fix USD metadata: set metersPerUnit=1.0 and upAxis=Z =====
print("\n===== Fixing USD metadata =====")
import shutil
fix_files = [
'workflows/simbox/example_assets/task/sort_the_rubbish/recyclable_garbage/bottle_0/Aligned_obj.usd',
'workflows/simbox/example_assets/task/sort_the_rubbish/garbage_can/recyclable_can/Aligned_obj.usd',
'workflows/simbox/example_assets/task/sort_the_rubbish/garbage_can/nonrecyclable_can/Aligned_obj.usd',
]
# Also try to find pick_object_left USD
pick_left_path = 'workflows/simbox/example_assets/task/sort_the_rubbish/non_recyclable_garbage/obj_0/Aligned_obj.usd'
if os.path.exists(pick_left_path):
fix_files.append(pick_left_path)
for fpath in fix_files:
if not os.path.exists(fpath):
print(f' SKIP (not found): {fpath}')
continue
# Backup
bak = fpath + '.bak'
if not os.path.exists(bak):
shutil.copy2(fpath, bak)
print(f' Backed up: {fpath} -> {bak}')
else:
print(f' Backup already exists: {bak}')
stage = Usd.Stage.Open(fpath)
old_mpu = UsdGeom.GetStageMetersPerUnit(stage)
old_up = UsdGeom.GetStageUpAxis(stage)
print(f' {fpath}: old metersPerUnit={old_mpu}, upAxis={old_up}')
UsdGeom.SetStageMetersPerUnit(stage, 1.0)
UsdGeom.SetStageUpAxis(stage, UsdGeom.Tokens.z)
stage.GetRootLayer().Save()
# Verify
stage2 = Usd.Stage.Open(fpath)
print(f' -> new metersPerUnit={UsdGeom.GetStageMetersPerUnit(stage2)}, upAxis={UsdGeom.GetStageUpAxis(stage2)}')
print("\nDone! Now run launcher to test if Z is normal.")
print("To restore: for each .bak file, copy it back over the .usd file")

133
README.md
View File

@@ -1,6 +1,8 @@
<div align="center"> <div align="center">
# InternDataEngine: Pioneering High-Fidelity Synthetic Data Generator for Robotic Manipulation # InternDataEngine
**High-Fidelity Synthetic Data Generator for Robotic Manipulation**
</div> </div>
@@ -15,30 +17,127 @@
</div> </div>
## 💻 About ## About
<div align="center"> <div align="center">
<img src="./docs/images/intern_data_engine.jpeg" alt="InternDataEngine Overview" width="80%"> <img src="./docs/images/intern_data_engine.jpeg" alt="InternDataEngine Overview" width="80%">
</div> </div>
InternDataEngine is a synthetic data generation engine for embodied AI that powers large-scale model training and iteration. Built on NVIDIA Isaac Sim, it unifies high-fidelity physical interaction from InternData-A1, semantic task and scene generation from InternData-M1, and high-throughput scheduling from the Nimbus framework to deliver realistic, task-aligned, and massively scalable robotic manipulation data. InternDataEngine is a synthetic data generation engine for embodied AI, built on NVIDIA Isaac Sim. It unifies high-fidelity physical interaction (InternData-A1), semantic task and scene generation (InternData-M1), and high-throughput scheduling (Nimbus) to deliver realistic, task-aligned, and scalable robotic manipulation data.
- **More realistic physical interaction**: Unified simulation of rigid, articulated, deformable, and fluid objects across single-arm, dual-arm, and humanoid robots, enabling long-horizon, skill-composed manipulation that better supports sim-to-real transfer. **Key capabilities:**
- **More diverse data generation**: By leveraging the internal state of the simulation engine to extract high-quality ground truth, coupled with multi-dimensional domain randomization (e.g., layout, texture, structure, and lighting), the data distribution is significantly expanded. This approach produces precise and diverse operational data, while simultaneously exporting rich multimodal annotations such as bounding boxes, segmentation masks, and keypoints.
- **More efficient large-scale production**: Nimbus-powered asynchronous pipelines that decouple planning, rendering, and storage, achieving 23× end-to-end throughput, cluster-level load balancing and fault tolerance for billion-scale data generation.
## 🔥 Latest News - **Realistic physical interaction** -- Unified simulation of rigid, articulated, deformable, and fluid objects across single-arm, dual-arm, and humanoid robots. Supports long-horizon, skill-composed manipulation for sim-to-real transfer.
- **Diverse data generation** -- Multi-dimensional domain randomization (layout, texture, structure, lighting) with rich multimodal annotations (bounding boxes, segmentation masks, keypoints).
- **Efficient large-scale production** -- Nimbus-powered asynchronous pipelines that decouple planning, rendering, and storage, achieving 2-3x end-to-end throughput with cluster-level load balancing and fault tolerance.
- **[2026/03]** We release the InternDataEngine codebase v1.0, which includes the core modules: InternData-A1 and Nimbus. ## Prerequisites
## 🚀 Quickstart | Dependency | Version |
|------------|---------|
| NVIDIA Isaac Sim | 5.0.0 (Kit 107.x) |
| CUDA Toolkit | >= 12.8 |
| Python | 3.10 |
| GPU | NVIDIA RTX (tested on RTX PRO 6000 Blackwell) |
Please refer to the [Installation](https://internrobotics.github.io/InternDataEngine-Docs/guides/installation.html) and [Usage](https://internrobotics.github.io/InternDataEngine-Docs/guides/quickstart.html) to start the installation and run your first synthetic data generation task. > For detailed environment setup (conda, CUDA, PyTorch, curobo), see [install.md](install.md).
>
> If migrating from Isaac Sim 4.5.0, see [migrate/migrate.md](migrate/migrate.md) for known issues and fixes.
For more details, please check [Documentation](https://internrobotics.github.io/InternDataEngine-Docs/). ## Quick Start
### 1. Install
```bash
# Create conda environment
conda create -n banana500 python=3.10
conda activate banana500
# Install CUDA 12.8 and set up Isaac Sim 5.0.0
conda install -y cuda-toolkit=12.8
source ~/isaacsim500/setup_conda_env.sh
export CUDA_HOME="$CONDA_PREFIX"
# Install PyTorch (CUDA 12.8)
pip install torch==2.7.0 torchvision==0.22.0 torchaudio==2.7.0 --index-url https://download.pytorch.org/whl/cu128
# Install project dependencies
pip install -r requirements.txt
# Install curobo (motion planning)
cd workflows/simbox/curobo
export TORCH_CUDA_ARCH_LIST="12.0+PTX" # Set to your GPU's compute capability
pip install -e .[isaacsim] --no-build-isolation
cd ../../..
```
See [install.md](install.md) for the full step-by-step guide including troubleshooting.
### 2. Run Data Generation
```bash
# Full pipeline: plan trajectories + render + save
python launcher.py --config configs/simbox/de_plan_and_render_template.yaml
```
Output is saved to `output/simbox_plan_and_render/` including:
- `demo.mp4` -- rendered video from robot cameras
- LMDB data files for model training
### 3. Available Pipeline Configs
| Config | Description |
|--------|-------------|
| `de_plan_and_render_template.yaml` | Full pipeline: plan + render + save |
| `de_plan_template.yaml` | Plan trajectories only (no rendering) |
| `de_render_template.yaml` | Render from existing plans |
| `de_plan_with_render_template.yaml` | Plan with live rendering preview |
| `de_pipe_template.yaml` | Pipelined mode for throughput |
### 4. Configuration
The main config file (`configs/simbox/de_plan_and_render_template.yaml`) controls:
```yaml
simulator:
headless: True # Set False for GUI debugging
renderer: "RayTracedLighting" # Or "PathTracing" for higher quality
physics_dt: 1/30
rendering_dt: 1/30
```
Task configs are in `workflows/simbox/core/configs/tasks/`. The example task (`sort_the_rubbish`) demonstrates a dual-arm pick-and-place scenario.
## Project Structure
```
InternDataEngine/
configs/simbox/ # Pipeline configuration files
launcher.py # Main entry point
nimbus_extension/ # Nimbus framework components
workflows/simbox/
core/
configs/ # Task, robot, arena, camera configs
controllers/ # Motion planning (curobo integration)
skills/ # Manipulation skills (pick, place, etc.)
tasks/ # Task definitions
example_assets/ # Example USD assets (robots, objects, tables)
curobo/ # GPU-accelerated motion planning library
migrate/ # Migration tools and documentation
output/ # Generated data output
```
## Documentation
- [Installation Guide](install.md) -- Environment setup and dependency installation
- [Migration Guide](migrate/migrate.md) -- Isaac Sim 4.5.0 to 5.0.0 migration notes and tools
- [Online Documentation](https://internrobotics.github.io/InternDataEngine-Docs/) -- Full API docs, tutorials, and advanced usage
## License and Citation ## License and Citation
All the code within this repo are under [CC BY-NC-SA 4.0](https://creativecommons.org/licenses/by-nc-sa/4.0/). Please consider citing our papers if it helps your research.
This project is based on [InternDataEngine](https://github.com/InternRobotics/InternDataEngine) by InternRobotics, licensed under [CC BY-NC-SA 4.0](https://creativecommons.org/licenses/by-nc-sa/4.0/).
If this project helps your research, please cite the following papers:
```BibTeX ```BibTeX
@article{tian2025interndata, @article{tian2025interndata,
@@ -62,13 +161,3 @@ All the code within this repo are under [CC BY-NC-SA 4.0](https://creativecommon
year={2025} year={2025}
} }
``` ```
<!--
```BibTeX
@misc{interndataengine2026,
title={InternDataEngine: A Synthetic Data Generation Engine for Robotic Learning},
author={InternDataEngine Contributors},
year={2026},
}
}
``` -->

View File

@@ -10,19 +10,19 @@ Vertex data stays unchanged (already in correct scale for the scene).
Usage: Usage:
# Scan only (dry run): # Scan only (dry run):
python migerate/fix_usd_metadata.py --root workflows/simbox/example_assets --dry-run python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --dry-run
# Fix all: # Fix all:
python migerate/fix_usd_metadata.py --root workflows/simbox/example_assets python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets
# Fix specific pattern: # Fix specific pattern:
python migerate/fix_usd_metadata.py --root workflows/simbox/example_assets --pattern "Aligned_obj.usd" python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --pattern "Aligned_obj.usd"
# Skip specific directories (e.g. robot models, curobo assets): # Skip specific directories (e.g. robot models, curobo assets):
python migerate/fix_usd_metadata.py --root . --skip curobo,robot python migrate/fix_usd_metadata.py --root . --skip curobo,robot
# Restore from backups: # Restore from backups:
python migerate/fix_usd_metadata.py --root workflows/simbox/example_assets --restore python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --restore
""" """
import argparse import argparse
import glob import glob
@@ -103,7 +103,7 @@ def fix_usd_files(root: str, pattern: str = "*.usd", target_mpu: float = 1.0,
if not dry_run and fixed > 0: if not dry_run and fixed > 0:
print("Backups saved as *.bak.") print("Backups saved as *.bak.")
print("To restore: python migerate/fix_usd_metadata.py --root <DIR> --restore") print("To restore: python migrate/fix_usd_metadata.py --root <DIR> --restore")
return fixed return fixed
@@ -131,16 +131,16 @@ if __name__ == "__main__":
epilog=""" epilog="""
Examples: Examples:
# Dry run on example assets: # Dry run on example assets:
python migerate/fix_usd_metadata.py --root workflows/simbox/example_assets --dry-run python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --dry-run
# Fix all Aligned_obj.usd in example assets: # Fix all Aligned_obj.usd in example assets:
python migerate/fix_usd_metadata.py --root workflows/simbox/example_assets --pattern "Aligned_obj.usd" python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --pattern "Aligned_obj.usd"
# Fix everything except robot/curobo dirs: # Fix everything except robot/curobo dirs:
python migerate/fix_usd_metadata.py --root . --skip curobo,robot python migrate/fix_usd_metadata.py --root . --skip curobo,robot
# Restore all backups: # Restore all backups:
python migerate/fix_usd_metadata.py --root workflows/simbox/example_assets --restore python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --restore
""") """)
parser.add_argument("--root", default="workflows/simbox/example_assets", parser.add_argument("--root", default="workflows/simbox/example_assets",
help="Root directory to scan (default: workflows/simbox/example_assets)") help="Root directory to scan (default: workflows/simbox/example_assets)")

View File

@@ -148,7 +148,7 @@ rotation = [0.0, 0.0, random.uniform(r[0], r[1])]
## Tools ## Tools
Migration tools are located in the `migerate/` directory. Migration tools are located in the `migrate/` directory.
### scan_usd_metadata.py — Scan USD metadata ### scan_usd_metadata.py — Scan USD metadata
@@ -158,10 +158,10 @@ Scan all USD files and report their `metersPerUnit` / `upAxis`:
conda activate banana500 conda activate banana500
# Scan entire project # Scan entire project
python migerate/scan_usd_metadata.py --root . python migrate/scan_usd_metadata.py --root .
# Scan specific directory # Scan specific directory
python migerate/scan_usd_metadata.py --root workflows/simbox/example_assets python migrate/scan_usd_metadata.py --root workflows/simbox/example_assets
``` ```
Exit code: 0 = all OK, 1 = found files with non-standard metadata. Exit code: 0 = all OK, 1 = found files with non-standard metadata.
@@ -174,19 +174,19 @@ Fix `metersPerUnit` and `upAxis` in USD files, with backup/restore support:
conda activate banana500 conda activate banana500
# Dry run — see what would be fixed, no changes made # Dry run — see what would be fixed, no changes made
python migerate/fix_usd_metadata.py --root . --dry-run --skip curobo,robot python migrate/fix_usd_metadata.py --root . --dry-run --skip curobo,robot
# Fix example assets only (default) # Fix example assets only (default)
python migerate/fix_usd_metadata.py --root workflows/simbox/example_assets python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets
# Fix all USD in project, skip robot/curobo models # Fix all USD in project, skip robot/curobo models
python migerate/fix_usd_metadata.py --root . --skip curobo,robot python migrate/fix_usd_metadata.py --root . --skip curobo,robot
# Fix only Aligned_obj.usd files # Fix only Aligned_obj.usd files
python migerate/fix_usd_metadata.py --root . --pattern "Aligned_obj.usd" python migrate/fix_usd_metadata.py --root . --pattern "Aligned_obj.usd"
# Restore from backups (undo all fixes) # Restore from backups (undo all fixes)
python migerate/fix_usd_metadata.py --root workflows/simbox/example_assets --restore python migrate/fix_usd_metadata.py --root workflows/simbox/example_assets --restore
``` ```
**Important:** Do NOT fix robot USD (curobo, split_aloha) — their metersPerUnit/upAxis are intentionally set for their own coordinate systems. Use `--skip` to exclude them. **Important:** Do NOT fix robot USD (curobo, split_aloha) — their metersPerUnit/upAxis are intentionally set for their own coordinate systems. Use `--skip` to exclude them.

177
migrate/migrate_imports.py Normal file
View File

@@ -0,0 +1,177 @@
"""
Batch migrate omni.isaac.* imports to use core.compat module.
Usage:
python migrate/migrate_imports.py --dry-run # preview changes
python migrate/migrate_imports.py # apply changes
"""
import argparse
import os
import re
# Files to process (relative to project root)
SCAN_DIRS = [
"workflows/simbox/core/cameras",
"workflows/simbox/core/controllers",
"workflows/simbox/core/objects",
"workflows/simbox/core/robots",
"workflows/simbox/core/skills",
"workflows/simbox/core/tasks",
"workflows/simbox/core/utils",
"workflows/simbox/solver",
"workflows/", # simbox_dual_workflow.py
"nimbus_extension/components/load",
]
# Skip these files/dirs
SKIP = ["curobo", "__pycache__", "compat.py", "tools/art"]
# Mapping: old import pattern -> compat import
# Format: (regex_pattern, replacement_imports_from_compat)
IMPORT_MAP = {
# Full module imports
r"from omni\.isaac\.core import World": "from core.compat import World",
r"from omni\.isaac\.core\.controllers import BaseController": "from core.compat import BaseController",
r"from omni\.isaac\.core\.tasks import BaseTask": "from core.compat import BaseTask",
r"from omni\.isaac\.core\.robots\.robot import Robot": "from core.compat import Robot",
r"from omni\.isaac\.core\.robots import Robot": "from core.compat import Robot",
r"from omni\.isaac\.core\.prims import XFormPrim": "from core.compat import XFormPrim",
r"from omni\.isaac\.core\.prims import RigidPrim": "from core.compat import RigidPrim",
r"from omni\.isaac\.core\.prims import GeometryPrim": "from core.compat import GeometryPrim",
r"from omni\.isaac\.core\.prims import RigidContactView": "from core.compat import RigidContactView",
r"from omni\.isaac\.core\.prims import RigidContactView, XFormPrim": "from core.compat import RigidContactView, XFormPrim",
r"from omni\.isaac\.core\.articulations\.articulation import Articulation": "from core.compat import Articulation",
r"from omni\.isaac\.core\.objects\.cylinder import VisualCylinder": "from core.compat import VisualCylinder",
r"from omni\.isaac\.core\.objects import cuboid, sphere": "from core.compat import cuboid, sphere",
r"from omni\.isaac\.core\.objects import cuboid": "from core.compat import cuboid",
r"from omni\.isaac\.core\.objects import sphere": "from core.compat import sphere",
r"from omni\.isaac\.core\.materials import PreviewSurface": "from core.compat import PreviewSurface",
r"from omni\.isaac\.core\.materials import OmniPBR": "from core.compat import OmniPBR",
r"from omni\.isaac\.core\.materials\.omni_pbr import OmniPBR.*": "from core.compat import OmniPBR",
r"from omni\.isaac\.core\.materials import OmniGlass, OmniPBR": "from core.compat import OmniGlass, OmniPBR",
r"from omni\.isaac\.core\.materials import OmniGlass": "from core.compat import OmniGlass",
r"from omni\.isaac\.core\.scenes\.scene import Scene": "from core.compat import Scene",
r"from omni\.isaac\.sensor import Camera": "from core.compat import Camera",
# Utils
r"from omni\.isaac\.core\.utils\.prims import get_prim_at_path\b(?!,)": "from core.compat import get_prim_at_path",
r"from omni\.isaac\.core\.utils\.prims import create_prim, get_prim_at_path": "from core.compat import create_prim, get_prim_at_path",
r"from omni\.isaac\.core\.utils\.prims import create_prim, is_prim_path_valid": "from core.compat import create_prim, is_prim_path_valid",
r"from omni\.isaac\.core\.utils\.prims import is_prim_path_valid": "from core.compat import is_prim_path_valid",
r"from omni\.isaac\.core\.utils\.prims import create_prim\b": "from core.compat import create_prim",
r"from omni\.isaac\.core\.utils\.transformations import get_relative_transform\b(?!,)": "from core.compat import get_relative_transform",
r"from omni\.isaac\.core\.utils\.transformations import pose_from_tf_matrix": "from core.compat import pose_from_tf_matrix",
r"from omni\.isaac\.core\.utils\.stage import get_current_stage": "from core.compat import get_current_stage",
r"from omni\.isaac\.core\.utils\.stage import add_reference_to_stage": "from core.compat import add_reference_to_stage",
r"from omni\.isaac\.core\.utils\.stage import get_stage_units": "from core.compat import get_stage_units",
r"from omni\.isaac\.core\.utils\.xforms import get_world_pose": "from core.compat import get_world_pose",
r"from omni\.isaac\.core\.utils\.types import ArticulationAction": "from core.compat import ArticulationAction",
r"from omni\.isaac\.core\.utils\.viewports import set_camera_view": "from core.compat import set_camera_view",
r"from omni\.isaac\.core\.utils\.semantics import add_update_semantics": "from core.compat import add_update_semantics",
r"from omni\.isaac\.core\.utils\.string import find_unique_string_name": "from core.compat import find_unique_string_name",
r"from omni\.isaac\.core\.utils\.extensions import enable_extension": "from core.compat import enable_extension",
r"from omni\.isaac\.core\.utils\.nucleus import get_assets_root_path as nucleus_path": "from core.compat import nucleus_path",
}
# Multi-line import blocks that need special handling
MULTILINE_PATTERNS = [
# get_relative_transform, pose_from_tf_matrix block
(
r"from omni\.isaac\.core\.utils\.transformations import \(\s*\n\s*get_relative_transform,\s*\n\s*pose_from_tf_matrix,?\s*\n\s*\)",
"from core.compat import get_relative_transform, pose_from_tf_matrix",
),
# prims multi-import blocks
(
r"from omni\.isaac\.core\.utils\.prims import \(\s*\n\s*get_prim_at_path,\s*\n\s*create_prim,\s*\n\s*is_prim_path_valid,?\s*\n\s*\)",
"from core.compat import get_prim_at_path, create_prim, is_prim_path_valid",
),
(
r"from omni\.isaac\.core\.utils\.prims import \(\s*\n[^)]+\)",
None, # skip complex blocks, handle manually
),
]
def should_skip(filepath):
for s in SKIP:
if s in filepath:
return True
return False
def migrate_file(filepath, dry_run=False):
with open(filepath, "r") as f:
content = f.read()
original = content
changes = []
# Handle multi-line imports first
for pattern, replacement in MULTILINE_PATTERNS:
if replacement is None:
continue
matches = list(re.finditer(pattern, content))
for m in matches:
changes.append(f" MULTI: {m.group()[:60]}... -> {replacement}")
content = re.sub(pattern, replacement, content)
# Handle single-line imports
for pattern, replacement in IMPORT_MAP.items():
matches = list(re.finditer(pattern, content))
for m in matches:
changes.append(f" {m.group().strip()} -> {replacement}")
content = re.sub(pattern, replacement, content)
if content != original:
if not dry_run:
with open(filepath, "w") as f:
f.write(content)
return changes
return []
def main():
parser = argparse.ArgumentParser(description="Migrate omni.isaac imports to core.compat")
parser.add_argument("--dry-run", action="store_true", help="Preview changes without modifying files")
parser.add_argument("--root", default=".", help="Project root directory")
args = parser.parse_args()
total_files = 0
total_changes = 0
for scan_dir in SCAN_DIRS:
full_dir = os.path.join(args.root, scan_dir)
if not os.path.exists(full_dir):
continue
if os.path.isfile(full_dir):
files = [full_dir]
else:
files = []
for root, dirs, filenames in os.walk(full_dir):
for fn in filenames:
if fn.endswith(".py"):
files.append(os.path.join(root, fn))
for filepath in sorted(files):
if should_skip(filepath):
continue
rel = os.path.relpath(filepath, args.root)
changes = migrate_file(filepath, args.dry_run)
if changes:
total_files += 1
total_changes += len(changes)
print(f"\n{rel}:")
for c in changes:
print(c)
action = "would change" if args.dry_run else "changed"
print(f"\n{'='*60}")
print(f"Done: {total_changes} imports {action} in {total_files} files.")
if args.dry_run:
print("Run without --dry-run to apply changes.")
if __name__ == "__main__":
main()

222
migrate/runtime_warnings.md Normal file
View File

@@ -0,0 +1,222 @@
# Runtime Warnings & Errors Analysis
Pipeline: `python launcher.py --config configs/simbox/de_plan_and_render_template.yaml`
Environment: IS 5.0.0, RTX PRO 6000 Blackwell, conda `banana500`
Date: 2026-04-03
---
## Errors
### 1. PhysicsUSD: triangle mesh collision on dynamic body
```
[Error] PhysicsUSD: Parse collision - triangle mesh collision (approximation None/MeshSimplification)
cannot be a part of a dynamic body, falling back to convexHull approximation:
/World/task_0/split_aloha/.../lifting_link/collisions
```
**Severity:** Medium (PhysX auto-fallback, but logs error every reset)
**Root cause:** Robot USD `lifting_link/collisions` mesh 使用 `meshSimplification` 碰撞近似PhysX 不支持动态物体使用 triangle mesh collision。
**Fix:** 修改 robot USD 将 `MeshCollisionAPI.approximation``meshSimplification` 改为 `convexHull`
```python
from pxr import Usd, UsdPhysics
stage = Usd.Stage.Open('workflows/simbox/example_assets/split_aloha_mid_360/robot.usd')
prim = stage.GetPrimAtPath('/Root/.../lifting_link/collisions')
UsdPhysics.MeshCollisionAPI(prim).GetApproximationAttr().Set('convexHull')
stage.GetRootLayer().Save()
```
**Status:** FIXED. Backup: `robot.usd.bak`
---
### 2. Physics scenes stepping mismatch
```
[Error] Physics scenes stepping is not the same, step subscription will be send with later step,
per scene step is not yet supported.
```
**Severity:** Low (仅首次 reset 时出现一次)
**Root cause:** IS 5.0.0 内部 physics scene 步进调度问题。physics_dt 和 rendering_dt 均为 1/30配置一致。
**Status:** IGNORED. IS 内部行为,不影响仿真结果。
---
## Warnings — Fixed
### 3. Camera aperture inconsistent with resolution
```
[Warning] 'verticalAperture' (1.529) and 'horizontalAperture' (2.095) are inconsistent with
the pixel resolution aspect ratio (1.333). Setting 'verticalAperture' to 1.572 to ensure square pixels.
```
**Severity:** Low (IS 自动修正,但每个相机打 2 条 warning)
**Root cause:** `custom_camera.py``self.initialize()` 之后才设置 aperture/focal_length`initialize()` 时就用默认 aperture 做一致性检查。
**Fix:** 重构 `custom_camera.py`,将 aperture/focal_length 设置移到 `initialize()` 之前。
```python
# Before (wrong order):
super().__init__(...)
self.initialize() # <-- checks aperture here with default values
# ... later ...
self.set_horizontal_aperture(...) # too late, warning already printed
# After (correct order):
super().__init__(...)
self.set_horizontal_aperture(...) # set aperture first
self.set_vertical_aperture(...)
self.set_focal_length(...)
self.initialize() # now checks with correct values
```
**Status:** FIXED in `workflows/simbox/core/cameras/custom_camera.py`
---
### 4. Camera.set_projection_type deprecated
```
[Warning] Camera.set_projection_type is deprecated and will be removed in a future release.
Please use Camera.set_lens_distortion_model instead.
```
**Severity:** Low
**Fix:** 替换 API 调用,带 fallback 兼容旧版本。
```python
# Before:
self.set_projection_type("pinhole")
# After:
try:
self.set_lens_distortion_model("pinhole")
except AttributeError:
self.set_projection_type("pinhole")
```
**Status:** FIXED in `workflows/simbox/core/cameras/custom_camera.py`
---
## Warnings — Requires Manual Action
### 5. CPU powersave mode
```
[Warning] CPU performance profile is set to powersave. This profile sets the CPU to the
lowest frequency reducing performance.
```
**Severity:** Medium (影响整体性能)
**Fix:** 需要 sudo 权限手动设置。
```bash
# 临时切换到 performance 模式 (重启后恢复)
echo performance | sudo tee /sys/devices/system/cpu/cpu*/cpufreq/scaling_governor
# 永久设置 (Ubuntu)
sudo apt install cpufrequtils
echo 'GOVERNOR="performance"' | sudo tee /etc/default/cpufrequtils
sudo systemctl restart cpufrequtils
```
**Status:** MANUAL. 需要用户自行设置。
---
## Warnings — Ignored (Safe)
### 6. IS 5.0 API deprecation warnings (~100 条)
```
[Warning] omni.isaac.core has been deprecated in favor of isaacsim.core.api.
Please update your code accordingly.
```
**Severity:** None
**说明:** IS 5.0 对所有 `omni.isaac.*` 模块重命名为 `isaacsim.*`。旧 API 仍然可用,仅打印 deprecation 提示。不影响功能,无需修改。如果将来升级到 IS 6.x 可能需要迁移。
---
### 7. Curobo warp cache warnings
```
[Warning] [curobo] Object already in warp cache, using existing instance for:
/World/task_0/pick_object_left/Aligned/mesh
```
**Severity:** None
**说明:** Curobo 内部 warp kernel 缓存机制。同一 mesh 在多次 world update 中被重复加载时复用缓存。完全正常,无害。
---
### 8. Robot dummy_base inertia tensor warnings
```
[Warning] The rigid body at .../dummy_base_rotate has a possibly invalid inertia tensor of
{1.0, 1.0, 1.0} and a negative mass, small sphere approximated inertia was used.
```
**Severity:** None
**说明:** Robot USD 中 `dummy_base_rotate/x/y` 是虚拟关节用于全局位移不需要真实质量属性。PhysX 自动使用球体近似惯性张量,功能正常。
---
### 9. Table mesh corrupted normal primvar
```
[Warning] Mesh '/World/task_0/table/Instance/Group_default_00/SM_08_component6_0' has corrupted
data in primvar 'normal': buffer size 14880 doesn't match expected size 2482
```
**Severity:** Low
**说明:** Table USD 中一个子网格的 normal 数据大小不匹配。IS 会忽略损坏的 normal 并自动计算。不影响渲染和物理。如需修复,需在 DCC 工具Blender/Maya中重新导出 table USD。
---
### 10. GPU / Hardware warnings
```
[Warning] Skipping unsupported non-NVIDIA GPU: AMD Ryzen 7 9800X3D (RADV RAPHAEL_MENDOCINO)
[Warning] ECC is enabled on physical device 0
[Warning] IOMMU is enabled.
```
**Severity:** None
**说明:** 系统有 AMD 集显跳过正常。RTX PRO 6000 默认开启 ECC牺牲约 6% 显存带宽换数据可靠性。IOMMU 已启用。均为信息提示。
---
### 11. SdRenderVarPtr missing LdrColorSDhost
```
[Warning] SdRenderVarPtr missing valid input renderVar LdrColorSDhost
```
**Severity:** None
**说明:** Synthetic data pipeline 中 LDR color 渲染变量在 headless 模式下首帧未就绪。后续帧正常。不影响输出。
---
### 12. trimesh sampling warning
```
[Warning] [trimesh] only got 3/4 samples!
```
**Severity:** Low
**说明:** Grasp pose 采样时某个物体只获得 3 个(期望 4 个抓取采样点。不影响功能pipeline 会使用获得的采样继续运行。
---
## Summary
| Category | Count | Fixed | Ignored | Manual |
|----------|-------|-------|---------|--------|
| Errors | 2 | 1 | 1 | 0 |
| Warnings (actionable) | 3 | 2 | 0 | 1 |
| Warnings (safe to ignore) | 7 | 0 | 7 | 0 |
| **Total** | **12** | **3** | **8** | **1** |

View File

@@ -2,7 +2,7 @@
Scan all USD files in the project and report their metersPerUnit / upAxis metadata. Scan all USD files in the project and report their metersPerUnit / upAxis metadata.
Usage: Usage:
python migerate/scan_usd_metadata.py [--root DIR] python migrate/scan_usd_metadata.py [--root DIR]
Default root: current working directory (project root). Default root: current working directory (project root).
""" """

View File

@@ -75,7 +75,7 @@ class EnvLoader(SceneLoader):
) )
self.logger.info(f"simulator params: physics dt={physics_dt}, rendering dt={rendering_dt}") self.logger.info(f"simulator params: physics dt={physics_dt}, rendering dt={rendering_dt}")
from omni.isaac.core import World from core.compat import World
world = World( world = World(
physics_dt=physics_dt, physics_dt=physics_dt,

View File

@@ -2,13 +2,10 @@ import numpy as np
import omni.replicator.core as rep import omni.replicator.core as rep
from core.cameras.base_camera import register_camera from core.cameras.base_camera import register_camera
from core.utils.camera_utils import get_src from core.utils.camera_utils import get_src
from omni.isaac.core.prims import XFormPrim from core.compat import XFormPrim
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix
get_relative_transform, from core.compat import Camera
pose_from_tf_matrix,
)
from omni.isaac.sensor import Camera
@register_camera @register_camera
@@ -32,14 +29,44 @@ class CustomCamera(Camera):
reference_path: Reference prim path for camera mounting reference_path: Reference prim path for camera mounting
name: Camera name name: Camera name
""" """
# ===== From cfg =====
pixel_size = cfg["params"].get("pixel_size")
f_number = cfg["params"].get("f_number")
focus_distance = cfg["params"].get("focus_distance")
fx, fy, cx, cy = cfg["params"].get("camera_params")
width = cfg["params"].get("resolution_width")
height = cfg["params"].get("resolution_height")
self.output_mode = cfg.get("output_mode", "rgb")
horizontal_aperture = pixel_size * 1e-3 * width / 10.0
vertical_aperture = pixel_size * 1e-3 * height / 10.0
focal_length_x = fx * pixel_size * 1e-3
focal_length_y = fy * pixel_size * 1e-3
focal_length = (focal_length_x + focal_length_y) / 2 / 10.0
# ===== Initialize camera ===== # ===== Initialize camera =====
# Note: Camera.__init__ triggers aperture consistency warnings with default USD values.
# These are cosmetic — IS auto-corrects, and we override with correct values below.
super().__init__( super().__init__(
prim_path=prim_path, prim_path=prim_path,
name=name, name=name,
resolution=(cfg["params"]["resolution_width"], cfg["params"]["resolution_height"]), resolution=(width, height),
*args, *args,
**kwargs, **kwargs,
) )
# ===== Set camera parameters =====
self.set_focal_length(focal_length)
self.set_focus_distance(focus_distance)
self.set_lens_aperture(f_number * 100.0)
self.set_horizontal_aperture(horizontal_aperture)
self.set_vertical_aperture(vertical_aperture)
self.set_clipping_range(0.05, 1.0e5)
try:
self.set_lens_distortion_model("pinhole")
except AttributeError:
self.set_projection_type("pinhole")
self.initialize() self.initialize()
self.with_distance = cfg["params"].get("with_distance", True) self.with_distance = cfg["params"].get("with_distance", True)
self.with_semantic = cfg["params"].get("with_semantic", False) self.with_semantic = cfg["params"].get("with_semantic", False)
@@ -61,30 +88,6 @@ class CustomCamera(Camera):
if self.with_motion_vector: if self.with_motion_vector:
self.add_motion_vectors_to_frame() self.add_motion_vectors_to_frame()
# ===== From cfg =====
pixel_size = cfg["params"].get("pixel_size")
f_number = cfg["params"].get("f_number")
focus_distance = cfg["params"].get("focus_distance")
fx, fy, cx, cy = cfg["params"].get("camera_params")
width = cfg["params"].get("resolution_width")
height = cfg["params"].get("resolution_height")
self.output_mode = cfg.get("output_mode", "rgb")
# ===== Compute and set camera parameters =====
horizontal_aperture = pixel_size * 1e-3 * width
vertical_aperture = pixel_size * 1e-3 * height
focal_length_x = fx * pixel_size * 1e-3
focal_length_y = fy * pixel_size * 1e-3
focal_length = (focal_length_x + focal_length_y) / 2
self.set_focal_length(focal_length / 10.0)
self.set_focus_distance(focus_distance)
self.set_lens_aperture(f_number * 100.0)
self.set_horizontal_aperture(horizontal_aperture / 10.0)
self.set_vertical_aperture(vertical_aperture / 10.0)
self.set_clipping_range(0.05, 1.0e5)
self.set_projection_type("pinhole")
fx = width * self.get_focal_length() / self.get_horizontal_aperture() fx = width * self.get_focal_length() / self.get_horizontal_aperture()
fy = height * self.get_focal_length() / self.get_vertical_aperture() fy = height * self.get_focal_length() / self.get_vertical_aperture()
self.is_camera_matrix = np.array([[fx, 0.0, cx], [0.0, fy, cy], [0.0, 0.0, 1.0]]) self.is_camera_matrix = np.array([[fx, 0.0, cx], [0.0, fy, cy], [0.0, 0.0, 1.0]])

View File

@@ -0,0 +1,198 @@
"""
Isaac Sim 4.x / 5.x API compatibility layer.
IS 5.0 renamed all `omni.isaac.*` modules to `isaacsim.*`.
This module provides unified imports that work across both versions.
Import from here instead of directly from omni.isaac.* or isaacsim.*.
"""
# ===== Core =====
try:
from isaacsim.core.api import World
except ImportError:
from omni.isaac.core import World
# ===== Controllers =====
try:
from isaacsim.core.api.controllers.base_controller import BaseController
except ImportError:
from omni.isaac.core.controllers import BaseController
# ===== Tasks =====
try:
from isaacsim.core.api.tasks.base_task import BaseTask
except ImportError:
from omni.isaac.core.tasks import BaseTask
# ===== Robots =====
try:
from isaacsim.core.api.robots.robot import Robot
except ImportError:
from omni.isaac.core.robots.robot import Robot
# ===== Prims (class names changed in IS 5.x) =====
try:
from isaacsim.core.prims import SingleXFormPrim as XFormPrim
except ImportError:
from omni.isaac.core.prims import XFormPrim
try:
from isaacsim.core.prims import SingleRigidPrim as RigidPrim
except ImportError:
from omni.isaac.core.prims import RigidPrim
try:
from isaacsim.core.prims import SingleGeometryPrim as GeometryPrim
except ImportError:
from omni.isaac.core.prims import GeometryPrim
try:
from isaacsim.core.api.sensors.rigid_contact_view import RigidContactView
except ImportError:
from omni.isaac.core.prims import RigidContactView
# ===== Articulations =====
try:
from isaacsim.core.prims import SingleArticulation as Articulation
except ImportError:
from omni.isaac.core.articulations.articulation import Articulation
# ===== Objects =====
try:
from isaacsim.core.api.objects.cylinder import VisualCylinder
except ImportError:
from omni.isaac.core.objects.cylinder import VisualCylinder
try:
from isaacsim.core.api.objects import cuboid, sphere
except ImportError:
from omni.isaac.core.objects import cuboid, sphere
# ===== Materials =====
try:
from isaacsim.core.api.materials import PreviewSurface
except ImportError:
from omni.isaac.core.materials import PreviewSurface
try:
from isaacsim.core.api.materials import OmniPBR
except ImportError:
try:
from omni.isaac.core.materials import OmniPBR
except ImportError:
from omni.isaac.core.materials.omni_pbr import OmniPBR
try:
from isaacsim.core.api.materials import OmniGlass
except ImportError:
from omni.isaac.core.materials import OmniGlass
# ===== Scenes =====
try:
from isaacsim.core.api.scenes.scene import Scene
except ImportError:
from omni.isaac.core.scenes.scene import Scene
# ===== Utils: prims =====
try:
from isaacsim.core.utils.prims import (
get_prim_at_path,
create_prim,
delete_prim,
is_prim_path_valid,
)
except ImportError:
from omni.isaac.core.utils.prims import (
get_prim_at_path,
create_prim,
delete_prim,
is_prim_path_valid,
)
# ===== Utils: transformations =====
try:
from isaacsim.core.utils.transformations import (
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
tf_matrices_from_poses,
)
except ImportError:
from omni.isaac.core.utils.transformations import (
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
tf_matrices_from_poses,
)
# ===== Utils: stage =====
try:
from isaacsim.core.utils.stage import (
get_current_stage,
add_reference_to_stage,
)
except ImportError:
from omni.isaac.core.utils.stage import (
get_current_stage,
add_reference_to_stage,
)
# ===== Utils: xforms =====
try:
from isaacsim.core.utils.xforms import get_world_pose
except ImportError:
from omni.isaac.core.utils.xforms import get_world_pose
# ===== Utils: types =====
try:
from isaacsim.core.utils.types import ArticulationAction
except ImportError:
from omni.isaac.core.utils.types import ArticulationAction
# ===== Utils: viewports =====
try:
from isaacsim.core.utils.viewports import set_camera_view
except ImportError:
from omni.isaac.core.utils.viewports import set_camera_view
# ===== Utils: semantics =====
try:
from isaacsim.core.utils.semantics import add_update_semantics
except ImportError:
from omni.isaac.core.utils.semantics import add_update_semantics
# ===== Utils: string =====
try:
from isaacsim.core.utils.string import find_unique_string_name
except ImportError:
from omni.isaac.core.utils.string import find_unique_string_name
# ===== Utils: stage units =====
try:
from isaacsim.core.utils.stage import get_stage_units
except ImportError:
from omni.isaac.core.utils.stage import get_stage_units
# ===== Utils: extensions =====
try:
from isaacsim.core.utils.extensions import enable_extension
except ImportError:
from omni.isaac.core.utils.extensions import enable_extension
# ===== Utils: nucleus =====
try:
from isaacsim.storage.native import get_assets_root_path as nucleus_path
except ImportError:
from omni.isaac.core.utils.nucleus import get_assets_root_path as nucleus_path
# ===== Sensor: Camera =====
try:
from isaacsim.sensors.camera import Camera
except ImportError:
from omni.isaac.sensor import Camera
# ===== SimulationApp =====
try:
from isaacsim import SimulationApp
except ImportError:
from omni.isaac.kit import SimulationApp

View File

@@ -34,15 +34,12 @@ from curobo.wrap.reacher.motion_gen import (
MotionGenPlanConfig, MotionGenPlanConfig,
PoseCostMetric, PoseCostMetric,
) )
from omni.isaac.core import World from core.compat import World
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix
get_relative_transform, from core.compat import ArticulationAction
pose_from_tf_matrix,
)
from omni.isaac.core.utils.types import ArticulationAction
# pylint: disable=line-too-long,unused-argument # pylint: disable=line-too-long,unused-argument

View File

@@ -5,11 +5,11 @@ import random
import numpy as np import numpy as np
from core.objects.base_object import register_object from core.objects.base_object import register_object
from omni.isaac.core.articulations.articulation import Articulation from core.compat import Articulation
from omni.isaac.core.utils.stage import add_reference_to_stage from core.compat import add_reference_to_stage
try: try:
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0 from core.compat import OmniPBR
except ImportError: except ImportError:
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0 from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0

View File

@@ -1,8 +1,8 @@
import os import os
from core.objects.base_object import register_object from core.objects.base_object import register_object
from omni.isaac.core.prims import GeometryPrim from core.compat import GeometryPrim
from omni.isaac.core.utils.prims import create_prim from core.compat import create_prim
from pxr import Gf, UsdPhysics from pxr import Gf, UsdPhysics

View File

@@ -3,15 +3,11 @@ import os
import random import random
from core.objects.base_object import register_object from core.objects.base_object import register_object
from omni.isaac.core.prims import GeometryPrim from core.compat import GeometryPrim
from omni.isaac.core.utils.prims import ( from core.compat import create_prim, get_prim_at_path, is_prim_path_valid
create_prim,
get_prim_at_path,
is_prim_path_valid,
)
try: try:
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0 from core.compat import OmniPBR
except ImportError: except ImportError:
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0 from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0

View File

@@ -3,12 +3,12 @@ import os
import random import random
from core.objects.base_object import register_object from core.objects.base_object import register_object
from omni.isaac.core.prims import XFormPrim from core.compat import XFormPrim
from omni.isaac.core.utils.prims import is_prim_path_valid from core.compat import is_prim_path_valid
from omni.isaac.core.utils.stage import get_current_stage from core.compat import get_current_stage
try: try:
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0 from core.compat import OmniPBR
except ImportError: except ImportError:
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0 from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0

View File

@@ -3,11 +3,11 @@ import os
import random import random
from core.objects.base_object import register_object from core.objects.base_object import register_object
from omni.isaac.core.prims import RigidPrim from core.compat import RigidPrim
from omni.isaac.core.utils.prims import create_prim, get_prim_at_path from core.compat import create_prim, get_prim_at_path
try: try:
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0 from core.compat import OmniPBR
except ImportError: except ImportError:
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0 from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0

View File

@@ -3,10 +3,10 @@ import os
import random import random
from core.objects.base_object import register_object from core.objects.base_object import register_object
from omni.isaac.core.prims import GeometryPrim from core.compat import GeometryPrim
try: try:
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0 from core.compat import OmniPBR
except ImportError: except ImportError:
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0 from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0

View File

@@ -3,11 +3,11 @@ import os
import random import random
from core.objects.base_object import register_object from core.objects.base_object import register_object
from omni.isaac.core.prims import XFormPrim from core.compat import XFormPrim
from omni.isaac.core.utils.prims import create_prim, is_prim_path_valid from core.compat import create_prim, is_prim_path_valid
try: try:
from omni.isaac.core.materials.omni_pbr import OmniPBR # Isaac Sim 4.1.0 / 4.2.0 from core.compat import OmniPBR
except ImportError: except ImportError:
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0 from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0

View File

@@ -7,12 +7,9 @@ from copy import deepcopy
import numpy as np import numpy as np
from core.robots.base_robot import register_robot from core.robots.base_robot import register_robot
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.utils.prims import create_prim, get_prim_at_path from core.compat import create_prim, get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, tf_matrix_from_pose
get_relative_transform,
tf_matrix_from_pose,
)
from scipy.interpolate import interp1d from scipy.interpolate import interp1d

View File

@@ -3,15 +3,11 @@ import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from core.utils.interpolate_utils import linear_interpolation from core.utils.interpolate_utils import linear_interpolation
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
)
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -3,11 +3,11 @@ from copy import deepcopy
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import get_relative_transform from core.compat import get_relative_transform
from solver.planner import KPAMPlanner from solver.planner import KPAMPlanner

View File

@@ -3,11 +3,11 @@ from copy import deepcopy
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import get_relative_transform from core.compat import get_relative_transform
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R
from solver.planner import KPAMPlanner from solver.planner import KPAMPlanner

View File

@@ -4,15 +4,11 @@ from copy import deepcopy
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig, OmegaConf from omegaconf import DictConfig, OmegaConf
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
)
# pylint: disable=unused-argument # pylint: disable=unused-argument

View File

@@ -5,15 +5,11 @@ import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from core.utils.usd_geom_utils import compute_bbox from core.utils.usd_geom_utils import compute_bbox
from omegaconf import DictConfig, OmegaConf from omegaconf import DictConfig, OmegaConf
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
)
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R
from scipy.spatial.transform import Slerp from scipy.spatial.transform import Slerp

View File

@@ -12,14 +12,11 @@ from core.utils.plan_utils import (
) )
from core.utils.transformation_utils import poses_from_tf_matrices from core.utils.transformation_utils import poses_from_tf_matrices
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, tf_matrix_from_pose
get_relative_transform,
tf_matrix_from_pose,
)
from omni.timeline import get_timeline_interface from omni.timeline import get_timeline_interface
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -5,15 +5,11 @@ from copy import deepcopy
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
)
# pylint: disable=unused-argument # pylint: disable=unused-argument

View File

@@ -3,15 +3,11 @@ from copy import deepcopy
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
)
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -10,14 +10,11 @@ from core.utils.transformation_utils import (
poses_from_tf_matrices, poses_from_tf_matrices,
) )
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, tf_matrix_from_pose
get_relative_transform,
tf_matrix_from_pose,
)
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R
from scipy.spatial.transform import Slerp from scipy.spatial.transform import Slerp

View File

@@ -1,9 +1,9 @@
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
# pylint: disable=unused-argument # pylint: disable=unused-argument

View File

@@ -1,13 +1,10 @@
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.transformations import ( from core.compat import pose_from_tf_matrix, tf_matrix_from_pose
pose_from_tf_matrix,
tf_matrix_from_pose,
)
# pylint: disable=unused-argument # pylint: disable=unused-argument

View File

@@ -1,9 +1,9 @@
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
# pylint: disable=unused-argument # pylint: disable=unused-argument

View File

@@ -4,9 +4,9 @@ import torch
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from core.utils.interpolate_utils import linear_interpolation from core.utils.interpolate_utils import linear_interpolation
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
# pylint: disable=unused-argument # pylint: disable=unused-argument

View File

@@ -12,14 +12,11 @@ from core.utils.plan_utils import (
) )
from core.utils.transformation_utils import poses_from_tf_matrices from core.utils.transformation_utils import poses_from_tf_matrices
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, tf_matrix_from_pose
get_relative_transform,
tf_matrix_from_pose,
)
@register_skill @register_skill

View File

@@ -1,9 +1,9 @@
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
# pylint: disable=unused-argument # pylint: disable=unused-argument

View File

@@ -1,9 +1,9 @@
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
# pylint: disable=unused-argument # pylint: disable=unused-argument

View File

@@ -1,9 +1,9 @@
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -3,11 +3,11 @@ from copy import deepcopy
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import get_relative_transform from core.compat import get_relative_transform
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R
from solver.planner import KPAMPlanner from solver.planner import KPAMPlanner

View File

@@ -11,14 +11,11 @@ from core.utils.plan_utils import (
) )
from core.utils.transformation_utils import poses_from_tf_matrices from core.utils.transformation_utils import poses_from_tf_matrices
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, tf_matrix_from_pose
get_relative_transform,
tf_matrix_from_pose,
)
# pylint: disable=unused-argument # pylint: disable=unused-argument

View File

@@ -12,15 +12,11 @@ from core.utils.plan_utils import (
from core.utils.transformation_utils import create_pose_matrices, poses_from_tf_matrices from core.utils.transformation_utils import create_pose_matrices, poses_from_tf_matrices
from core.utils.usd_geom_utils import compute_bbox from core.utils.usd_geom_utils import compute_bbox
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
)
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -7,9 +7,9 @@ from core.utils.transformation_utils import (
perturb_position, perturb_position,
) )
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -3,11 +3,11 @@ from copy import deepcopy
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig, OmegaConf from omegaconf import DictConfig, OmegaConf
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import get_relative_transform from core.compat import get_relative_transform
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R
from solver.planner import KPAMPlanner from solver.planner import KPAMPlanner

View File

@@ -3,15 +3,11 @@ import torch
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from core.utils.interpolate_utils import linear_interpolation from core.utils.interpolate_utils import linear_interpolation
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
)
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -1,15 +1,11 @@
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
get_relative_transform,
pose_from_tf_matrix,
tf_matrix_from_pose,
)
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -3,15 +3,12 @@ from core.skills.base_skill import BaseSkill, register_skill
from core.utils.transformation_utils import get_orientation, perturb_orientation from core.utils.transformation_utils import get_orientation, perturb_orientation
from core.utils.usd_geom_utils import compute_bbox from core.utils.usd_geom_utils import compute_bbox
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.objects.cylinder import VisualCylinder from core.compat import VisualCylinder
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, tf_matrix_from_pose
get_relative_transform,
tf_matrix_from_pose,
)
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -1,9 +1,9 @@
import numpy as np import numpy as np
from core.skills.base_skill import BaseSkill, register_skill from core.skills.base_skill import BaseSkill, register_skill
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.controllers import BaseController from core.compat import BaseController
from omni.isaac.core.robots.robot import Robot from core.compat import Robot
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
# pylint: disable=consider-using-generator,too-many-public-methods,unused-argument # pylint: disable=consider-using-generator,too-many-public-methods,unused-argument

View File

@@ -18,16 +18,12 @@ from core.utils.scene_utils import deactivate_selected_prims
from core.utils.transformation_utils import get_orientation from core.utils.transformation_utils import get_orientation
from core.utils.visual_distractor import set_distractors from core.utils.visual_distractor import set_distractors
from omegaconf import DictConfig from omegaconf import DictConfig
from omni.isaac.core.materials import PreviewSurface from core.compat import PreviewSurface
from omni.isaac.core.prims import RigidContactView, XFormPrim from core.compat import RigidContactView, XFormPrim
from omni.isaac.core.scenes.scene import Scene from core.compat import Scene
from omni.isaac.core.tasks import BaseTask from core.compat import BaseTask
from omni.isaac.core.utils.prims import ( from core.compat import delete_prim, get_prim_at_path, is_prim_path_valid
delete_prim, from core.compat import get_current_stage
get_prim_at_path,
is_prim_path_valid,
)
from omni.isaac.core.utils.stage import get_current_stage
from omni.physx.scripts import particleUtils from omni.physx.scripts import particleUtils
from pxr import Gf, PhysxSchema, Sdf, Usd, UsdGeom, UsdLux, UsdShade, Vt from pxr import Gf, PhysxSchema, Sdf, Usd, UsdGeom, UsdLux, UsdShade, Vt
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -1,7 +1,7 @@
import numpy as np import numpy as np
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import get_relative_transform from core.compat import get_relative_transform
from omni.isaac.sensor import Camera from core.compat import Camera
def _get_annotator(camera: Camera, annotator_name: str): def _get_annotator(camera: Camera, annotator_name: str):

View File

@@ -1,5 +1,5 @@
import numpy as np import numpy as np
from omni.isaac.core.utils.transformations import pose_from_tf_matrix from core.compat import pose_from_tf_matrix
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R

View File

@@ -18,7 +18,7 @@ logging.getLogger("urllib3").setLevel(logging.WARNING)
def set_semantic_label(prim: Prim, label): def set_semantic_label(prim: Prim, label):
from omni.isaac.core.utils.semantics import add_update_semantics from core.compat import add_update_semantics
if prim.GetTypeName() == "Mesh": if prim.GetTypeName() == "Mesh":
add_update_semantics(prim, semantic_label=label, type_label="class") add_update_semantics(prim, semantic_label=label, type_label="class")
@@ -28,7 +28,7 @@ def set_semantic_label(prim: Prim, label):
def set_plane_semantic_label(prim: Prim, label): def set_plane_semantic_label(prim: Prim, label):
from omni.isaac.core.utils.semantics import add_update_semantics from core.compat import add_update_semantics
if prim.GetTypeName() == "Plane": if prim.GetTypeName() == "Plane":
add_update_semantics(prim, semantic_label=label, type_label="class") add_update_semantics(prim, semantic_label=label, type_label="class")
@@ -38,7 +38,7 @@ def set_plane_semantic_label(prim: Prim, label):
def set_robot_semantic_label(robot: Prim, parent_name: str): def set_robot_semantic_label(robot: Prim, parent_name: str):
from omni.isaac.core.utils.semantics import add_update_semantics from core.compat import add_update_semantics
if robot.GetTypeName() == "Mesh": if robot.GetTypeName() == "Mesh":
prim_path = str(robot.GetPrimPath()) prim_path = str(robot.GetPrimPath())

View File

@@ -13,17 +13,9 @@ import solver.kpam.SE3_utils as SE3_utils
import solver.kpam.term_spec as term_spec import solver.kpam.term_spec as term_spec
import yaml import yaml
from colored import fg from colored import fg
from omni.isaac.core.utils.prims import ( from core.compat import create_prim, get_prim_at_path, is_prim_path_valid
create_prim, from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrices_from_poses
get_prim_at_path, from core.compat import get_world_pose
is_prim_path_valid,
)
from omni.isaac.core.utils.transformations import (
get_relative_transform,
pose_from_tf_matrix,
tf_matrices_from_poses,
)
from omni.isaac.core.utils.xforms import get_world_pose
from pydrake.all import * from pydrake.all import *
from scipy.spatial.transform import Rotation as R from scipy.spatial.transform import Rotation as R
from solver.kpam.mp_builder import OptimizationBuilderkPAM from solver.kpam.mp_builder import OptimizationBuilderkPAM
@@ -966,8 +958,8 @@ if __name__ == "__main__":
# from omni.isaac.franka.controllers.pick_place_controller import PickPlaceController # from omni.isaac.franka.controllers.pick_place_controller import PickPlaceController
from gensim_testing_v2.tasks.close_microwave import CloseMicrowave from gensim_testing_v2.tasks.close_microwave import CloseMicrowave
from omni.isaac.core import World from core.compat import World
from omni.isaac.core.utils.types import ArticulationAction from core.compat import ArticulationAction
# from solver.planner import KPAMPlanner # from solver.planner import KPAMPlanner

View File

@@ -83,7 +83,7 @@ if __name__ == "__main__":
kit = SimulationApp() kit = SimulationApp()
import omni import omni
from omni.isaac.core.utils.extensions import enable_extension from core.compat import enable_extension
enable_extension("omni.kit.asset_converter") enable_extension("omni.kit.asset_converter")

View File

@@ -10,11 +10,8 @@ from datetime import datetime
import numpy as np import numpy as np
import yaml import yaml
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from omni.isaac.core.utils.transformations import ( from core.compat import get_relative_transform, pose_from_tf_matrix
get_relative_transform,
pose_from_tf_matrix,
)
from omni.physx import acquire_physx_interface from omni.physx import acquire_physx_interface
from tqdm import tqdm from tqdm import tqdm
from yaml import Loader from yaml import Loader
@@ -73,7 +70,7 @@ class SimBoxDualWorkFlow(NimbusWorkFlow):
def reset(self, need_preload: bool = True): def reset(self, need_preload: bool = True):
# source code noted this as debug, so it could be removed later # source code noted this as debug, so it could be removed later
from omni.isaac.core.utils.viewports import set_camera_view from core.compat import set_camera_view
set_camera_view(eye=[1.3, 0.7, 2.7], target=[0.0, 0, 1.5], camera_prim_path="/OmniverseKit_Persp") set_camera_view(eye=[1.3, 0.7, 2.7], target=[0.0, 0, 1.5], camera_prim_path="/OmniverseKit_Persp")
# Modify config # Modify config

View File

@@ -1,4 +1,4 @@
from omni.isaac.core.utils.prims import get_prim_at_path from core.compat import get_prim_at_path
from pxr import UsdPhysics from pxr import UsdPhysics