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>
This commit is contained in:
@@ -2,13 +2,10 @@ import numpy as np
|
||||
import omni.replicator.core as rep
|
||||
from core.cameras.base_camera import register_camera
|
||||
from core.utils.camera_utils import get_src
|
||||
from omni.isaac.core.prims import XFormPrim
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
)
|
||||
from omni.isaac.sensor import Camera
|
||||
from core.compat import XFormPrim
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix
|
||||
from core.compat import Camera
|
||||
|
||||
|
||||
@register_camera
|
||||
|
||||
198
workflows/simbox/core/compat.py
Normal file
198
workflows/simbox/core/compat.py
Normal 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
|
||||
@@ -34,15 +34,12 @@ from curobo.wrap.reacher.motion_gen import (
|
||||
MotionGenPlanConfig,
|
||||
PoseCostMetric,
|
||||
)
|
||||
from omni.isaac.core import World
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
)
|
||||
from omni.isaac.core.utils.types import ArticulationAction
|
||||
from core.compat import World
|
||||
from core.compat import BaseController
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix
|
||||
from core.compat import ArticulationAction
|
||||
|
||||
|
||||
# pylint: disable=line-too-long,unused-argument
|
||||
|
||||
@@ -5,11 +5,11 @@ import random
|
||||
|
||||
import numpy as np
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.articulations.articulation import Articulation
|
||||
from omni.isaac.core.utils.stage import add_reference_to_stage
|
||||
from core.compat import Articulation
|
||||
from core.compat import add_reference_to_stage
|
||||
|
||||
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:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -1,8 +1,8 @@
|
||||
import os
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import GeometryPrim
|
||||
from omni.isaac.core.utils.prims import create_prim
|
||||
from core.compat import GeometryPrim
|
||||
from core.compat import create_prim
|
||||
from pxr import Gf, UsdPhysics
|
||||
|
||||
|
||||
|
||||
@@ -3,15 +3,11 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import GeometryPrim
|
||||
from omni.isaac.core.utils.prims import (
|
||||
create_prim,
|
||||
get_prim_at_path,
|
||||
is_prim_path_valid,
|
||||
)
|
||||
from core.compat import GeometryPrim
|
||||
from core.compat import create_prim, get_prim_at_path, is_prim_path_valid
|
||||
|
||||
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:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -3,12 +3,12 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import XFormPrim
|
||||
from omni.isaac.core.utils.prims import is_prim_path_valid
|
||||
from omni.isaac.core.utils.stage import get_current_stage
|
||||
from core.compat import XFormPrim
|
||||
from core.compat import is_prim_path_valid
|
||||
from core.compat import get_current_stage
|
||||
|
||||
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:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import RigidPrim
|
||||
from omni.isaac.core.utils.prims import create_prim, get_prim_at_path
|
||||
from core.compat import RigidPrim
|
||||
from core.compat import create_prim, get_prim_at_path
|
||||
|
||||
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:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -3,10 +3,10 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import GeometryPrim
|
||||
from core.compat import GeometryPrim
|
||||
|
||||
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:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ import os
|
||||
import random
|
||||
|
||||
from core.objects.base_object import register_object
|
||||
from omni.isaac.core.prims import XFormPrim
|
||||
from omni.isaac.core.utils.prims import create_prim, is_prim_path_valid
|
||||
from core.compat import XFormPrim
|
||||
from core.compat import create_prim, is_prim_path_valid
|
||||
|
||||
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:
|
||||
from isaacsim.core.api.materials import OmniPBR # Isaac Sim 4.5.0
|
||||
|
||||
|
||||
@@ -7,12 +7,9 @@ from copy import deepcopy
|
||||
|
||||
import numpy as np
|
||||
from core.robots.base_robot import register_robot
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.utils.prims import create_prim, get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import Robot
|
||||
from core.compat import create_prim, get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
from scipy.interpolate import interp1d
|
||||
|
||||
|
||||
|
||||
@@ -3,15 +3,11 @@ import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.interpolate_utils import linear_interpolation
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from solver.planner import KPAMPlanner
|
||||
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from solver.planner import KPAMPlanner
|
||||
|
||||
|
||||
@@ -4,15 +4,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig, OmegaConf
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -5,15 +5,11 @@ import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.usd_geom_utils import compute_bbox
|
||||
from omegaconf import DictConfig, OmegaConf
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from scipy.spatial.transform import Slerp
|
||||
|
||||
|
||||
@@ -12,14 +12,11 @@ from core.utils.plan_utils import (
|
||||
)
|
||||
from core.utils.transformation_utils import poses_from_tf_matrices
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
from omni.timeline import get_timeline_interface
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
@@ -5,15 +5,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -3,15 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -10,14 +10,11 @@ from core.utils.transformation_utils import (
|
||||
poses_from_tf_matrices,
|
||||
)
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from scipy.spatial.transform import Slerp
|
||||
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -1,13 +1,10 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import pose_from_tf_matrix, tf_matrix_from_pose
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -4,9 +4,9 @@ import torch
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.interpolate_utils import linear_interpolation
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -12,14 +12,11 @@ from core.utils.plan_utils import (
|
||||
)
|
||||
from core.utils.transformation_utils import poses_from_tf_matrices
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
|
||||
|
||||
@register_skill
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from solver.planner import KPAMPlanner
|
||||
|
||||
|
||||
@@ -11,14 +11,11 @@ from core.utils.plan_utils import (
|
||||
)
|
||||
from core.utils.transformation_utils import poses_from_tf_matrices
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
|
||||
|
||||
# pylint: disable=unused-argument
|
||||
|
||||
@@ -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.usd_geom_utils import compute_bbox
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -7,9 +7,9 @@ from core.utils.transformation_utils import (
|
||||
perturb_position,
|
||||
)
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -3,11 +3,11 @@ from copy import deepcopy
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig, OmegaConf
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
from solver.planner import KPAMPlanner
|
||||
|
||||
|
||||
@@ -3,15 +3,11 @@ import torch
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from core.utils.interpolate_utils import linear_interpolation
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -1,15 +1,11 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -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.usd_geom_utils import compute_bbox
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.objects.cylinder import VisualCylinder
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
tf_matrix_from_pose,
|
||||
)
|
||||
from core.compat import BaseController
|
||||
from core.compat import VisualCylinder
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, tf_matrix_from_pose
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
import numpy as np
|
||||
from core.skills.base_skill import BaseSkill, register_skill
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.controllers import BaseController
|
||||
from omni.isaac.core.robots.robot import Robot
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from core.compat import BaseController
|
||||
from core.compat import Robot
|
||||
from core.compat import BaseTask
|
||||
|
||||
|
||||
# pylint: disable=consider-using-generator,too-many-public-methods,unused-argument
|
||||
|
||||
@@ -18,16 +18,12 @@ from core.utils.scene_utils import deactivate_selected_prims
|
||||
from core.utils.transformation_utils import get_orientation
|
||||
from core.utils.visual_distractor import set_distractors
|
||||
from omegaconf import DictConfig
|
||||
from omni.isaac.core.materials import PreviewSurface
|
||||
from omni.isaac.core.prims import RigidContactView, XFormPrim
|
||||
from omni.isaac.core.scenes.scene import Scene
|
||||
from omni.isaac.core.tasks import BaseTask
|
||||
from omni.isaac.core.utils.prims import (
|
||||
delete_prim,
|
||||
get_prim_at_path,
|
||||
is_prim_path_valid,
|
||||
)
|
||||
from omni.isaac.core.utils.stage import get_current_stage
|
||||
from core.compat import PreviewSurface
|
||||
from core.compat import RigidContactView, XFormPrim
|
||||
from core.compat import Scene
|
||||
from core.compat import BaseTask
|
||||
from core.compat import delete_prim, get_prim_at_path, is_prim_path_valid
|
||||
from core.compat import get_current_stage
|
||||
from omni.physx.scripts import particleUtils
|
||||
from pxr import Gf, PhysxSchema, Sdf, Usd, UsdGeom, UsdLux, UsdShade, Vt
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
import numpy as np
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import get_relative_transform
|
||||
from omni.isaac.sensor import Camera
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform
|
||||
from core.compat import Camera
|
||||
|
||||
|
||||
def _get_annotator(camera: Camera, annotator_name: str):
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
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
|
||||
|
||||
|
||||
|
||||
@@ -18,7 +18,7 @@ logging.getLogger("urllib3").setLevel(logging.WARNING)
|
||||
|
||||
|
||||
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":
|
||||
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):
|
||||
from omni.isaac.core.utils.semantics import add_update_semantics
|
||||
from core.compat import add_update_semantics
|
||||
|
||||
if prim.GetTypeName() == "Plane":
|
||||
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):
|
||||
from omni.isaac.core.utils.semantics import add_update_semantics
|
||||
from core.compat import add_update_semantics
|
||||
|
||||
if robot.GetTypeName() == "Mesh":
|
||||
prim_path = str(robot.GetPrimPath())
|
||||
|
||||
@@ -13,17 +13,9 @@ import solver.kpam.SE3_utils as SE3_utils
|
||||
import solver.kpam.term_spec as term_spec
|
||||
import yaml
|
||||
from colored import fg
|
||||
from omni.isaac.core.utils.prims import (
|
||||
create_prim,
|
||||
get_prim_at_path,
|
||||
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 core.compat import create_prim, get_prim_at_path, is_prim_path_valid
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix, tf_matrices_from_poses
|
||||
from core.compat import get_world_pose
|
||||
from pydrake.all import *
|
||||
from scipy.spatial.transform import Rotation as R
|
||||
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 gensim_testing_v2.tasks.close_microwave import CloseMicrowave
|
||||
from omni.isaac.core import World
|
||||
from omni.isaac.core.utils.types import ArticulationAction
|
||||
from core.compat import World
|
||||
from core.compat import ArticulationAction
|
||||
|
||||
# from solver.planner import KPAMPlanner
|
||||
|
||||
|
||||
@@ -83,7 +83,7 @@ if __name__ == "__main__":
|
||||
kit = SimulationApp()
|
||||
|
||||
import omni
|
||||
from omni.isaac.core.utils.extensions import enable_extension
|
||||
from core.compat import enable_extension
|
||||
|
||||
enable_extension("omni.kit.asset_converter")
|
||||
|
||||
|
||||
@@ -10,11 +10,8 @@ from datetime import datetime
|
||||
|
||||
import numpy as np
|
||||
import yaml
|
||||
from omni.isaac.core.utils.prims import get_prim_at_path
|
||||
from omni.isaac.core.utils.transformations import (
|
||||
get_relative_transform,
|
||||
pose_from_tf_matrix,
|
||||
)
|
||||
from core.compat import get_prim_at_path
|
||||
from core.compat import get_relative_transform, pose_from_tf_matrix
|
||||
from omni.physx import acquire_physx_interface
|
||||
from tqdm import tqdm
|
||||
from yaml import Loader
|
||||
@@ -73,7 +70,7 @@ class SimBoxDualWorkFlow(NimbusWorkFlow):
|
||||
|
||||
def reset(self, need_preload: bool = True):
|
||||
# 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")
|
||||
# Modify config
|
||||
|
||||
@@ -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
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user