Isaac Sim 4.0 support, Kinematics API doc, Windows support

This commit is contained in:
Balakumar Sundaralingam
2024-07-20 14:51:43 -07:00
parent 2ae381f328
commit 3690d28c54
83 changed files with 2818 additions and 497 deletions

View File

@@ -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(