Isaac Sim 4.0 support, Kinematics API doc, Windows support
This commit is contained in:
@@ -9,6 +9,12 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
@@ -10,6 +10,12 @@
|
||||
#
|
||||
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
|
||||
@@ -9,6 +9,12 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
@@ -9,6 +9,12 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
@@ -156,7 +162,6 @@ if __name__ == "__main__":
|
||||
tensor_args,
|
||||
collision_checker_type=CollisionCheckerType.MESH,
|
||||
collision_cache={"obb": n_obstacle_cuboids, "mesh": n_obstacle_mesh},
|
||||
velocity_scale=0.75,
|
||||
interpolation_dt=0.02,
|
||||
ee_link_name="right_gripper",
|
||||
)
|
||||
@@ -180,7 +185,11 @@ if __name__ == "__main__":
|
||||
cmd_plan = None
|
||||
articulation_controller = robot.get_articulation_controller()
|
||||
plan_config = MotionGenPlanConfig(
|
||||
enable_graph=False, enable_graph_attempt=4, max_attempts=2, enable_finetune_trajopt=True
|
||||
enable_graph=False,
|
||||
enable_graph_attempt=4,
|
||||
max_attempts=2,
|
||||
enable_finetune_trajopt=True,
|
||||
time_dilation_factor=0.5,
|
||||
)
|
||||
|
||||
plan_idx = 0
|
||||
|
||||
@@ -31,7 +31,7 @@ try:
|
||||
from omni.isaac.urdf import _urdf # isaacsim 2022.2
|
||||
except ImportError:
|
||||
# Third Party
|
||||
from omni.importer.urdf import _urdf # isaac sim 2023.1
|
||||
from omni.importer.urdf import _urdf # isaac sim 2023.1 or above
|
||||
|
||||
ISAAC_SIM_23 = True
|
||||
# Standard Library
|
||||
@@ -68,22 +68,23 @@ def add_robot_to_scene(
|
||||
robot_name: str = "robot",
|
||||
position: np.array = np.array([0, 0, 0]),
|
||||
):
|
||||
urdf_interface = _urdf.acquire_urdf_interface()
|
||||
|
||||
urdf_interface = _urdf.acquire_urdf_interface()
|
||||
# Set the settings in the import config
|
||||
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 = False
|
||||
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 = 20000
|
||||
import_config.default_position_drive_damping = 500
|
||||
import_config.default_drive_strength = 1047.19751
|
||||
import_config.default_position_drive_damping = 52.35988
|
||||
import_config.default_drive_type = _urdf.UrdfJointTargetType.JOINT_DRIVE_POSITION
|
||||
import_config.distance_scale = 1
|
||||
import_config.density = 0.0
|
||||
|
||||
asset_path = get_assets_path()
|
||||
if (
|
||||
"external_asset_path" in robot_config["kinematics"]
|
||||
@@ -115,18 +116,7 @@ def add_robot_to_scene(
|
||||
linkp = stage.GetPrimAtPath(robot_path)
|
||||
set_prim_transform(linkp, [position[0], position[1], position[2], 1, 0, 0, 0])
|
||||
|
||||
if False and ISAAC_SIM_23: # this doesn't work in isaac sim 2023.1.1
|
||||
robot_p.set_solver_velocity_iteration_count(0)
|
||||
robot_p.set_solver_position_iteration_count(44)
|
||||
|
||||
my_world._physics_context.set_solver_type("PGS")
|
||||
|
||||
if ISAAC_SIM_23: # fix to load robot correctly in isaac sim 2023.1.1
|
||||
linkp = stage.GetPrimAtPath(robot_path + "/" + base_link_name)
|
||||
mass = UsdPhysics.MassAPI(linkp)
|
||||
mass.GetMassAttr().Set(0)
|
||||
robot = my_world.scene.add(robot_p)
|
||||
# robot_path = robot.prim_path
|
||||
return robot, robot_path
|
||||
|
||||
|
||||
|
||||
@@ -9,6 +9,12 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
|
||||
@@ -9,6 +9,12 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
|
||||
@@ -10,6 +10,12 @@
|
||||
#
|
||||
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
@@ -238,6 +244,7 @@ def main():
|
||||
max_attempts=max_attempts,
|
||||
enable_finetune_trajopt=True,
|
||||
parallel_finetune=True,
|
||||
time_dilation_factor=0.5,
|
||||
)
|
||||
|
||||
usd_help.load_stage(my_world.stage)
|
||||
@@ -407,7 +414,7 @@ def main():
|
||||
cmd_idx = 0
|
||||
|
||||
else:
|
||||
carb.log_warn("Plan did not converge to a solution. No action is being taken.")
|
||||
carb.log_warn("Plan did not converge to a solution: " + str(result.status))
|
||||
target_pose = cube_position
|
||||
target_orientation = cube_orientation
|
||||
past_pose = cube_position
|
||||
|
||||
@@ -10,6 +10,12 @@
|
||||
#
|
||||
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
|
||||
@@ -11,10 +11,11 @@
|
||||
#
|
||||
|
||||
|
||||
# script running (ubuntu):
|
||||
#
|
||||
|
||||
############################################################
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
|
||||
# Third Party
|
||||
|
||||
@@ -11,10 +11,11 @@
|
||||
#
|
||||
|
||||
|
||||
# script running (ubuntu):
|
||||
#
|
||||
|
||||
############################################################
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
|
||||
# Third Party
|
||||
@@ -241,7 +242,7 @@ def main():
|
||||
|
||||
step_index = my_world.current_time_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)
|
||||
|
||||
@@ -9,6 +9,12 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
@@ -138,14 +144,11 @@ def main():
|
||||
tensor_args,
|
||||
collision_checker_type=CollisionCheckerType.MESH,
|
||||
use_cuda_graph=True,
|
||||
num_trajopt_seeds=12,
|
||||
num_graph_seeds=12,
|
||||
interpolation_dt=0.03,
|
||||
collision_cache={"obb": n_obstacle_cuboids, "mesh": n_obstacle_mesh},
|
||||
collision_activation_distance=0.025,
|
||||
acceleration_scale=1.0,
|
||||
fixed_iters_trajopt=True,
|
||||
trajopt_tsteps=40,
|
||||
maximum_trajectory_dt=0.5,
|
||||
)
|
||||
motion_gen = MotionGen(motion_gen_config)
|
||||
print("warming up...")
|
||||
@@ -157,6 +160,7 @@ def main():
|
||||
enable_graph=False,
|
||||
enable_graph_attempt=4,
|
||||
max_attempts=10,
|
||||
time_dilation_factor=0.5,
|
||||
)
|
||||
|
||||
usd_help.load_stage(my_world.stage)
|
||||
@@ -329,7 +333,7 @@ def main():
|
||||
cmd_idx = 0
|
||||
|
||||
else:
|
||||
carb.log_warn("Plan did not converge to a solution. No action is being taken.")
|
||||
carb.log_warn("Plan did not converge to a solution: " + str(result.status))
|
||||
target_pose = cube_position
|
||||
past_pose = cube_position
|
||||
if cmd_plan is not None:
|
||||
|
||||
@@ -9,6 +9,13 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
@@ -38,11 +45,24 @@ from curobo.util_file import get_world_configs_path, join_path, load_yaml
|
||||
from curobo.wrap.model.robot_world import RobotWorld, RobotWorldConfig
|
||||
|
||||
simulation_app.update()
|
||||
# Standard Library
|
||||
import argparse
|
||||
|
||||
# Third Party
|
||||
from omni.isaac.core import World
|
||||
from omni.isaac.core.materials import OmniPBR
|
||||
from omni.isaac.core.objects import cuboid, sphere
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
|
||||
parser.add_argument(
|
||||
"--show-window",
|
||||
action="store_true",
|
||||
help="When True, shows camera image in a CV window",
|
||||
default=False,
|
||||
)
|
||||
args = parser.parse_args()
|
||||
|
||||
|
||||
def draw_points(voxels):
|
||||
# Third Party
|
||||
@@ -216,20 +236,21 @@ if __name__ == "__main__":
|
||||
bounding = Cuboid("t", dims=[1, 1, 1], pose=[0, 0, 0, 1, 0, 0, 0])
|
||||
voxels = model.world_model.get_voxels_in_bounding_box(bounding, 0.025)
|
||||
# print(data_camera.depth_image)
|
||||
depth_image = data["raw_depth"]
|
||||
color_image = data["raw_rgb"]
|
||||
depth_colormap = cv2.applyColorMap(
|
||||
cv2.convertScaleAbs(depth_image, alpha=100), cv2.COLORMAP_VIRIDIS
|
||||
)
|
||||
images = np.hstack((color_image, depth_colormap))
|
||||
if args.show_window:
|
||||
depth_image = data["raw_depth"]
|
||||
color_image = data["raw_rgb"]
|
||||
depth_colormap = cv2.applyColorMap(
|
||||
cv2.convertScaleAbs(depth_image, alpha=100), cv2.COLORMAP_VIRIDIS
|
||||
)
|
||||
images = np.hstack((color_image, depth_colormap))
|
||||
|
||||
cv2.namedWindow("Align Example", cv2.WINDOW_NORMAL)
|
||||
cv2.imshow("Align Example", images)
|
||||
key = cv2.waitKey(1)
|
||||
# Press esc or 'q' to close the image window
|
||||
if key & 0xFF == ord("q") or key == 27:
|
||||
cv2.destroyAllWindows()
|
||||
break
|
||||
cv2.namedWindow("Align Example", cv2.WINDOW_NORMAL)
|
||||
cv2.imshow("Align Example", images)
|
||||
key = cv2.waitKey(1)
|
||||
# Press esc or 'q' to close the image window
|
||||
if key & 0xFF == ord("q") or key == 27:
|
||||
cv2.destroyAllWindows()
|
||||
break
|
||||
|
||||
draw_points(voxels)
|
||||
d, d_vec = model.get_collision_vector(x_sph)
|
||||
|
||||
@@ -9,6 +9,12 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
@@ -64,9 +70,17 @@ parser = argparse.ArgumentParser()
|
||||
|
||||
|
||||
parser.add_argument("--robot", type=str, default="franka.yml", help="robot configuration to load")
|
||||
|
||||
parser.add_argument(
|
||||
"--waypoints", action="store_true", help="When True, sets robot in static mode", default=False
|
||||
)
|
||||
parser.add_argument(
|
||||
"--show-window",
|
||||
action="store_true",
|
||||
help="When True, shows camera image in a CV window",
|
||||
default=False,
|
||||
)
|
||||
|
||||
parser.add_argument(
|
||||
"--use-debug-draw",
|
||||
action="store_true",
|
||||
@@ -330,7 +344,7 @@ if __name__ == "__main__":
|
||||
if cmd_step_idx == 0:
|
||||
draw_rollout_points(mpc.get_visual_rollouts(), clear=not args.use_debug_draw)
|
||||
|
||||
if step_index < 2:
|
||||
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)
|
||||
@@ -374,7 +388,7 @@ if __name__ == "__main__":
|
||||
if not args.use_debug_draw:
|
||||
voxel_viewer.clear()
|
||||
|
||||
if True:
|
||||
if args.show_window:
|
||||
depth_image = data["raw_depth"]
|
||||
color_image = data["raw_rgb"]
|
||||
depth_colormap = cv2.applyColorMap(
|
||||
@@ -384,7 +398,6 @@ if __name__ == "__main__":
|
||||
depth_colormap = cv2.flip(depth_colormap, 1)
|
||||
|
||||
images = np.hstack((color_image, depth_colormap))
|
||||
|
||||
cv2.namedWindow("NVBLOX Example", cv2.WINDOW_NORMAL)
|
||||
cv2.imshow("NVBLOX Example", images)
|
||||
key = cv2.waitKey(1)
|
||||
|
||||
@@ -9,6 +9,12 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
@@ -60,6 +66,12 @@ from curobo.util.usd_helper import UsdHelper
|
||||
|
||||
parser = argparse.ArgumentParser()
|
||||
|
||||
parser.add_argument(
|
||||
"--show-window",
|
||||
action="store_true",
|
||||
help="When True, shows camera image in a CV window",
|
||||
default=False,
|
||||
)
|
||||
|
||||
parser.add_argument("--robot", type=str, default="franka.yml", help="robot configuration to load")
|
||||
parser.add_argument(
|
||||
@@ -316,7 +328,7 @@ if __name__ == "__main__":
|
||||
voxel_viewer.clear()
|
||||
# draw_points(voxels)
|
||||
|
||||
if True:
|
||||
if args.show_window:
|
||||
depth_image = data["raw_depth"]
|
||||
color_image = data["raw_rgb"]
|
||||
depth_colormap = cv2.applyColorMap(
|
||||
|
||||
@@ -9,6 +9,14 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
@@ -154,7 +162,6 @@ class CuroboController(BaseController):
|
||||
collision_cache={"obb": n_obstacle_cuboids, "mesh": n_obstacle_mesh},
|
||||
store_ik_debug=self._save_log,
|
||||
store_trajopt_debug=self._save_log,
|
||||
velocity_scale=0.75,
|
||||
)
|
||||
self.motion_gen = MotionGen(motion_gen_config)
|
||||
print("warming up...")
|
||||
@@ -173,6 +180,7 @@ class CuroboController(BaseController):
|
||||
partial_ik_opt=False,
|
||||
parallel_finetune=True,
|
||||
pose_cost_metric=pose_metric,
|
||||
time_dilation_factor=0.75,
|
||||
)
|
||||
self.usd_help.load_stage(self.my_world.stage)
|
||||
self.cmd_plan = None
|
||||
@@ -455,7 +463,7 @@ print(articulation_controller.get_gains())
|
||||
print(articulation_controller.get_max_efforts())
|
||||
robot = my_franka
|
||||
print("**********************")
|
||||
if True:
|
||||
if False:
|
||||
robot.enable_gravity()
|
||||
articulation_controller.set_gains(
|
||||
kps=np.array(
|
||||
|
||||
@@ -9,6 +9,13 @@
|
||||
# its affiliates is strictly prohibited.
|
||||
#
|
||||
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
|
||||
@@ -12,6 +12,13 @@
|
||||
# This script downloads robot usd assets from isaac sim for using in CuRobo.
|
||||
|
||||
|
||||
try:
|
||||
# Third Party
|
||||
import isaacsim
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
|
||||
# Third Party
|
||||
import torch
|
||||
|
||||
|
||||
@@ -55,12 +55,6 @@ def demo_full_config_mpc():
|
||||
mpc_config = MpcSolverConfig.load_from_robot_config(
|
||||
robot_cfg,
|
||||
world_file,
|
||||
use_cuda_graph=True,
|
||||
use_cuda_graph_metrics=True,
|
||||
use_cuda_graph_full_step=False,
|
||||
use_lbfgs=False,
|
||||
use_es=False,
|
||||
use_mppi=True,
|
||||
store_rollouts=True,
|
||||
step_dt=0.03,
|
||||
)
|
||||
|
||||
Reference in New Issue
Block a user