release repository
This commit is contained in:
172
examples/isaac_sim/util/convert_urdf_to_usd.py
Normal file
172
examples/isaac_sim/util/convert_urdf_to_usd.py
Normal file
@@ -0,0 +1,172 @@
|
||||
#
|
||||
# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
|
||||
#
|
||||
# NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
|
||||
# property and proprietary rights in and to this material, related
|
||||
# documentation and any modifications thereto. Any use, reproduction,
|
||||
# disclosure or distribution of this material and related documentation
|
||||
# without an express license agreement from NVIDIA CORPORATION or
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
a = torch.zeros(4, device="cuda:0")
|
||||
|
||||
# Standard Library
|
||||
import argparse
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
parser.add_argument(
|
||||
"--robot",
|
||||
type=str,
|
||||
default="franka.yml",
|
||||
help="Robot configuration to download",
|
||||
)
|
||||
parser.add_argument("--save_usd", default=False, action="store_true")
|
||||
args = parser.parse_args()
|
||||
|
||||
# Third Party
|
||||
from omni.isaac.kit import SimulationApp
|
||||
|
||||
simulation_app = SimulationApp({"headless": args.save_usd})
|
||||
|
||||
# Third Party
|
||||
import omni.usd
|
||||
from omni.isaac.core import World
|
||||
from omni.isaac.core.robots import Robot
|
||||
from omni.isaac.core.utils.types import ArticulationAction
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
from omni.isaac.urdf import _urdf # isaacsim 2022.2
|
||||
except ImportError:
|
||||
from omni.importer.urdf import _urdf # isaac sim 2023.1
|
||||
|
||||
# CuRobo
|
||||
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,
|
||||
join_path,
|
||||
load_yaml,
|
||||
)
|
||||
|
||||
|
||||
def save_usd():
|
||||
my_world = World(stage_units_in_meters=1.0)
|
||||
|
||||
import_config = _urdf.ImportConfig()
|
||||
import_config.merge_fixed_joints = False
|
||||
import_config.convex_decomp = False
|
||||
import_config.import_inertia_tensor = True
|
||||
import_config.fix_base = True
|
||||
import_config.make_default_prim = True
|
||||
import_config.self_collision = False
|
||||
import_config.create_physics_scene = True
|
||||
import_config.import_inertia_tensor = False
|
||||
import_config.default_drive_strength = 10000
|
||||
import_config.default_position_drive_damping = 100
|
||||
import_config.default_drive_type = _urdf.UrdfJointTargetType.JOINT_DRIVE_POSITION
|
||||
import_config.distance_scale = 1
|
||||
import_config.density = 0.0
|
||||
# Get the urdf file path
|
||||
robot_config = load_yaml(join_path(get_robot_configs_path(), args.robot))
|
||||
urdf_path = join_path(get_assets_path(), robot_config["robot_cfg"]["kinematics"]["urdf_path"])
|
||||
asset_path = join_path(
|
||||
get_assets_path(), robot_config["robot_cfg"]["kinematics"]["asset_root_path"]
|
||||
)
|
||||
urdf_interface = _urdf.acquire_urdf_interface()
|
||||
full_path = join_path(get_assets_path(), robot_config["robot_cfg"]["kinematics"]["urdf_path"])
|
||||
default_config = robot_config["robot_cfg"]["kinematics"]["cspace"]["retract_config"]
|
||||
j_names = robot_config["robot_cfg"]["kinematics"]["cspace"]["joint_names"]
|
||||
|
||||
robot_path = get_path_of_dir(full_path)
|
||||
filename = get_filename(full_path)
|
||||
imported_robot = urdf_interface.parse_urdf(robot_path, filename, import_config)
|
||||
robot_path = urdf_interface.import_robot(
|
||||
robot_path, filename, imported_robot, import_config, ""
|
||||
)
|
||||
robot = my_world.scene.add(Robot(prim_path=robot_path, name="robot"))
|
||||
# robot.disable_gravity()
|
||||
i = 0
|
||||
|
||||
my_world.reset()
|
||||
|
||||
usd_help = UsdHelper()
|
||||
usd_help.load_stage(my_world.stage)
|
||||
save_path = join_path(get_assets_path(), robot_config["robot_cfg"]["kinematics"]["usd_path"])
|
||||
usd_help.write_stage_to_file(save_path, True)
|
||||
print("Wrote usd file to " + save_path)
|
||||
simulation_app.close()
|
||||
|
||||
|
||||
def debug_usd():
|
||||
my_world = World(stage_units_in_meters=1.0)
|
||||
|
||||
import_config = _urdf.ImportConfig()
|
||||
import_config.merge_fixed_joints = False
|
||||
import_config.convex_decomp = False
|
||||
import_config.import_inertia_tensor = True
|
||||
import_config.fix_base = True
|
||||
import_config.make_default_prim = True
|
||||
import_config.self_collision = False
|
||||
import_config.create_physics_scene = True
|
||||
import_config.import_inertia_tensor = False
|
||||
import_config.default_drive_strength = 10000
|
||||
import_config.default_position_drive_damping = 100
|
||||
import_config.default_drive_type = _urdf.UrdfJointTargetType.JOINT_DRIVE_POSITION
|
||||
import_config.distance_scale = 1
|
||||
import_config.density = 0.0
|
||||
# Get the urdf file path
|
||||
robot_config = load_yaml(join_path(get_robot_configs_path(), args.robot))
|
||||
urdf_path = join_path(get_assets_path(), robot_config["robot_cfg"]["kinematics"]["urdf_path"])
|
||||
asset_path = join_path(
|
||||
get_assets_path(), robot_config["robot_cfg"]["kinematics"]["asset_root_path"]
|
||||
)
|
||||
urdf_interface = _urdf.acquire_urdf_interface()
|
||||
full_path = join_path(get_assets_path(), robot_config["robot_cfg"]["kinematics"]["urdf_path"])
|
||||
default_config = robot_config["robot_cfg"]["kinematics"]["cspace"]["retract_config"]
|
||||
j_names = robot_config["robot_cfg"]["kinematics"]["cspace"]["joint_names"]
|
||||
|
||||
robot_path = get_path_of_dir(full_path)
|
||||
filename = get_filename(full_path)
|
||||
imported_robot = urdf_interface.parse_urdf(robot_path, filename, import_config)
|
||||
robot_path = urdf_interface.import_robot(
|
||||
robot_path, filename, imported_robot, import_config, ""
|
||||
)
|
||||
robot = my_world.scene.add(Robot(prim_path=robot_path, name="robot"))
|
||||
# robot.disable_gravity()
|
||||
i = 0
|
||||
|
||||
articulation_controller = robot.get_articulation_controller()
|
||||
my_world.reset()
|
||||
|
||||
while simulation_app.is_running():
|
||||
my_world.step(render=True)
|
||||
if i == 0:
|
||||
idx_list = [robot.get_dof_index(x) for x in j_names]
|
||||
robot.set_joint_positions(default_config, idx_list)
|
||||
i += 1
|
||||
# if dof_n is not None:
|
||||
# dof_i = [robot.get_dof_index(x) for x in j_names]
|
||||
#
|
||||
# robot.set_joint_positions(default_config, dof_i)
|
||||
if robot.is_valid():
|
||||
art_action = ArticulationAction(default_config, joint_indices=idx_list)
|
||||
articulation_controller.apply_action(art_action)
|
||||
usd_help = UsdHelper()
|
||||
usd_help.load_stage(my_world.stage)
|
||||
save_path = join_path(get_assets_path(), robot_config["robot_cfg"]["kinematics"]["usd_path"])
|
||||
usd_help.write_stage_to_file(save_path, True)
|
||||
simulation_app.close()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
if args.save_usd:
|
||||
save_usd()
|
||||
else:
|
||||
debug_usd()
|
||||
69
examples/isaac_sim/util/dowload_assets.py
Normal file
69
examples/isaac_sim/util/dowload_assets.py
Normal file
@@ -0,0 +1,69 @@
|
||||
#
|
||||
# Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
|
||||
#
|
||||
# NVIDIA CORPORATION, its affiliates and licensors retain all intellectual
|
||||
# property and proprietary rights in and to this material, related
|
||||
# documentation and any modifications thereto. Any use, reproduction,
|
||||
# disclosure or distribution of this material and related documentation
|
||||
# without an express license agreement from NVIDIA CORPORATION or
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
# This script downloads robot usd assets from isaac sim for using in CuRobo.
|
||||
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
a = torch.zeros(4, device="cuda:0")
|
||||
|
||||
# Third Party
|
||||
from omni.isaac.kit import SimulationApp
|
||||
|
||||
simulation_app = SimulationApp({"headless": True})
|
||||
# Third Party
|
||||
from omni.isaac.core import World
|
||||
from omni.isaac.core.robots import Robot
|
||||
from omni.isaac.core.utils.nucleus import get_assets_root_path as nucleus_path
|
||||
from omni.isaac.core.utils.stage import add_reference_to_stage
|
||||
|
||||
# CuRobo
|
||||
from curobo.util.usd_helper import UsdHelper
|
||||
from curobo.util_file import get_assets_path, get_robot_configs_path, join_path, load_yaml
|
||||
|
||||
# supported robots:
|
||||
robots = ["franka.yml", "ur10.yml"]
|
||||
# Standard Library
|
||||
import argparse
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
parser.add_argument(
|
||||
"--robot",
|
||||
type=str,
|
||||
default="franka.yml",
|
||||
help="Robot configuration to download",
|
||||
)
|
||||
args = parser.parse_args()
|
||||
|
||||
if __name__ == "__main__":
|
||||
r = args.robot
|
||||
my_world = World(stage_units_in_meters=1.0)
|
||||
robot_config = load_yaml(join_path(get_robot_configs_path(), r))
|
||||
usd_path = nucleus_path() + robot_config["robot_cfg"]["kinematics"]["isaac_usd_path"]
|
||||
|
||||
usd_help = UsdHelper()
|
||||
robot_name = r
|
||||
prim_path = robot_config["robot_cfg"]["kinematics"]["usd_robot_root"]
|
||||
add_reference_to_stage(usd_path=usd_path, prim_path=prim_path)
|
||||
robot = my_world.scene.add(Robot(prim_path=prim_path, name=robot_name))
|
||||
usd_help.load_stage(my_world.stage)
|
||||
|
||||
my_world.reset()
|
||||
articulation_controller = robot.get_articulation_controller()
|
||||
|
||||
# create a new stage and add robot to usd path:
|
||||
save_path = join_path(get_assets_path(), robot_config["robot_cfg"]["kinematics"]["usd_path"])
|
||||
usd_help.write_stage_to_file(save_path, True)
|
||||
my_world.clear()
|
||||
my_world.clear_instance()
|
||||
simulation_app.close()
|
||||
Reference in New Issue
Block a user