Coding-isaacsim-控制-Franka和Carter机器人

摘要

在 Isaac Sim 仿真环境中添加 Franka 和 Carter 两个机器人,设置它们的初始位姿,然后进行 4 个循环的仿真,在不同的循环中控制机器人的移动和停止,并在特定循环中打印 Carter 机器人的关节位置。最后关闭仿真应用。

code

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
# Copyright (c) 2020-2024, NVIDIA CORPORATION. All rights reserved.
#
# NVIDIA CORPORATION and its licensors retain all intellectual property
# and proprietary rights in and to this software, related documentation
# and any modifications thereto. Any use, reproduction, disclosure or
# distribution of this software and related documentation without an express
# license agreement from NVIDIA CORPORATION is strictly prohibited.
# 导入SimulationApp类,用于启动Isaac Sim仿真应用
from isaacsim import SimulationApp
# 启动仿真应用,设置为非无头模式,即打开GUI界面
simulation_app = SimulationApp({"headless": False})
import sys

import carb
import numpy as np
# 导入World类,用于管理仿真世界
from isaacsim.core.api import World
# 导入Articulation类,用于处理可活动的关节物体
from isaacsim.core.prims import Articulation
# 导入一些实用函数,用于添加引用到场景、获取场景单位等
from isaacsim.core.utils.stage import add_reference_to_stage, get_stage_units
# 导入ArticulationAction类型,用于定义关节动作
from isaacsim.core.utils.types import ArticulationAction
# 导入设置相机视角的实用函数
from isaacsim.core.utils.viewports import set_camera_view
# 导入获取资产根路径的函数
from isaacsim.storage.native import get_assets_root_path

# 准备场景
# 获取Isaac Sim资产的根路径
assets_root_path = get_assets_root_path()
# 如果无法找到资产根路径,记录错误信息,关闭仿真应用并退出程序
if assets_root_path is None:
carb.log_error("Could not find Isaac Sim assets folder")
simulation_app.close()
sys.exit()

# 创建一个世界对象,设置场景单位为米
my_world = World(stage_units_in_meters=1.0)
# 向场景中添加默认的地面平面
my_world.scene.add_default_ground_plane()
# 设置相机视角,指定相机位置和目标位置
set_camera_view(
eye=[5.0, 0.0, 1.5], target=[0.00, 0.00, 1.00], camera_prim_path="/OmniverseKit_Persp"
)

# 添加Franka机器人到场景
# 构建Franka机器人的USD文件路径
asset_path = assets_root_path + "/Isaac/Robots/Franka/franka.usd"
# 将Franka机器人的USD文件引用添加到场景中,指定其在场景中的路径
add_reference_to_stage(usd_path=asset_path, prim_path="/World/Arm")
# 创建一个Franka机器人的关节物体对象
arm = Articulation(prim_paths_expr="/World/Arm", name="my_arm")

# 添加Carter机器人到场景
# 构建Carter机器人的USD文件路径
asset_path = assets_root_path + "/Isaac/Robots/NVIDIA/Carter/nova_carter/nova_carter.usd"
# 将Carter机器人的USD文件引用添加到场景中,指定其在场景中的路径
add_reference_to_stage(usd_path=asset_path, prim_path="/World/Car")
# 创建一个Carter机器人的关节物体对象
car = Articulation(prim_paths_expr="/World/Car", name="my_car")

# 设置Franka机器人和Carter机器人的初始位姿,避免在仿真开始前发生碰撞
# 设置Franka机器人的世界位置
arm.set_world_poses(positions=np.array([[0.0, 1.0, 0.0]]) / get_stage_units())
# 设置Carter机器人的世界位置
car.set_world_poses(positions=np.array([[0.0, -1.0, 0.0]]) / get_stage_units())

# 初始化世界
my_world.reset()

# 进行4个循环的仿真
for i in range(4):
# 打印当前循环次数
print("running cycle: ", i)
# 在第1次和第3次循环时,移动机器人
if i == 1 or i == 3:
print("moving")
# 移动Franka机器人,设置其关节位置
arm.set_joint_positions([[-1.5, 0.0, 0.0, -1.5, 0.0, 1.5, 0.5, 0.04, 0.04]])
# 移动Carter机器人,设置其关节速度
car.set_joint_velocities([[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0]])
# 在第2次循环时,停止机器人
if i == 2:
print("stopping")
# 重置Franka机器人的关节位置
arm.set_joint_positions([[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]])
# 停止Carter机器人,设置其关节速度为0
car.set_joint_velocities([[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]])

# 每个循环中进行100步的仿真
for j in range(100):
# 执行一步仿真,同时进行渲染和物理模拟
my_world.step(render=True)
# 在第3次循环时,打印Carter机器人的关节位置
if i == 3:
# 获取Carter机器人的关节位置
car_joint_positions = car.get_joint_positions()
print("car joint positions:", car_joint_positions)

# 关闭仿真应用
simulation_app.close()