add isaac sim 2023 support and dockerfiles
This commit is contained in:
@@ -17,25 +17,12 @@ a = torch.zeros(4, device="cuda:0")
|
||||
# Standard Library
|
||||
import argparse
|
||||
|
||||
# CuRobo
|
||||
from curobo.cuda_robot_model.cuda_robot_model import CudaRobotModel
|
||||
|
||||
# from curobo.wrap.reacher.ik_solver import IKSolver, IKSolverConfig
|
||||
from curobo.geom.sdf.world import CollisionCheckerType
|
||||
from curobo.geom.types import WorldConfig
|
||||
from curobo.rollout.rollout_base import Goal
|
||||
from curobo.types.base import TensorDeviceType
|
||||
from curobo.types.math import Pose
|
||||
from curobo.types.robot import JointState, RobotConfig
|
||||
from curobo.types.state import JointState
|
||||
from curobo.util_file import get_robot_configs_path, get_world_configs_path, join_path, load_yaml
|
||||
from curobo.wrap.reacher.ik_solver import IKSolver, IKSolverConfig
|
||||
from curobo.wrap.reacher.motion_gen import MotionGen, MotionGenConfig, MotionGenPlanConfig
|
||||
from curobo.wrap.reacher.mpc import MpcSolver, MpcSolverConfig
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
parser.add_argument(
|
||||
"--headless", action="store_true", help="When True, enables headless mode", default=False
|
||||
"--headless_mode",
|
||||
type=str,
|
||||
default=None,
|
||||
help="To run headless, use one of [native, websocket], webrtc might not work.",
|
||||
)
|
||||
parser.add_argument(
|
||||
"--visualize_spheres",
|
||||
@@ -54,52 +41,49 @@ from omni.isaac.kit import SimulationApp
|
||||
|
||||
simulation_app = SimulationApp(
|
||||
{
|
||||
"headless": args.headless,
|
||||
"headless": args.headless_mode is not None,
|
||||
"width": "1920",
|
||||
"height": "1080",
|
||||
}
|
||||
)
|
||||
# Third Party
|
||||
from omni.isaac.core.utils.extensions import enable_extension
|
||||
|
||||
# CuRobo
|
||||
from curobo.util_file import (
|
||||
get_assets_path,
|
||||
get_filename,
|
||||
get_path_of_dir,
|
||||
get_robot_configs_path,
|
||||
join_path,
|
||||
load_yaml,
|
||||
)
|
||||
|
||||
ext_list = [
|
||||
"omni.kit.asset_converter",
|
||||
# "omni.kit.livestream.native",
|
||||
"omni.kit.tool.asset_importer",
|
||||
"omni.isaac.asset_browser",
|
||||
"omni.isaac.urdf",
|
||||
]
|
||||
[enable_extension(x) for x in ext_list]
|
||||
simulation_app.update()
|
||||
|
||||
# Standard Library
|
||||
from typing import Dict
|
||||
|
||||
# Third Party
|
||||
import carb
|
||||
import numpy as np
|
||||
from helper import add_robot_to_scene
|
||||
from helper import add_extensions, add_robot_to_scene
|
||||
from omni.isaac.core import World
|
||||
from omni.isaac.core.objects import cuboid, sphere
|
||||
from omni.isaac.core.robots import Robot
|
||||
|
||||
########### OV #################
|
||||
from omni.isaac.core.utils.extensions import enable_extension
|
||||
from omni.isaac.core.utils.types import ArticulationAction
|
||||
|
||||
# CuRobo
|
||||
from curobo.cuda_robot_model.cuda_robot_model import CudaRobotModel
|
||||
|
||||
# from curobo.wrap.reacher.ik_solver import IKSolver, IKSolverConfig
|
||||
from curobo.geom.sdf.world import CollisionCheckerType
|
||||
from curobo.geom.types import WorldConfig
|
||||
from curobo.rollout.rollout_base import Goal
|
||||
from curobo.types.base import TensorDeviceType
|
||||
from curobo.types.math import Pose
|
||||
from curobo.types.robot import JointState, RobotConfig
|
||||
from curobo.types.state import JointState
|
||||
from curobo.util.logger import setup_curobo_logger
|
||||
from curobo.util.usd_helper import UsdHelper
|
||||
from curobo.util_file import (
|
||||
get_assets_path,
|
||||
get_filename,
|
||||
get_path_of_dir,
|
||||
get_robot_configs_path,
|
||||
get_world_configs_path,
|
||||
join_path,
|
||||
load_yaml,
|
||||
)
|
||||
from curobo.wrap.reacher.ik_solver import IKSolver, IKSolverConfig
|
||||
from curobo.wrap.reacher.motion_gen import MotionGen, MotionGenConfig, MotionGenPlanConfig
|
||||
from curobo.wrap.reacher.mpc import MpcSolver, MpcSolverConfig
|
||||
|
||||
########### OV #################
|
||||
|
||||
|
||||
############################################################
|
||||
|
||||
@@ -225,6 +209,7 @@ def main():
|
||||
result = ik_solver.solve_batch(goal_pose)
|
||||
|
||||
print("Curobo is Ready")
|
||||
add_extensions(simulation_app, args.headless_mode)
|
||||
|
||||
usd_help.load_stage(my_world.stage)
|
||||
usd_help.add_world_to_stage(world_cfg, base_frame="/World")
|
||||
@@ -246,7 +231,7 @@ def main():
|
||||
|
||||
step_index = my_world.current_time_step_index
|
||||
# print(step_index)
|
||||
if step_index == 0:
|
||||
if step_index <= 2:
|
||||
my_world.reset()
|
||||
idx_list = [robot.get_dof_index(x) for x in j_names]
|
||||
robot.set_joint_positions(default_config, idx_list)
|
||||
|
||||
Reference in New Issue
Block a user