

Isaac Sim 一百讲(8):Robot
从零开始的 Isaac Sim 之路,第一季开始!
前言#
在之前的介绍中,我们已经讲解了如何去使用相机来采集画面,那么在此之后,其实距离完整的使用 Isaac Sim 就只差了几个基本的环节,主要还是聚焦在如何使用 Isaac Sim 来搭建一个简单的机器人模型,并且让它动起来。我们在这一章中会介绍一下 Isaac Sim 中的机器人系统,以及一些基本的使用方法。
事实上,在本个章节结束之后,Isaac 101的全部内容也就将到此结束了。可以想象的是,读者可以复用之前的章节中使用资产,并且添加物理的方式来搭建一个室内操作场景。在这一环节中,其实难点往往在于需要寻找合适的资产。并且在此之后,可以在场景中添加机器人,并且使用一些方式来获取抓取位姿,如本章节后续介绍的使用 AnyGrasp 的方式,利用本章节中介绍的运动控制方法,以及机器人相应的函数来去控制机器人,并且使用上一章节中相机的调用方式来去获得视觉数据,即可完成对于 Isaac Sim 数据采集或者评测所需要的绝大多数函数的使用。
本章节的内容会比之前的要长一些,因为「让机器人动起来」这件事本身就是由好几个相对独立的环节拼起来的:怎么把机器人加载进场景、怎么直接控制关节、怎么用运动规划求解一条无碰撞的轨迹、怎么获取一个合理的抓取位姿。我们会依次介绍这几个部分,并且在运动规划环节中重点讲一下 cuRobo 的调用以及它和 Isaac Sim 的 Robot 是如何联动的。
机器人就是 Articulation#
在 Isaac Sim 中,机器人本质上就是一个 Articulation,也就是一组通过关节(Joint)连接起来的刚体(Rigid Body)。我们在之前的章节中已经讲过 Rigid 和 Joint 的概念,机器人无非就是把这些东西按照一个特定的拓扑结构组织起来,并且每一个可动的关节都带有一个 Drive,可以接受位置或者速度的控制指令。
Isaac Sim 提供了 omni.isaac.core.robots.robot.Robot 这个类来对 Articulation 进行上层封装,它本质上是 Articulation 的一个子类,提供了诸如 get_joint_positions()、set_joint_positions()、apply_action() 等方法。一般来说我们会直接把一个机器人的 USD 加载进来,然后用 Robot 类去包裹对应的 prim:
from omni.isaac.core.robots.robot import Robot
from omni.isaac.core.utils.prims import create_prim
# 把机器人 USD 加载到指定的 prim path 下
create_prim(
prim_path="/World/robot",
prim_type="Xform",
usd_path="/path/to/your/robot.usd",
)
robot = Robot(prim_path="/World/robot", name="my_robot")
# 一些求解器相关的参数,影响物理仿真的稳定性
robot.set_solver_position_iteration_count(124)
robot.set_solver_velocity_iteration_count(4)
robot.set_stabilization_threshold(0.005)
# 设置机器人在世界中的位置和姿态
robot.set_world_pose(position, orientation)python笔者有一些开源的 Huggingface 仓库里面包含了一些处理后的 Robot USD 资产,如 Franka RoboTiq,更多的机器人资产需要同时配置 cuRobo 的文件,不过 Franka 本身还是有一些自带的可以使用。
需要注意的是,Robot 对象在 World reset() 之前是不能直接读写关节状态的,因为此时底层的物理 View 还没有初始化。所以一般的流程是:先创建好所有 prim,把 robot 加入 world.scene,调用 world.reset(),然后再 robot.initialize()。
world.scene.add(robot)
world.reset()
robot.initialize()pythoninitialize() 之后,机器人就成功激活了,我们可以拿到它的自由度信息:
print(robot.dof_names) # 每个关节的名字,顺序很重要
print(robot.num_dof) # 总自由度数
print(robot.get_joint_positions()) # 当前每个关节的角度/位置python这里有一个非常关键、并且在后面运动规划环节会反复用到的点:dof_names 的顺序就是关节状态向量的顺序。Isaac Sim 内部的关节顺序是按照 USD 的拓扑解析出来的,它和你脑子里想的「关节 1 到关节 7」的顺序不一定一致,更不一定和 cuRobo 期望的顺序一致。后面我们会专门处理这个对齐问题。
直接控制机器人#
控制机器人最直接的方式有两种,分别对应直接设置和力控。
第一种是 set_joint_positions(),它会直接把关节设置到指定的位置,绕过物理引擎,相当于瞬移。这在初始化机器人姿态、或者重置场景的时候非常有用,但是它不符合物理,不应该在正常的控制循环中使用:
# 直接把 Franka 摆到一个默认的初始姿态(7 个臂关节 + 若干夹爪关节)
robot.set_joint_positions(
[0.0, -0.785, 0.0, -2.356, 0.0, 1.57079, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
)python值得一提的是,对于我们使用的 Franka RoboTiq 资产来说,其包含一个 RoboTiq 夹爪,包含了六个自由度,当然,实际上这个夹爪的不同自由度之间存在约束,如 Mimic Joint 等,因此实际上在控制一个 Joint 的时候其他的都会随之运动。
第二种才是符合物理的控制方式,即给关节的 Drive 设置目标,让物理引擎在每一步仿真中根据 stiffness 和 damping 把关节朝着目标驱动过去。在 Isaac Sim 中,这一般通过 ArticulationView 来做:
# robot_view 即 robot._articulation_view
robot_view = robot._articulation_view
# 给指定的关节设置位置目标,物理引擎会逐步驱动过去
robot_view.set_joint_position_targets(
target_joint_positions,
joint_indices=[0, 1, 2, 3, 4, 5, 6], # 只控制 7 个臂关节
)pythonjoint_indices 这个参数用来指定我们要控制哪些关节,这一点非常实用,因为一个机器人往往把「手臂」和「夹爪」放在同一个 Articulation 里,但是它们的控制逻辑是分开的:手臂用运动规划给出的轨迹来驱动,而夹爪只需要在「张开」和「闭合」两个状态之间切换。
以 Franka + Robotiq 夹爪为例,臂有 7 个自由度,夹爪有 6 个自由度(Robotiq 2F-85 是个多连杆的结构),我们可以这样定义张开和闭合:
arm_dof_num = 7
gripper_open = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
gripper_close = [0.7853, 0.7853, -0.7853, -0.7853, -0.7853, -0.7853]
# 把规划得到的臂部轨迹和夹爪状态拼成一个完整的 action
def make_action(arm_joints, grasp: bool):
return np.concatenate([
arm_joints[:arm_dof_num],
gripper_close if grasp else gripper_open,
])python值得一提的是,Robotiq 这种带 mimic 关节的夹爪在 Isaac Sim 里非常容易出问题,因为它的多个连杆之间是有约束关系的,如果 Drive 的 stiffness、damping、max force 设置得不合理,可能存在一些物理问题。一个比较 work 的做法是手动给这些关节设置较小的 stiffness 和 damping,并且把那些「被带动」的从动关节的 max force 直接设为 0,让它们完全由主动关节带动:
from genmanip.utils.usd_utils import (
set_drive_damping_and_stiffness,
set_drive_max_force,
)
# 主动关节:给一个比较软的驱动,通过调节 damping 和 stiffness 可以改变夹爪的闭合速度等
for joint in active_joints:
set_drive_damping_and_stiffness(joint_path, damping=0.01, stiffness=0.1)
set_drive_max_force(joint_path, 10000.0)
# 从动关节:max force 设为 0,纯粹被带动
for joint in passive_joints:
set_drive_max_force(joint_path, 0.0)python当然,另外一种则是只控制第一个 Joint 即可。
为什么需要运动规划#
现在我们已经能够控制每一个关节了,但是有一个很现实的问题,在实际的控制中,我们可以得到一些中间 Key Frame,但是往往也是笛卡尔空间的指令,而并非纯 Joint Position 的指令。
从笛卡尔空间的目标位姿(end-effector pose)反推出关节空间的角度,这就是 逆运动学(IK);而在此基础上,还要保证整条运动轨迹不会撞到桌子、不会撞到别的物体、不会自己撞自己,这就是 运动规划(Motion Planning)。这两件事都不简单,尤其是后者,是一个相当吃算力的优化问题。
我们这里使用的是 NVIDIA 的 cuRobo,它是一个完全跑在 GPU 上的运动规划库,把 IK、碰撞检测、轨迹优化全都用 CUDA 实现并且并行化,所以速度非常快,单条轨迹的规划往往在几十毫秒的量级。它和 Isaac Sim 同属 NVIDIA 全家桶,配合起来也比较自然。除此之外的常见运动库还包括 MPLib 以及 PyRoki
关于 cuRobo 的安装,这里就不展开了,直接参考官方文档即可,它支持从源码安装或者作为 Isaac Sim 的扩展安装。下面我们重点讲它的调用,以及如何和 Isaac Sim 的 Robot 联动。
cuRobo 的调用#
cuRobo 的核心对象有两个,MotionGen 负责完整的运动规划(给一个目标位姿,吐出一条无碰撞的关节轨迹),IKSolver 负责纯粹的逆运动学(给一个目标位姿,吐出一组关节角,不管轨迹)。我们一般会把它们封装在一个 Planner 类里统一管理。
首先是初始化。cuRobo 通过一份 robot config(描述机器人的运动学、碰撞球、关节限制等)和一份 world config(描述环境中的障碍物)来构建求解器:
from curobo.geom.sdf.world import CollisionCheckerType
from curobo.geom.types import WorldConfig
from curobo.types.base import TensorDeviceType
from curobo.types.math import Pose
from curobo.types.state import JointState
from curobo.util.usd_helper import UsdHelper
from curobo.wrap.reacher.ik_solver import IKSolver, IKSolverConfig
from curobo.wrap.reacher.motion_gen import (
MotionGen,
MotionGenConfig,
MotionGenPlanConfig,
)
from omni.isaac.core.utils.stage import get_current_stage
class CuroboPlanner:
def __init__(self, robot_cfg: dict, robot_prim_path: str) -> None:
self.robot_prim_path = robot_prim_path
self.robot_cfg = robot_cfg
self.tensor_args = TensorDeviceType()
# UsdHelper 是 cuRobo 与 Isaac Sim 之间的桥梁,
# 它可以直接读取当前的 USD Stage,把里面的物体转换成障碍物
self.usd_helper = UsdHelper()
self.usd_helper.load_stage(get_current_stage())
# 一开始世界里没有障碍物,后面用 update() 从场景里同步
self.world_cfg = WorldConfig()
# 运动规划的配置
self.plan_config = MotionGenPlanConfig(
enable_graph=False,
max_attempts=10,
enable_finetune_trajopt=True,
time_dilation_factor=1.0,
)
self.motion_gen_config = MotionGenConfig.load_from_robot_config(
self.robot_cfg,
self.world_cfg,
self.tensor_args,
interpolation_dt=0.01,
collision_checker_type=CollisionCheckerType.MESH,
collision_cache={"obb": 3000, "mesh": 3000},
use_cuda_graph=True,
self_collision_check=True,
num_trajopt_seeds=12,
num_graph_seeds=12,
optimize_dt=True,
)
self.motion_gen = MotionGen(self.motion_gen_config)
# warmup 会预先编译 CUDA graph,第一次规划会比较慢,之后就快了
self.motion_gen.warmup(warmup_js_trajopt=False)
# 单独的 IK 求解器
self.ik_config = IKSolverConfig.load_from_robot_config(
self.robot_cfg,
None,
rotation_threshold=0.05,
position_threshold=0.005,
num_seeds=128,
self_collision_check=True,
tensor_args=self.tensor_args,
use_cuda_graph=True,
)
self.ik_solver = IKSolver(self.ik_config)
# 关键:这个顺序需要和 cuRobo 内部的关节顺序对齐,后面会讲
self.ordered_js_names = []
self.dof_len = 7python这里 robot_cfg 是一份 YAML 配置,cuRobo 官方仓库里给了非常多常见机器人(Franka、UR5、xArm 等)的现成配置,直接拿来用即可。它描述了机器人的 URDF 路径、base link、end-effector link、碰撞球(cuRobo 用一堆球来近似机器人的碰撞体积,这样碰撞检测可以做得更快)、关节限制等等。
障碍物#
cuRobo 并不知道 Isaac Sim 场景里有什么东西,我们需要在每次规划之前,把当前 Stage 里的物体作为障碍物同步给它。UsdHelper 提供了直接从 Stage 抓取障碍物的能力:
def update(self, ignore_list: list[str] = []) -> None:
robot_name = self.robot_prim_path.split("/")[-1]
obstacles = self.usd_helper.get_obstacles_from_stage(
ignore_substring=[robot_name, "Camera"] + ignore_list,
reference_prim_path=self.robot_prim_path,
).get_collision_check_world()
self.motion_gen.update_world(obstacles)python这里有几个细节:第一,一定要把机器人自己排除掉,否则机器人会把自己的身体当成障碍物,导致规划永远失败;第二,相机这种没有实体的 prim 也要排掉;第三,被抓取的物体也通常要临时排掉,因为我们恰恰是要让夹爪靠近它。所以 ignore_list 里一般会动态地加上当前要抓取的物体和桌子。
关节顺序#
前面强调过,Isaac Sim 的 dof_names 顺序和 cuRobo 内部的关节顺序不一定一致。cuRobo 期望接收和返回的关节状态都是按照它自己的 ordered_js_names 来排列的,所以我们需要在两边之间做一次重排。cuRobo 的 JointState 提供了 get_ordered_joint_state() 来做这件事:
# 设置 cuRobo 期望的关节顺序(和 robot_cfg 里的 cspace 对应)
planner.ordered_js_names = [
"panda_joint1", "panda_joint2", "panda_joint3", "panda_joint4",
"panda_joint5", "panda_joint6", "panda_joint7",
]python在规划的时候,我们从 Isaac Sim 拿到当前的关节状态(顺序是 Isaac 的),构造成 cuRobo 的 JointState,然后用 get_ordered_joint_state() 重排成 cuRobo 的顺序;规划完成之后,再把结果按照 Isaac 的顺序重排回来,这样才能正确地喂给 set_joint_position_targets()。
规划一条轨迹#
把上面这些拼起来,一个完整的 plan 方法长这样:
def plan(
self,
ee_translation_goal: np.ndarray, # 目标位置 (3,),在机器人坐标系下
ee_orientation_goal: np.ndarray, # 目标姿态四元数 (4,),wxyz
sim_js, # Isaac 当前的关节状态
dof_names: list | None = None,
grasp: bool = False,
) -> list[np.ndarray] | None:
# 构造目标位姿
ik_goal = Pose(
position=self.tensor_args.to_device(ee_translation_goal),
quaternion=self.tensor_args.to_device(ee_orientation_goal),
)
# 把 Isaac 的关节状态搬到 GPU 上,构造成 cuRobo 的 JointState
cu_js = JointState(
position=self.tensor_args.to_device(sim_js.positions),
velocity=self.tensor_args.to_device(sim_js.velocities) * 0.0,
acceleration=self.tensor_args.to_device(sim_js.velocities) * 0.0,
jerk=self.tensor_args.to_device(sim_js.velocities) * 0.0,
joint_names=self.ordered_js_names if dof_names is None else dof_names,
)
# 按 cuRobo 期望的顺序重排
cu_js = cu_js.get_ordered_joint_state(self.ordered_js_names)
# plan_single 是核心,返回一个 result 对象
result = self.motion_gen.plan_single(
cu_js.unsqueeze(0), ik_goal, self.plan_config.clone()
)
if result.success is not None and result.success.item():
# 拿到插值后的稠密轨迹,再重排回 Isaac 的关节顺序
cmd_plan = result.get_interpolated_plan()
cmd_plan = cmd_plan.get_ordered_joint_state(self.raw_js_names)
position_list = []
for idx in range(len(cmd_plan.position)):
joint_positions = cmd_plan.position[idx].cpu().numpy()
position_list.append(joint_positions[: self.dof_len])
return position_list # 一连串关节角,就是轨迹上的每一个点
else:
return None # 规划失败(够不着 / 有碰撞 / 自碰撞)pythonplan_single 返回的 result 里 success 标志了规划是否成功,失败的原因可能是目标够不着、路径上有碰撞、或者会发生自碰撞。成功的话通过 get_interpolated_plan() 拿到一条插值过的稠密轨迹,它是一连串关节角,我们只需要在仿真循环里把这些关节角依次喂给机器人就行了。
IK 和 FK 也是类似的封装,单点求解,不涉及轨迹:
def ik_single(self, target_pose, cur_joint_positions):
seed_config = self.tensor_args.to_device(cur_joint_positions.reshape(1, 1, -1))
pose = Pose(
self.tensor_args.to_device(target_pose[:3]),
self.tensor_args.to_device(target_pose[3:]),
)
ik_result = self.ik_solver.solve_single(pose, seed_config=seed_config)
if not ik_result.success.item():
return None
return ik_result.js_solution.position.cpu().numpy().squeeze()python坐标系#
最后一个坑是坐标系。AnyGrasp 也好、我们自己指定的目标也好,给出来的位姿一般是在世界坐标系下的,但是 cuRobo 规划时用的是机器人 base link 坐标系。所以在调用 plan 之前,需要把目标位姿从世界系变换到机器人系。
变换的逻辑就是一次标准的位姿求逆再左乘,注意 Isaac Sim 的四元数约定是 wxyz,而 scipy 的 Rotation 用的是 xyzw,所以代码里到处都是 [[1, 2, 3, 0]] 这种重排索引:
from scipy.spatial.transform import Rotation as R
def transform_goal_to_robot_frame(robot, goal_pos, goal_quat_wxyz):
# 目标在世界系下的齐次变换矩阵
goal_matrix = np.eye(4)
goal_matrix[:3, :3] = R.from_quat(goal_quat_wxyz[[1, 2, 3, 0]]).as_matrix()
goal_matrix[:3, 3] = goal_pos
# 机器人在世界系下的齐次变换矩阵
robot_p, robot_q = robot.get_world_pose()
robot_matrix = np.eye(4)
robot_matrix[:3, :3] = R.from_quat(robot_q[[1, 2, 3, 0]]).as_matrix()
robot_matrix[:3, 3] = robot_p
# 把目标从世界系变换到机器人系
goal_in_robot = np.linalg.inv(robot_matrix) @ goal_matrix
pos = goal_in_robot[:3, 3]
quat_wxyz = R.from_matrix(goal_in_robot[:3, :3]).as_quat()[[3, 0, 1, 2]]
return pos, quat_wxyzpython把这三件事都对齐之后,cuRobo 和 Isaac Sim 就能正确地联动起来了。
执行轨迹#
规划完成之后,剩下的就是在仿真循环里执行这条轨迹。前面讲过,我们用 set_joint_position_targets() 来驱动手臂,并且每一步都要 step 一下让物理引擎推进:
# trajectory 是 plan() 返回的一连串关节角
for arm_joints in trajectory:
action = make_action(arm_joints, grasp=False) # 拼上夹爪状态
robot_view.set_joint_position_targets(
action, joint_indices=default_dof_indices
)
world.step(render=False) # 推进物理;需要画面时再单独 render()python这里又回到了上一章节中讨论过的 step 问题:在机械臂的 Drive 参数不那么完美的情况下,用 step(render=False) 推进物理、再单独 render() 出画面,会比直接 step() 更接近真实的物理表现。
用 AnyGrasp 获取抓取位姿#
到这里,「给定一个目标位姿,让机器人无碰撞地过去」这件事已经完全解决了。还剩最后一个问题,即如何获得目标位姿。对于绝大多数的数据生成来说,比如说对于 Articulation 的操作或者一些特定的任务,往往这就是设计的核心所在。不过对于抓取任务来说,这似乎已经被解决,即抓取位姿检测任务。
我们使用 AnyGrasp,它输入一帧 RGBD 数据以及相机内参,输出一组相机坐标系下带分数的候选抓取位姿。AnyGrasp 的 SDK 需要申请 license,并且对 Python 版本和 CUDA 版本有要求,安装部分参考 笔者之前的博客 即可。
最直接的用法是离线跑一帧数据,核心就是从深度图反投影出点云,喂给模型:
from gsnet import AnyGrasp
from graspnetAPI import GraspGroup
anygrasp = AnyGrasp(cfgs)
anygrasp.load_net()
# 从深度图反投影出点云
xmap, ymap = np.meshgrid(np.arange(W), np.arange(H))
points_z = depths / scale
points_x = (xmap - cx) / fx * points_z
points_y = (ymap - cy) / fy * points_z
points = np.stack([points_x, points_y, points_z], axis=-1)
mask = (points_z > 0) & (points_z < 1)
points = points[mask].astype(np.float32)
colors = colors[mask].astype(np.float32)
# 检测抓取,返回一个 GraspGroup
gg, cloud = anygrasp.get_grasp(
points, colors, apply_object_mask=True, collision_detection=True
)
gg = gg.nms().sort_by_score() # 非极大值抑制 + 按分数排序
best_grasp = gg[0] # 分数最高的抓取python用服务的方式调用#
在实际的数据采集流水线里,AnyGrasp 模型加载一次要占不少显存,而且我们往往需要并行跑很多个 Isaac Sim 实例,每个实例都自己加载一份模型既慢又浪费。所以更实用的做法是把 AnyGrasp 包成一个 HTTP 服务,模型常驻显存,Isaac 这边作为客户端按需请求。
服务端用 Flask 起一个进程,把模型加载好之后等着接收点云数据:
from flask import Flask, request, jsonify
app = Flask(__name__)
anygrasp = AnyGrasp(cfgs)
anygrasp.load_net() # 模型常驻
@app.route("/process", methods=["POST"])
def process_data():
data = request.get_json()
colors = np.array(data["colors"], dtype=np.uint8)
depths = np.array(data["depths"], dtype=np.uint16)
# ... 反投影 + get_grasp ...
gg = gg.nms().sort_by_score()
grasp_list = [{
"translation": g.translation.tolist(),
"rotation_matrix": g.rotation_matrix.tolist(),
"depth": g.depth,
"score": g.score,
} for g in gg]
return jsonify({"grasp_groups": grasp_list}), 200
app.run(host="0.0.0.0", port=5001)python客户端(也就是 Isaac Sim 这边)把相机拍到的 RGB 和深度发过去,拿回一组抓取位姿。这样我们甚至可以起一堆服务(不同端口、不同卡),让多个 Isaac 实例随机挑一个来请求,做到负载均衡:
import requests
def get_grasp_pose(colors, depth, fx, fy, cx, cy, address, port, scale=1000.0):
data = {
"colors": colors.tolist(),
"depths": (depth * scale).tolist(),
"fx": fx, "fy": fy, "cx": cx, "cy": cy,
"scale": scale, "dense_mode": True,
}
response = requests.post(f"http://{address}:{port}/process", json=data)
if response.status_code == 200:
return response.json()["grasp_groups"]
return Nonepython从相机系到世界系#
AnyGrasp 给出的抓取位姿是在相机坐标系下的,而我们前面规划用的是世界坐标系,所以又得做一次坐标变换。这里需要特别小心的是,AnyGrasp / GraspNet 的相机坐标系约定和 Isaac Sim 的相机坐标系约定是不一样的,中间需要插一个修正矩阵:
def get_world_grasp_from_camera_coords(
camera_position, camera_quaternion, point_3d, matrix_grasp
):
rotation_cam_to_world = R.from_quat(camera_quaternion[[1, 2, 3, 0]])
# 这两个矩阵用来对齐 GraspNet 和 Isaac 的相机坐标系约定
transform_custom_pose = np.array([[0, 0, 1], [0, -1, 0], [1, 0, 0]])
correction_matrix = np.array([[1, 0, 0], [0, 0, -1], [0, 1, 0]])
point_in_world = (
rotation_cam_to_world.as_matrix()
@ correction_matrix @ transform_custom_pose @ point_3d
+ camera_position
)
rotation_world = (
rotation_cam_to_world
* R.from_matrix(correction_matrix @ transform_custom_pose)
* R.from_matrix(matrix_grasp)
* R.from_matrix(np.linalg.inv(transform_custom_pose))
).as_quat()[[3, 0, 1, 2]]
return point_in_world, rotation_worldpython这一段的两个修正矩阵是纯粹的坐标系约定对齐,属于「不这么写就抓不准」的经验性代码,具体的数值取决于你的相机是怎么摆的、用的哪个版本的 GraspNet,照搬不一定对,需要自己用可视化验证一下抓取位姿是不是落在物体上。
一个抓取放置的完整流程#
把本章节的所有东西串起来,一个最简化的「抓起 A 放到 B 上」的流程大致是这样的:
# 1. 用相机拍一帧 RGBD
rgb = get_rgb(camera)
depth = get_depth(camera)
# 2. 请求 AnyGrasp,拿到世界系下的抓取位姿
grasps = request_anygrasp(camera, rgb, depth)
grasp = select_best_grasp(grasps, target_object) # 挑一个落在目标物体上的
# 3. 把当前场景同步给 cuRobo 作为障碍物
planner.update(ignore_list=[target_object_name, table_name])
# 4. 规划「抓取前的预备位姿 -> 抓取位姿」并执行
sim_js = robot.get_joints_state()
for goal in [pre_grasp_pose, grasp["pose"]]:
pos, quat = transform_goal_to_robot_frame(robot, goal["pos"], goal["quat"])
trajectory = planner.plan(pos, quat, sim_js, grasp=True)
execute_trajectory(robot_view, trajectory, world, grasp=False)
# 5. 闭合夹爪
close_gripper(robot_view, world)
# 6. 规划「抬起 -> 移动到 B 上方 -> 放下」并执行,过程中保持夹爪闭合
# ...(和上面对称)
# 7. 张开夹爪,完成
open_gripper(robot_view, world)python实际工程里的代码当然要复杂得多,笔者的仓库 GenManip 是一个比较成熟的实现,读者可以后续参考其中的实现。
小结#
在本章节中,我们介绍了 Isaac Sim 中机器人的本质(Articulation)、如何加载和直接控制机器人、为什么需要运动规划,以及如何用 cuRobo 进行运动规划并和 Isaac Sim 联动,最后还介绍了如何用 AnyGrasp 获取抓取位姿,并把整条流程串了起来。
到这里,Isaac 101 的全部内容就告一段落了。从安装、Prim、USD、变换、物理、碰撞、相机,一直到现在的机器人,读者应该已经具备了用 Isaac Sim 搭建一个完整的操作场景、并且采集数据或者进行评测所需要的全部基础知识。剩下的,就是去实践,去踩坑,去把这些零件拼成你自己想要的东西了。
现有的 Coding Agent 相较于一年前,已经具备了比较基础的 Isaac Sim 的开发功能(主要确实 Isaac Sim 的文档比较一般,开发难度高又导致可以用于训练的代码不多),你可以依靠他们,进一步迭代一个更好的 Isaac Sim 脚手架,并且用于 Evaluation 或者 Data Generation。
祝你开心。