5 脚本化开发¶

Isaac Sim除了提供OmniGraph低代码开发方式,也提供了Python API进行脚本化开发机器人任务场景。本节内容将结合实际案例,介绍Isaac Sim提供的常用Python API及相关开发方法。

注:本课程提供的Isaac Sim容器已包含Isaac Sim的Python开发环境,你需要通过VsCode / Cursor连接至Isaac Sim容器方可进行开发,具体连接方法见“01_Isaac Sim仿真平台介绍及容器化安装”的1.2.5部分。以下部分将以已通过VsCode / Cursor连接至Isaac Sim容器的前提下进行介绍。

5.1 环境前置准备¶

通过VsCode / Cursor连接至Isaac Sim容器后,Isaac Sim容器已预置VsCode / Cursor的工作区配置(例如Python解释器路径)。但连接后,VsCode / Cursor默认未安装Python扩展,需要安装Python扩展方可解释脚本内Python API。以下是安装Python扩展开发步骤。

  1. 打开左侧导航栏,点击扩展入口(如图步骤 1)

  2. 在扩展页面搜索"Python"(如图步骤 2)

  3. 点击在容器内安装Python扩展(如图步骤 3)

安装Python 扩展

VsCode / Cursor安装Python扩展后,可参考以下步骤设置Python解释器,开发时可通过"Ctrl + 鼠标左键)查看相关API,无需翻看Isaac Sim API文档。

5.2 相关概念介绍¶

5.2.1 脚本化方式¶

在Isaac Sim中,Python脚本化开发可以通过两种方式实现:Extension(扩展)和Standalone(独立脚本)。

  • Extension(扩展):集成于Isaac Sim图形化界面内,一般用于测试Isaac Sim的API或搭建简单场景,需要依赖"runheadless.sh"脚本启动Isaac Sim且打开相关扩展方可验证脚本内容。

  • Standalone(独立脚本):此类脚本通常包含Isaac Sim应用程序启动、任务逻辑实现、仿真终止条件设置等内容,一般用于复杂任务场景,无需依赖"runheadless.sh"进行启动Isaac Sim。

以下分别为Extension(扩展)、Standalone(独立脚本)示例代码,可直观感受这两者主要的区别(全流程及核心流程)。

Extension(扩展)示例代码:

from isaacsim.examples.interactive.base_sample import BaseSample

# Note: checkout the required tutorials at https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/overview.html


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):

        world = self.get_world()
        world.scene.add_default_ground_plane()
        return

    async def setup_post_load(self):
        return

    async def setup_pre_reset(self):
        return

    async def setup_post_reset(self):
        return

    def world_cleanup(self):
        return

5.2.1.1 Extension 脚本主要代码解析¶

由于 Extension(扩展) 方式集成并依赖于 Isaac Sim 的图形化界面,因此为了能够在仿真过程中使用图形化界面的按键对扩展脚本程序进行控制,我们需要在使用:

  • BaseSample: 该对象预定义了扩展仿真脚本的关键生命周期方法,确保代码在正确的阶段执行,相当于扩展仿真脚本的脚手架
  • setup_scene: 该函数为父对象 BaseSample 的预定义函数,该函数决定了,当我们按下load后进行场景加载前的环境配置(如光照、地面、场景和资产的加载与初始化)
  • setup_post_load: 该函数同样为父函数 BaseSample 的预定义函数,该函数决定了,当我们按下load后进行场景加载时的具体操作(如绑定机器人的控制器等操作)
  • setup_pre_reset: 该函数同样为父函数 BaseSample 的预定义函数,该函数决定了,当我们按下Reset后场景的初始化前操作
  • setup_post_reset: 该函数同样为父函数 BaseSample 的预定义函数,该函数决定了,当我们按下Reset后场景的初始化时具体操作

Standalone(独立脚本)示例代码:

import numpy as np
from isaacsim import SimulationApp

simulation_app = SimulationApp({"headless": False})

from isaacsim.core.api import World
from isaacsim.core.api.objects import DynamicCuboid, VisualCuboid

my_world = World(stage_units_in_meters=1.0)

cube_1 = my_world.scene.add(
    VisualCuboid(
        prim_path="/new_cube_1",
        name="visual_cube",
        position=np.array([0, 0, 0.5]),
        size=0.3,
        color=np.array([255, 255, 255]),
    )
)

cube_2 = my_world.scene.add(
    DynamicCuboid(
        prim_path="/new_cube_2",
        name="cube_1",
        position=np.array([0, 0, 1.0]),
        scale=np.array([0.6, 0.5, 0.2]),
        size=1.0,
        color=np.array([255, 0, 0]),
    )
)

cube_3 = my_world.scene.add(
    DynamicCuboid(
        prim_path="/new_cube_3",
        name="cube_2",
        position=np.array([0, 0, 3.0]),
        scale=np.array([0.1, 0.1, 0.1]),
        size=1.0,
        color=np.array([0, 0, 255]),
        linear_velocity=np.array([0, 0, 0.4]),
    )
)

my_world.scene.add_default_ground_plane()

for i in range(5):
    my_world.reset()
    for i in range(500):
        my_world.step(render=True)
        print(cube_2.get_angular_velocity())
        print(cube_2.get_world_pose())

simulation_app.close()

5.3.1.2 Standalone 独立脚本主题代码解析¶

5.2.2 仿真概念及API关系阐述¶

在Isaac Sim脚本化开发中,定义场景、任务时会涉及六个仿真概念,分别为Prim(基本元素)、Stage(舞台)、Scene(场景)、World(世界)、Simulation(仿真)、Application(应用)。这些概念共同构成了仿真的层次化结构,理解它们的关系对于高效开发至关重要。

其中,Prim(基本元素)和Stage(舞台)是属于USD文件里的定义,多个Prim可组合为一个Stage,Stage可在仿真里抽象为某个物体,例如:一台四轮小车会包含四个轮子、车身,其中轮子、车身属于Prim,将这些Prim组合到有一个Stage,在仿真场景中这个Stage就是一台四轮小车。

另外,Scene(场景)、World(世界)、Simulation(仿真)这三个概念分别对应"02_Isaac Sim图形化界面及常见工作流介绍"章节提及到的仿真十要素中的物理引擎、环境、物理场景。

以下是这六个仿真概念及关系阐述。

1. 基本元素(Prim)¶

Prim(Primitive)是 USD(通用场景描述)中的基本构建块,代表仿真环境中的任何对象,如机器人、传感器或环境物体。每个 Prim 都包含描述其状态和行为的属性(如位置、旋转、材质等)。Prim 是构成仿真场景的最小单位,所有更高级别的概念(如场景、世界)都是基于 Prim 构建的。

2. 舞台(Stage)¶

舞台是 USD 的核心概念,定义了 Prim 的逻辑组织和空间关系:

  • 层级结构:Prim 通过路径(如 /World/Robot/Arm)形成父子关系。
  • 属性管理:存储 Prim 的物理参数、材质等属性。
  • 上下文:没有舞台,Prim 无法存在或关联。

类比:舞台是戏剧表演的物理空间,所有演员(Prim)必须站在舞台上才能表演。

3. 场景(Scene)¶

场景是世界的子集,包含一组关联的 Prim:

  • 静态环境:如地面、墙壁。
  • 动态物体:如机器人、可移动物体。
  • 默认配置:灯光、坐标系等。

通过 world.scene 操作场景内容:

# 添加默认地面和机器人
ground = world.scene.add_default_ground_plane()
robot = world.scene.add(Robot(prim_path="/World/Franka"))

4. 世界(World)¶

世界是仿真的全局管理者,功能包括:

  • 时间控制:设置物理步长(Physics DT)和渲染频率。
  • 物理引擎:初始化重力、碰撞检测等。
  • 场景管理:加载或切换不同的场景。

在代码中,World 类是仿真的入口:

world = World(stage_units_in_meters=1.0, physics_dt=1.0/60.0)

5. 仿真(Simulation)¶

仿真是推动虚拟环境随时间变化的核心机制。它通过动态修改 Prim 的属性(如位置、速度)来模拟物理行为。例如:

  • 机械臂的运动通过更新关节角度实现。
  • 物体的碰撞通过调整刚体属性模拟。

6. 应用(Application)¶

应用是仿真的"外壳",负责管理以下内容:

  • 渲染:可视化仿真内容(如光线追踪、视窗显示)。
  • 交互:提供用户界面(GUI)、命令行或 API 控制仿真。
  • 扩展:支持通过 Python 脚本或插件添加功能(如自定义控制器)。

在 Isaac Sim 中,应用可以是:

  • 带GUI界面的Isaac Sim应用程序。
  • 无头模式(Headless)的Isaac Sim应用程序(后台运行)。

核心概念关系可视化¶

核心概念关系

核心概念的API层次关系¶

2. 协作流程¶

  1. 应用启动仿真,并加载 舞台(Stage)。
  2. 世界在舞台上初始化物理规则和时间管理。
  3. 场景在世界中添加具体的 Prim(如机器人、环境)。
  4. 仿真通过修改 Prim 属性(如位置、速度)推动时间前进。
  5. 舞台维护所有 Prim 的关系和属性,供应用渲染和交互。

3. 剧场模型类比¶

概念 剧场类比 交互关系
Application 剧院 提供入口,管理演出流程(灯光、售票)。
Simulation 戏剧剧本 通过指令(代码)驱动演员(Prim)表演。
Stage 物理舞台 所有表演发生的空间,演员必须站在舞台上。
World 导演 + 幕后团队 控制时间进度(幕布切换)、协调场景变化。
Scene 当前幕布的布景 包含当前需要的道具和演员组合。
Prim 演员或道具 通过属性(位置、动作)参与表演。

实际开发中的使用示例¶

from isaacsim import SimulationApp
from isaacsim.core.api import World
from isaacsim.robot.wheeled_robots.controllers.differential_controller import DifferentialController
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
from isaacsim.storage.native import get_assets_root_path

# 开启Application和Simulation
simulation_app = SimulationApp({"headless": False})

# 创建World,定义World的度量单位
my_world = World(stage_units_in_meters=1.0)

# 添加Stage至Scene(注:jetbot.usd可理解为一个Stage,由多个Prim组成)
assets_root_path = get_assets_root_path()
if assets_root_path is None:
    carb.log_error("Could not find Isaac Sim assets folder")
jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
my_jetbot = my_world.scene.add(
    WheeledRobot(
        prim_path="/World/Jetbot",
        name="my_jetbot",
        wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],
        create_robot=True,
        usd_path=jetbot_asset_path,
        position=np.array([0, 0.0, 2.0]),
    )
)
my_world.scene.add_default_ground_plane()
my_controller = DifferentialController(name="simple_control", wheel_radius=0.03, wheel_base=0.1125)
my_world.reset()

# 仿真逻辑
i = 0
reset_needed = False
while simulation_app.is_running():
    my_world.step(render=True)
    if my_world.is_stopped() and not reset_needed:
        reset_needed = True
    if my_world.is_playing():
        if reset_needed:
            my_world.reset()
            my_controller.reset()
            reset_needed = False
        if i >= 0 and i < 1000:
            # forward
            my_jetbot.apply_wheel_actions(my_controller.forward(command=[0.05, 0]))
            print(my_jetbot.get_linear_velocity())
        i += 1
    if args.test is True:
        break

通过理解这些概念及其关系,开发者可以更高效地设计仿真任务,例如:

  • 通过 World 控制全局仿真参数。
  • 通过 Scene 管理特定任务的物体集合。
  • 通过 Stage 直接操作 Prim 的底层属性。

5.3 Isaac Sim脚本化入门——多机器人协助搬运扩展案例开发¶

本节将通过"多机器人协助搬运案例"介绍Isaac Sim扩展的脚本化开发过程。这一案例最终效果如下。

案例效果

由于这是扩展的脚本化开发,因此需要先启动Isaac Sim应用程序进行加载扩展来查看代码运行情况。

注意(十分重要):当扩展代码调整后,需在VsCode / Cursor保存调整内容后,重启Isaac Sim应用程序及扩展方可查看变化情况(重启实现方法:在启动Isaac Sim应用程序的终端输入Ctrl + C终止Isaac Sim应用程序进程再启动Isaac Sim应用程序,重启后再按以下步骤打开相关扩展即可查看变化)。

本案例将围绕Hello World扩展进行开发,以下是在Isaac Sim可视化界面加载这一扩展的步骤。

  1. 通过VsCode / Cursor连接至Isaac Sim容器及启动Isaac Sim应用程序(参考01_Isaac Sim仿真平台介绍及容器化安装1.2.5内容)

  2. 通过Isaac Sim WebRTC Streaming Client连接Isaac Sim应用程序(参考01_Isaac Sim仿真平台介绍及容器化安装1.3内容)

  3. 通过"Windows > Examples > Robotics Examples"激活Robotics Examples选项。

Robotics Examples激活

  1. 在Robotics Examples选项中加载"Hello World"扩展内容。

加载Hello World扩展

5.3.1 打开扩展代码及添加立方体至场景内¶

Hello World扩展代码路径为/isaac-sim/extension_examples/hello_world/hello_world.py,在已连接Isaac Sim容器的VsCode / Cursor打开效果如下。

可以看到这一扩展继承自 BaseSample,包含__init__、setup_scene、setup_post_load、setup_pre_reset、setup_post_reset、world_cleanup这六个方法,以下是这六个方法作用介绍。

注:BaseSample是一个样板扩展应用程序,为每个扩展应用程序设置了基础功能(例如当用户点击"Load"按钮时加载场景)。

  1. init__方法:通过 super().__init() 调用 BaseSample 的构造函数,初始化基础设置(如物理时间步长、场景单位等)。

  2. setup_scene方法:设置场景内容(如添加地面、物体等)。

  3. setup_post_load方法:在场景加载后执行初始化操作(如设置变量、控制器等)。

  4. setup_pre_reset方法:在场景重置前执行清理操作(如移除物理回调、重置控制器等)。

  5. setup_post_reset方法:在场景重置后执行初始化操作(如重新添加物理回调、设置目标等)。

  6. world_cleanup方法:在扩展关闭或热重载时清理资源(如释放内存、断开连接等)。

以下使用 Python API 将立方体作为刚体添加到场景中,调整Hello World扩展代码内容如下。

from isaacsim.examples.interactive.base_sample import BaseSample
import numpy as np
# 立方体 Python API引用
from isaacsim.core.api.objects import DynamicCuboid

class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        world.scene.add_default_ground_plane()
        fancy_cube = world.scene.add(
            DynamicCuboid(
                prim_path="/World/random_cube",  # 立方体在 USD 舞台中的 prim 路径
                name="fancy_cube",  # 对象名称
                position=np.array([0, 0, 1.0]),  # 立方体世界坐标位置
                scale=np.array([0.5015, 0.5015, 0.5015]),  # 立方体缩放比例
                color=np.array([0, 0, 1.0]),  # 立方体颜色,使用数组表示RGB值
            ))
        return
    
    async def setup_post_load(self):
        return

    async def setup_pre_reset(self):
        return

    async def setup_post_reset(self):
        return

    def world_cleanup(self):
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展可以看到一个蓝色的立方体将加载至场景内。点击"Play"按钮可以看到立方体向下落。

新增方块

5.3.2 添加机器人至场景内¶

刚刚添加立方体至场景内,目的只是感受代码与扩展内容同时变化,但这不是案例目的。因此,需要把立方体去除,在场景里引入Jetbot机器人,Hello World扩展代码调整如下。

注:以下涉及Nucleus服务器为Isaac Sim资产服务器,本课程镜像把Isaac Sim资产服务器获取资产路径设置为/isaac-sim/isaacsim-assets,即与文件浏览器打开的资产内容路径一致。

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.core.utils.nucleus import get_assets_root_path
from isaacsim.core.utils.stage import add_reference_to_stage
from isaacsim.core.api.robots import Robot
import carb


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        # 获取当前世界的实例
        world = self.get_world()
        # 向场景中添加默认的地面平面
        world.scene.add_default_ground_plane()

        # 获取 Nucleus 服务器中 /Isaac 文件夹的路径
        assets_root_path = get_assets_root_path()
        if assets_root_path is None:
            # 使用 carb 记录错误日志(终端显示)
            carb.log_error("未找到包含 /Isaac 文件夹的 Nucleus 服务器")

        # 定义 Jetbot 机器人的 USD 文件路径
        asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        # 在 USD 舞台中创建一个新的 XFormPrim,并将其指向 USD 文件作为引用
        # 类似于内存中的指针
        add_reference_to_stage(usd_path=asset_path, prim_path="/World/Fancy_Robot")

        # 将 Jetbot 的 prim 根节点包装到 Robot 类中,并添加到场景中
        # 以便使用高级 API 设置/获取属性,并初始化所需的物理句柄等
        # 注意:此调用不会在舞台窗口中创建 Jetbot,它已经在 add_reference_to_stage 中创建
        jetbot_robot = world.scene.add(Robot(prim_path="/World/Fancy_Robot", name="fancy_robot"))

        # 注意:在调用 reset 之前,无法访问与 Articulation 相关的信息
        # 因为物理句柄尚未初始化。setup_post_load 在第一次 reset 后调用,因此可以在此处操作
        print("第一次 reset 前的自由度数量: " + str(jetbot_robot.num_dof))  # 输出 None
        return

    async def setup_post_load(self):
        return

    async def setup_pre_reset(self):
        return

    async def setup_post_reset(self):
        return

    def world_cleanup(self):
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展可以看到Jetbot机器人将加载至场景内。但是点击"Play"按钮后,Jetbot无法自主移动。下一步骤将对Jetbot增加移动功能。

引入Jetbot

5.3.3 Jetbot增加移动功能¶

由"04_基于OmniGraph的仿真逻辑控制"内容可以知道,要让Jetbot机器人拥有移动功能需要对它的左右轮增加控制器。Hello World扩展代码调整如下:

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.core.utils.types import ArticulationAction
from isaacsim.core.utils.nucleus import get_assets_root_path
from isaacsim.core.utils.stage import add_reference_to_stage
from isaacsim.core.api.robots import Robot
import numpy as np
import carb


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        # 获取当前世界的实例
        world = self.get_world()
        # 添加默认地面平面
        world.scene.add_default_ground_plane()
        # 获取 Nucleus 服务器中 /Isaac 文件夹的路径
        assets_root_path = get_assets_root_path()
        if assets_root_path is None:
            # 记录错误日志(终端显示)
            carb.log_error("未找到包含 /Isaac 文件夹的 Nucleus 服务器")
        # 定义 Jetbot 机器人的 USD 文件路径
        asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        # 将 USD 文件引用到舞台中
        add_reference_to_stage(usd_path=asset_path, prim_path="/World/Fancy_Robot")
        # 将 Jetbot 包装为 Robot 类实例并添加到场景
        jetbot_robot = world.scene.add(Robot(prim_path="/World/Fancy_Robot", name="fancy_robot"))
        return

    async def setup_post_load(self):
        # 获取当前世界的实例
        self._world = self.get_world()
        # 从场景中获取名为 "fancy_robot" 的机器人对象
        self._jetbot = self._world.scene.get_object("fancy_robot")
        # 获取机器人的关节控制器(隐式 PD 控制器)
        # 通过此控制器可以设置 PD 增益、应用动作、切换控制模式等
        # 注意:必须在第一次 reset 后调用
        self._jetbot_articulation_controller = self._jetbot.get_articulation_controller()
        # 添加物理回调函数,在每次物理步进时发送动作
        self._world.add_physics_callback("sending_actions", callback_fn=self.send_robot_actions)
        return

    def send_robot_actions(self, step_size):
        # 每个关节控制器都有 apply_action 方法
        # 接收 ArticulationAction 参数,包含关节位置、关节力和关节速度(可选)
        # 参数可以是 numpy 数组、浮点数列表或 None(表示不应用动作)
        # 也可以通过 self._jetbot.apply_action(...) 调用
        self._jetbot_articulation_controller.apply_action(
            ArticulationAction(
                joint_positions=None,
                joint_efforts=None,
                joint_velocities=5 * np.random.rand(2,)
            )
        )
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Play"按钮后,Jetbot应用随机速度进行前进。

Jetbot随机速度前进

刚才我们通过点击Play按钮,让 JetBot 以随机速度前进,观察到不同速度下的运动效果。 但如果想重新测试一组新的随机速度,或者发现机器人卡住需要重来,该怎么办呢?—— 这时就需要用到 Reset 按钮。按钮位置如下:

在这里插入图片描述



5.3.3.1 为什么不直接使用Play按钮下的Stop按钮进行重置呢?¶

首先我们可以通过下表了解一下具体的按键作用以及他们背后的逻辑

按钮 作用 适用场景
Play 启动/继续仿真,物理引擎开始计算 首次运行或暂停后恢复
Reset 完全重置场景到初始状态(位置、速度归零,但保留程序逻辑) 更换参数、修复错误或重复实验
Stop 强制停止仿真,释放资源(需谨慎使用) 结束整个仿真进程

注意上面提到的Stop按钮:它会直接终止仿真进程,但因为我们尚未编写资源清理代码(如卸载模型、断开传感器连接),因此直接使用Stop按钮将会导致再次Play重新仿真时会出现参数缺失的报错



5.3.4 通过WheelRobot API简化Jetbot移动功能实现¶

Isaac Sim对于常见的机器人类型进行功能封装,对于Jetbot这一轮式机器人Isaac Sim通过WheeledRobot这一类型进行封装,实现引入Jetbot、移动功能时可通过WheeledRobot简化大量代码。以下将通过WheeledRobot类完成Jetbot机器人引用及移动功能实现。

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.core.utils.nucleus import get_assets_root_path
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
from isaacsim.core.utils.types import ArticulationAction
import numpy as np


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        # 获取当前世界的实例
        world = self.get_world()
        # 添加默认地面平面
        world.scene.add_default_ground_plane()
        # 获取 Nucleus 服务器中 /Isaac 文件夹的路径
        assets_root_path = get_assets_root_path()
        # 定义 Jetbot 机器人的 USD 文件路径
        jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        # 创建轮式机器人实例并添加到场景
        # 参数说明:
        # - prim_path: 机器人在 USD 舞台中的路径
        # - name: 机器人唯一名称
        # - wheel_dof_names: 轮子关节名称列表
        # - create_robot: 是否创建机器人
        # - usd_path: 机器人模型文件路径
        self._jetbot = world.scene.add(
            WheeledRobot(
                prim_path="/World/Fancy_Robot",
                name="fancy_robot",
                wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],
                create_robot=True,
                usd_path=jetbot_asset_path,
            )
        )
        return

    async def setup_post_load(self):
        # 获取当前世界的实例
        self._world = self.get_world()
        # 从场景中获取机器人对象
        self._jetbot = self._world.scene.get_object("fancy_robot")
        # 添加物理回调函数,在每次物理步进时发送轮子动作
        self._world.add_physics_callback("sending_actions", callback_fn=self.send_robot_actions)
        return

    def send_robot_actions(self, step_size):
        # 应用轮子动作
        # 使用 ArticulationAction 设置轮子的关节速度(随机生成)
        # joint_positions 和 joint_efforts 设为 None 表示不控制位置和力
        self._jetbot.apply_wheel_actions(
            ArticulationAction(
                joint_positions=None,
                joint_efforts=None,
                joint_velocities=5 * np.random.rand(2,)
            )
        )
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Play"按钮后,Jetbot应用随机速度进行前进。

Jetbot随机前进

注意: 由于我们并尚未编写资源清理代码(如卸载模型、断开传感器连接),因此如果想重新测试一组新的随机速度,我们可以使用Reset按钮



5.3.5 通过自定义差速控制器实现机器人运动控制¶

在8.3.4的代码可以看到,实现Jetbot机器人移动功能只是赋予关节速度,但是这种方式无法精确控制机器人运动。以下将构建一个自定义的差速控制器实现Jetbot机器人运动控制。Hello World扩展代码调整如下:

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.core.utils.nucleus import get_assets_root_path
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
from isaacsim.core.utils.types import ArticulationAction
from isaacsim.core.api.controllers import BaseController
import numpy as np


class CoolController(BaseController):
    def __init__(self):
        super().__init__(name="my_cool_controller")
        # 开环控制器,基于独轮车模型
        self._wheel_radius = 0.03  # 轮子半径(单位:米)
        self._wheel_base = 0.1125  # 轮子间距(单位:米)
        return

    def forward(self, command):
        # command 包含两个参数:
        # - command[0]: 前进速度
        # - command[1]: 角速度(偏航角)
        joint_velocities = [0.0, 0.0]
        # 计算左轮速度
        joint_velocities[0] = ((2 * command[0]) - (command[1] * self._wheel_base)) / (2 * self._wheel_radius)
        # 计算右轮速度
        joint_velocities[1] = ((2 * command[0]) + (command[1] * self._wheel_base)) / (2 * self._wheel_radius)
        # 返回关节速度控制指令
        return ArticulationAction(joint_velocities=joint_velocities)


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        # 获取当前世界的实例
        world = self.get_world()
        # 添加默认地面平面
        world.scene.add_default_ground_plane()
        # 获取 Nucleus 服务器中 /Isaac 文件夹的路径
        assets_root_path = get_assets_root_path()
        # 定义 Jetbot 机器人的 USD 文件路径
        jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        # 创建轮式机器人实例并添加到场景
        world.scene.add(
            WheeledRobot(
                prim_path="/World/Fancy_Robot",  # 机器人在 USD 舞台中的路径
                name="fancy_robot",              # 机器人唯一名称
                wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],  # 轮子关节名称
                create_robot=True,               # 是否创建机器人
                usd_path=jetbot_asset_path,      # 机器人模型文件路径
            )
        )
        return

    async def setup_post_load(self):
        # 获取当前世界的实例
        self._world = self.get_world()
        # 从场景中获取机器人对象
        self._jetbot = self._world.scene.get_object("fancy_robot")
        # 添加物理回调函数,在每次物理步进时发送机器人动作
        self._world.add_physics_callback("sending_actions", callback_fn=self.send_robot_actions)
        # 初始化自定义控制器
        self._my_controller = CoolController()
        return

    def send_robot_actions(self, step_size):
        # 应用控制器计算的动作
        # 参数说明:
        # - command[0]: 前进速度(0.20 米/秒)
        # - command[1]: 角速度(π/4 弧度/秒)
        self._jetbot.apply_action(self._my_controller.forward(command=[0.20, np.pi / 4]))
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Play"按钮后,Jetbot应用特定的前进速度和角速度进行移动。

Jetbot特定速度前进

注意: 由于我们并尚未编写资源清理代码(如卸载模型、断开传感器连接),因此如果想重新测试一组新的随机速度,我们可以使用Reset按钮



5.3.6 通过Isaac Sim底盘控制API实现Jetbot运动控制及导航功能¶

同样地,Isaac Sim在轮式机器人运动场景中,也封装了常见的控制器。其中,它通过DifferentialController类实现轮式机器人的差速控制,可通过其取代我们8.3.5实现的CoolController。在导航的场景下,Isaac Sim也提供了对应的控制器(WheelBasePoseController)。通过DifferentialController差速控制器和WheelBasePoseController位置控制器的组合,可以实现Jetbot运动控制及导航功能。Hello World扩展代码调整如下

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.core.utils.nucleus import get_assets_root_path
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
# 引用轮式机器人位置控制器
from isaacsim.robot.wheeled_robots.controllers.wheel_base_pose_controller import WheelBasePoseController
# 引用轮式机器人就差速控制器
from isaacsim.robot.wheeled_robots.controllers.differential_controller import DifferentialController
import numpy as np


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        # 获取当前世界的实例
        world = self.get_world()
        # 添加默认地面平面
        world.scene.add_default_ground_plane()
        # 获取 Nucleus 服务器中 /Isaac 文件夹的路径
        assets_root_path = get_assets_root_path()
        # 定义 Jetbot 机器人的 USD 文件路径
        jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        # 创建轮式机器人实例并添加到场景
        world.scene.add(
            WheeledRobot(
                prim_path="/World/Fancy_Robot",  # 机器人在 USD 舞台中的路径
                name="fancy_robot",              # 机器人唯一名称
                wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],  # 轮子关节名称
                create_robot=True,               # 是否创建机器人
                usd_path=jetbot_asset_path,      # 机器人模型文件路径
            )
        )
        return

    async def setup_post_load(self):
        # 获取当前世界的实例
        self._world = self.get_world()
        # 从场景中获取机器人对象
        self._jetbot = self._world.scene.get_object("fancy_robot")
        # 添加物理回调函数,在每次物理步进时发送机器人动作
        self._world.add_physics_callback("sending_actions", callback_fn=self.send_robot_actions)
        self._my_controller = WheelBasePoseController(
            name="cool_controller",
            open_loop_wheel_controller=DifferentialController(
                name="simple_control",
                wheel_radius=0.03,  # 轮子半径(单位:米)
                wheel_base=0.1125   # 轮子间距(单位:米)
            ),
            is_holonomic=False
        )
        return

    def send_robot_actions(self, step_size):
        # 获取机器人当前位姿(位置和方向)
        position, orientation = self._jetbot.get_world_pose()
        # 应用控制器计算的动作
        # 参数说明:
        # - start_position: 机器人当前位置
        # - start_orientation: 机器人当前方向
        # - goal_position: 目标位置([0.8, 0.8])
        self._jetbot.apply_action(
            self._my_controller.forward(
                start_position=position,
                start_orientation=orientation,
                goal_position=np.array([0.8, 0.8])
            )
        )
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Play"按钮后,Jetbot前往预设的目标点。

Jetbot导航

注意: 由于我们并尚未编写资源清理代码(如卸载模型、断开传感器连接),因此如果想重新测试一组新的随机速度,我们可以使用Reset按钮



5.3.7 添加机械臂至场景内¶

在这个案例中,Jetbot小车机器人的任务(从A点到达B点)已经基本完成,后续在多机器人协作部分增加取物体/放下物体即可。本部分将暂时把Jetbot及相关任务逻辑去除,通过Hello World扩展增加机械臂部分。本案例将通过Franka机械臂完成物品夹取摆放的功能。以下将Hello World扩展场景加载设置为引入一个Franka机械臂以及方块,具体Hello World扩展代码如下:

from isaacsim.examples.interactive.base_sample import BaseSample
# 通过该API类实现引用Franka机械臂
from isaacsim.robot.manipulators.examples.franka import Franka
from isaacsim.core.api.objects import DynamicCuboid
import numpy as np


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        # 获取当前世界的实例
        world = self.get_world()
        # 添加默认地面平面
        world.scene.add_default_ground_plane()
        
        # 添加 Franka 机械臂到场景
        # Franka 是一个机器人专用类,提供额外功能(如夹爪和末端执行器实例)
        franka = world.scene.add(
            Franka(
                prim_path="/World/Fancy_Franka",  # 机械臂在 USD 舞台中的路径
                name="fancy_franka"               # 机械臂唯一名称
            )
        )
        
        # 添加一个立方体供 Franka 抓取
        world.scene.add(
            DynamicCuboid(
                prim_path="/World/random_cube",  # 立方体在 USD 舞台中的路径
                name="fancy_cube",               # 立方体唯一名称
                position=np.array([0.3, 0.3, 0.3]),  # 立方体初始位置(x, y, z)
                scale=np.array([0.0515, 0.0515, 0.0515]),  # 立方体缩放比例
                color=np.array([0, 0, 1.0]),     # 立方体颜色(RGB,范围 0-1)
            )
        )
        return

Isaac Sim对Franka机械臂进行API封装,可以通过isaacsim.robot.manipulators.examples.franka类完成 Franka 机器人资产引用及配置。同样地,通过DynamicCuboid类加载待夹取的方块。

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Load"按钮后,Franka机器人和方块将加载至场景内。

Franka、方块加载

5.3.8 添加机械臂控制器¶

以上部分只是把Franka机械臂加载至场景内,但是Franka机械臂并无法根据方块位置进行夹取和摆放。Isaac Sim已对Franka机械臂夹取、摆放任务进行控制器封装(isaacsim.robot.manipulators.examples.franka.controllers模块的PickPlaceController),通过该控制器,输入目标夹取物品位置以及目标摆放位置,即可实现Franka机械臂夹取和摆放。Hello World扩展代码调整如下。

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka import Franka
from isaacsim.core.api.objects import DynamicCuboid
from isaacsim.robot.manipulators.examples.franka.controllers import PickPlaceController
import numpy as np


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        # 获取当前世界的实例
        world = self.get_world()
        # 添加默认地面平面
        world.scene.add_default_ground_plane()
        # 添加 Franka 机械臂到场景
        franka = world.scene.add(
            Franka(
                prim_path="/World/Fancy_Franka",  # 机械臂在 USD 舞台中的路径
                name="fancy_franka"               # 机械臂唯一名称
            )
        )
        # 添加一个立方体供 Franka 抓取
        world.scene.add(
            DynamicCuboid(
                prim_path="/World/random_cube",  # 立方体在 USD 舞台中的路径
                name="fancy_cube",               # 立方体唯一名称
                position=np.array([0.3, 0.3, 0.3]),  # 立方体初始位置(x, y, z)
                scale=np.array([0.0515, 0.0515, 0.0515]),  # 立方体缩放比例
                color=np.array([0, 0, 1.0]),     # 立方体颜色(RGB,范围 0-1)
            )
        )
        return

    async def setup_post_load(self):
        # 获取当前世界的实例和对象
        self._world = self.get_world()
        self._franka = self._world.scene.get_object("fancy_franka")
        self._fancy_cube = self._world.scene.get_object("fancy_cube")
        # 初始化抓取放置控制器
        self._controller = PickPlaceController(
            name="pick_place_controller",  # 控制器名称
            gripper=self._franka.gripper,  # 机械臂夹爪实例
            robot_articulation=self._franka  # 机械臂实例
        )
        # 添加物理回调函数,在每次物理步进时执行
        self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
        # 设置夹爪为打开状态
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)
        # 启动仿真(异步)
        await self._world.play_async()
        return

    # 重置按钮按下后调用此函数
    # 重置世界中的任何状态应在此处完成
    async def setup_post_reset(self):
        # 重置控制器和夹爪状态
        self._controller.reset()
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)
        # 重新启动仿真(异步)
        await self._world.play_async()
        return

    def physics_step(self, step_size):
        # 获取立方体当前位置
        cube_position, _ = self._fancy_cube.get_world_pose()
        # 设置目标放置位置
        goal_position = np.array([-0.3, -0.3, 0.0515 / 2.0])
        # 获取机械臂当前关节位置
        current_joint_positions = self._franka.get_joint_positions()
        # 计算机械臂动作(抓取和放置)
        actions = self._controller.forward(
            picking_position=cube_position,  # 抓取位置
            placing_position=goal_position,  # 放置位置
            current_joint_positions=current_joint_positions  # 当前关节位置
        )
        # 应用动作到机械臂
        self._franka.apply_action(actions)
        # 如果控制器完成任务(状态机到达最终状态),暂停仿真
        if self._controller.is_done():
            self._world.pause()
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Load"按钮后,Franka机器人和方块将加载至场景内。点击"Play"按钮后,Franka夹取目标方块及放置至目标位置。

5.3.9使用Task类封装任务进行代码解耦¶

以上仅完成一个夹取、放置方块任务,扩展代码已经接近100行了,如果还要增加其他任务细节,Hello World扩展代码量将十分多。Isaac Sim提供Task类,可实现仿真任务的封装,实现任务封装后,扩展代码将大幅减少,仅需在必要部分加入任务相关内容即可。

5.3.9.1 什么是Task类?¶

在isaacsim中,Task类是一个核心的概念,它主要被用于定义和管理机器人在仿真环境中的行为、目标、执行逻辑以及任务之间的依赖关系,它的作用类似于机器人任务调度和协调的框架,使得开发者能够以结构化的方式设计复杂的机器人工作流。



5.3.9.2 为什么使用Task类?¶

如一开头所说的,task类的主要任务就是:

  1. 封装机器人的行为
  2. 管理任务状态
  3. 辅助任务场景的配置

通过task类,我们能够更好的管理机器人任务,让复杂的机器人任务更易于设计、调试和扩展,适用于仿真训练、多机器人协作和真实机器人控制等场景。

以下代码将任务逻辑封装在 FrankaPlaying 类(继承自 BaseTask),通过加载任务内容至world对象(世界),可实现Franka机械臂、方块等场景设置、任务相关的参数设置以及任务完成状态展示。在此基础上,Hello World仅增加夹取、放置任务的控制器的配置即可。以下是调整后的Hello World扩展代码。

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka import Franka
from isaacsim.core.api.objects import DynamicCuboid
from isaacsim.robot.manipulators.examples.franka.controllers import PickPlaceController
from isaacsim.core.api.tasks import BaseTask
import numpy as np

class FrankaPlaying(BaseTask):
    # 注意:这里仅覆盖部分任务方法,更多可重写方法请参考基类(如 calculate_metrics, is_done 等方法)
    def __init__(self, name):
        super().__init__(name=name, offset=None)
        self._goal_position = np.array([-0.3, -0.3, 0.0515 / 2.0])  # 立方体目标放置位置
        self._task_achieved = False  # 任务完成标志
        return

    # 设置任务场景(添加地面、立方体和Franka机械臂)
    def set_up_scene(self, scene):            
        super().set_up_scene(scene)
        scene.add_default_ground_plane()  # 添加默认地面
        # 添加动态立方体
        self._cube = scene.add(DynamicCuboid(
            prim_path="/World/random_cube",  # 立方体路径
            name="fancy_cube",               # 立方体名称
            position=np.array([0.3, 0.3, 0.3]),  # 初始位置
            scale=np.array([0.0515, 0.0515, 0.0515]),  # 大小
            color=np.array([0, 0, 1.0])      # 初始颜色(蓝色)
        ))
        # 添加Franka机械臂
        self._franka = scene.add(Franka(
            prim_path="/World/Fancy_Franka",  # 机械臂路径
            name="fancy_franka"               # 机械臂名称
        ))
        return

    # 返回任务观察数据(机械臂关节位置、立方体位置、目标位置)
    def get_observations(self):           
        cube_position, _ = self._cube.get_world_pose()  # 获取立方体位置
        current_joint_positions = self._franka.get_joint_positions()  # 获取机械臂关节位置
        observations = {
            self._franka.name: {"joint_positions": current_joint_positions},
            self._cube.name: {
                "position": cube_position,
                "goal_position": self._goal_position  # 目标位置
            }
        }
        return observations

    # 每步物理仿真前调用,检查任务是否完成(立方体是否接近目标位置)
    def pre_step(self, control_index, simulation_time):    
        cube_position, _ = self._cube.get_world_pose()
        # 如果立方体接近目标位置(误差<0.02),标记任务完成并改为绿色
        if not self._task_achieved and np.mean(np.abs(self._goal_position - cube_position)) < 0.02:
            self._cube.get_applied_visual_material().set_color(color=np.array([0, 1.0, 0]))  # 绿色
            self._task_achieved = True
        return

    # 每次重置后调用,初始化夹爪和立方体状态
    def post_reset(self):              
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)  # 打开夹爪
        self._cube.get_applied_visual_material().set_color(color=np.array([0, 0, 1.0]))  # 重置立方体为蓝色
        self._task_achieved = False  # 重置任务状态
        return


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        # 将任务添加到世界中
        world.add_task(FrankaPlaying(name="my_first_task"))    # 任务添加过后将会自动调用task中定义的逻辑进行执行
        return

    async def setup_post_load(self):
        self._world = self.get_world()
        # 从场景中获取Franka机械臂对象
        self._franka = self._world.scene.get_object("fancy_franka")
        # 初始化抓取放置控制器
        self._controller = PickPlaceController(
            name="pick_place_controller",  # 控制器名称
            gripper=self._franka.gripper,  # 绑定夹爪
            robot_articulation=self._franka  # 绑定机械臂
        )
        # 添加物理回调函数,在每步仿真中调用physics_step
        self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
        # 启动仿真(异步)
        await self._world.play_async()
        return

    async def setup_post_reset(self):
        self._controller.reset()  # 重置控制器
        await self._world.play_async()  # 重新启动仿真
        return

    def physics_step(self, step_size):
        # 获取任务观察数据(立方体位置、目标位置、机械臂关节状态)
        current_observations = self._world.get_observations()   # 执行该函数的时候将会调用所有添加任务的get_observations函数
        # 计算机械臂动作(抓取和放置)
        actions = self._controller.forward(
            picking_position=current_observations["fancy_cube"]["position"],  # 抓取位置
            placing_position=current_observations["fancy_cube"]["goal_position"],  # 放置位置
            current_joint_positions=current_observations["fancy_franka"]["joint_positions"]  # 当前关节位置
        )
        # 应用动作到机械臂
        self._franka.apply_action(actions)
        # 如果任务完成,暂停仿真
        if self._controller.is_done():
            self._world.pause()
        return

在上面的代码中,我们增加了:

  • BaseTask: task基类,用于创建一个新的任务对象,任务对象定义了任务的具体操作以及任务所属的机器人的建立与初始化方式等内容
  • BaseTask.set_up_scene: 任务的创建场景的接口,该函数每次在world进行加载创建或reset的时候默认都会执行一次函数
  • BaseTask.get_observations: 任务获取观察值的接口,当执行world.get_observations的时候将会自动调用该函数
  • BaseTask.pre_step: 任务具体执行仿真任务,在加载场景的时候将会自动将task存储到world._task列表中,并且每次步进的时候会执行pre_step函数
  • BaseTask.post_reset: 任务的reset接口,它主要用于定义场景reset的时候的操作,每次world.reset函数执行的时候,都将会执行该函数

由于我们使用了task来来进行定义任务项

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Load"按钮后,Franka机器人将夹取目标方块。当摆放至目标位置时,方块颜色变化。

Franka夹取目标方块

5.3.10 使用官方封装Franka夹取、放置任务类¶

因为Isaac Sim官方将Franka机械臂作为机械臂操作部分的主要示例机器人,他们对Franka机械臂夹取、放置任务也进行封装,上述任务部分代码可通过isaacsim.robot.manipulators.examples.franka.tasks模块的PickPlace进行替代。以下是调整后的Hello World扩展代码。

注:8.3.9重点展示夹取、仿真任务类如何构建,本部分重点介绍Isaac Sim官方封装的Franka机械臂任务类。如有未适配Isaac Sim机械臂夹取、放置任务实现,可重点理解8.3.9部分的夹取、放置任务实现逻辑。

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka.tasks import PickPlace
from isaacsim.robot.manipulators.examples.franka.controllers import PickPlaceController


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        # 将PickPlace任务添加到世界中
        # PickPlace是预定义的抓取放置任务,包含机械臂和立方体的初始化逻辑
        world.add_task(PickPlace(name="awesome_task"))
        return

    async def setup_post_load(self):
        self._world = self.get_world()
        # 获取任务的参数(通过get_params方法)
        # 任务参数以字典形式返回,例如:
        # {"robot_name": {"value": "fancy_franka", "modifiable": False}, ...}
        task_params = self._world.get_task("awesome_task").get_params()
        
        # 从场景中获取Franka机械臂对象
        self._franka = self._world.scene.get_object(task_params["robot_name"]["value"])
        # 获取立方体的名称(用于后续观察数据)
        self._cube_name = task_params["cube_name"]["value"]
        
        # 初始化抓取放置控制器
        self._controller = PickPlaceController(
            name="pick_place_controller",  # 控制器名称
            gripper=self._franka.gripper,  # 绑定机械臂夹爪
            robot_articulation=self._franka  # 绑定机械臂实例
        )
        
        # 添加物理回调函数,在每步仿真中调用physics_step
        self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
        # 启动仿真(异步)
        await self._world.play_async()
        return

    async def setup_post_reset(self):
        # 重置控制器状态
        self._controller.reset()
        # 重新启动仿真
        await self._world.play_async()
        return

    def physics_step(self, step_size):
        # 获取当前任务的观察数据(包括立方体位置、目标位置、机械臂关节状态)
        current_observations = self._world.get_observations()
        
        # 计算机械臂动作(抓取和放置)
        actions = self._controller.forward(
            picking_position=current_observations[self._cube_name]["position"],  # 立方体当前位置
            placing_position=current_observations[self._cube_name]["target_position"],  # 目标放置位置
            current_joint_positions=current_observations[self._franka.name]["joint_positions"]  # 机械臂当前关节位置
        )
        
        # 应用动作到机械臂
        self._franka.apply_action(actions)
        
        # 如果控制器标记任务完成,暂停仿真
        if self._controller.is_done():
            self._world.pause()
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Load"按钮后,Franka机器人将夹取目标方块。

Franka夹取目标方块

5.3.11 加载Jetbot、Franka机器人¶

以上部分已经分别把Jetbor机器人导航、Franka机器人夹取和放置任务实现,以下将通过RobotsPlaying完成Jetbot、Franka机器人的引入以及相关任务参数设置(例如方块初始位置为Jetbot机器人位置上方,开始仿真时方块会掉落至Jetbot运送货架上)。以下是调整后Hello World代码内容。

注:为避免代码过长,Franka机器人将通过PickPlane类加载Franka机器人且设计对应任务。

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka.tasks import PickPlace
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
from isaacsim.core.utils.nucleus import get_assets_root_path
from isaacsim.core.api.tasks import BaseTask
import numpy as np


class RobotsPlaying(BaseTask):      # 建立名为RobotsPlaying的task类对象
    def __init__(self, name):
        super().__init__(name=name, offset=None)
        # Jetbot 的目标位置
        self._jetbot_goal_position = np.array([130, 30, 0])
        # 使用 PickPlace 子任务(避免重复实现抓取逻辑)
        # 只需设置立方体的初始位置和目标位置
        self._pick_place_task = PickPlace(
            cube_initial_position=np.array([0.1, 0.3, 0.05]),  # 立方体初始位置
            target_position=np.array([0.7, -0.3, 0.0515 / 2.0])  # 目标放置位置
        )
        return

    def set_up_scene(self, scene):   # 在加载或reset场景的时候执行的操作
        super().set_up_scene(scene)
        # 初始化 PickPlace 子任务的场景(地面、Franka 机械臂、立方体)
        self._pick_place_task.set_up_scene(scene)
        # 获取 Nucleus 服务器中 /Isaac 文件夹的路径
        assets_root_path = get_assets_root_path()
        # 定义 Jetbot 机器人的 USD 文件路径
        jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        # 添加 Jetbot 到场景
        self._jetbot = scene.add(
            WheeledRobot(
                prim_path="/World/Fancy_Robot",  # 机器人在 USD 舞台中的路径
                name="fancy_robot",              # 机器人唯一名称
                wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],  # 轮子关节名称
                create_robot=True,               # 是否创建机器人
                usd_path=jetbot_asset_path,      # 机器人模型文件路径
                position=np.array([0, 0.3, 0])   # 机器人初始位置
            )
        )
        # 获取 PickPlace 任务的参数(如 Franka 机械臂名称)
        pick_place_params = self._pick_place_task.get_params()
        self._franka = scene.get_object(pick_place_params["robot_name"]["value"])
        # 修改 Franka 的默认位置(重置后生效)
        self._franka.set_world_pose(position=np.array([1.0, 0, 0]))
        self._franka.set_default_state(position=np.array([1.0, 0, 0]))
        return

    def get_observations(self):      # 调用world.get_observations函数的时候的具体操作
        # 获取 Jetbot 的当前位姿(位置和方向)
        current_jetbot_position, current_jetbot_orientation = self._jetbot.get_world_pose()
        # 返回 Jetbot 的观察数据(用于导航任务)
        observations = {
            self._jetbot.name: {
                "position": current_jetbot_position,
                "orientation": current_jetbot_orientation,
                "goal_position": self._jetbot_goal_position  # 目标位置
            }
        }
        return observations

    def get_params (self):           # 用于获取task参数的接口,该函数默认并不会自动执行,需要自行使用 BaseTask.get_params() 进行调用
        # 获取 PickPlace 任务的参数,并添加 Jetbot 和 Franka 的名称
        pick_place_params = self._pick_place_task.get_params()
        params_representation = pick_place_params
        params_representation["jetbot_name"] = {"value": self._jetbot.name, "modifiable": False}
        params_representation["franka_name"] = pick_place_params["robot_name"]
        return params_representations

    def post_reset(self):            # 定义场景reset的时候的操作,每次world.reset函数执行的时候,都将会执行该函数
        # 重置后打开 Franka 的夹爪
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        # 将任务添加到世界中
        world.add_task(RobotsPlaying(name="awesome_task"))
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Load"按钮后,Jetbot机器人和Franka机器人将加载至场景内,但不会执行任务。

5.3.12 实现Jetbot搬运方块任务¶

由于8.3.11已经设置方块初始位置在Jetbot机器人货架上方,因此Jetbot部分仅实现从A点至B点的导航任务即可。以下为调整后的Hello World扩展代码。

注:Jetbot导航任务逻辑与8.3.6相同。

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka.tasks import PickPlace
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
from isaacsim.core.utils.nucleus import get_assets_root_path
from isaacsim.robot.wheeled_robots.controllers.wheel_base_pose_controller import WheelBasePoseController
from isaacsim.robot.wheeled_robots.controllers.differential_controller import DifferentialController
from isaacsim.core.api.tasks import BaseTask
import numpy as np


class RobotsPlaying(BaseTask):                  # 建立名为RobotsPlaying的task类对象
    def __init__(self, name):
        super().__init__(name=name, offset=None)
        # 设置Jetbot的目标位置
        self._jetbot_goal_position = np.array([1.3, 0.3, 0])
        # 使用PickPlace子任务,设置立方体的初始位置和目标位置
        self._pick_place_task = PickPlace(
            cube_initial_position=np.array([0.1, 0.3, 0.05]),
            target_position=np.array([0.7, -0.3, 0.0515 / 2.0])
        )
        return

    def set_up_scene(self, scene):              # 在加载或reset场景的时候执行的操作
        super().set_up_scene(scene)
        # 初始化PickPlace子任务的场景(地面、Franka机械臂、立方体)
        self._pick_place_task.set_up_scene(scene)
        # 获取Nucleus服务器中/Isaac文件夹的路径
        assets_root_path = get_assets_root_path()
        # 定义Jetbot机器人的USD文件路径
        jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        # 添加Jetbot到场景
        self._jetbot = scene.add(
            WheeledRobot(
                prim_path="/World/Fancy_Jetbot",  # 机器人在USD舞台中的路径
                name="fancy_jetbot",              # 机器人唯一名称
                wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],  # 轮子关节名称
                create_robot=True,               # 是否创建机器人
                usd_path=jetbot_asset_path,      # 机器人模型文件路径
                position=np.array([0, 0.3, 0])   # 机器人初始位置
            )
        )
        # 获取PickPlace任务的参数(如Franka机械臂名称)
        pick_place_params = self._pick_place_task.get_params()
        self._franka = scene.get_object(pick_place_params["robot_name"]["value"])
        # 修改Franka的默认位置(重置后生效)
        self._franka.set_world_pose(position=np.array([1.0, 0, 0]))
        self._franka.set_default_state(position=np.array([1.0, 0, 0]))
        return

    def get_observations(self):                   # 调用world.get_observations函数的时候的具体操作
        # 获取Jetbot的当前位姿(位置和方向)
        current_jetbot_position, current_jetbot_orientation = self._jetbot.get_world_pose()
        # 返回Jetbot的观察数据(用于导航任务)
        observations = {
            self._jetbot.name: {
                "position": current_jetbot_position,
                "orientation": current_jetbot_orientation,
                "goal_position": self._jetbot_goal_position  # 目标位置
            }
        }
        return observations

    def get_params(self):
        # 获取PickPlace任务的参数,并添加Jetbot和Franka的名称
        pick_place_params = self._pick_place_task.get_params()
        params_representation = pick_place_params
        params_representation["jetbot_name"] = {"value": self._jetbot.name, "modifiable": False}
        params_representation["franka_name"] = pick_place_params["robot_name"]
        return params_representation

    def post_reset(self):                         # 定义场景reset的时候的操作,每次world.reset函数执行的时候,都将会执行该函数
        # 重置后打开Franka的夹爪
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        # 将任务添加到世界中
        world.add_task(RobotsPlaying(name="awesome_task"))
        return

    async def setup_post_load(self):
        self._world = self.get_world()
        # 获取任务参数
        task_params = self._world.get_task("awesome_task").get_params()
        # 从场景中获取Jetbot对象
        self._jetbot = self._world.scene.get_object(task_params["jetbot_name"]["value"])
        # 初始化Jetbot控制器
        # WheelBasePoseController: 主控制器,用于位姿控制
        # DifferentialController: 底层差速驱动控制器
        self._jetbot_controller = WheelBasePoseController(
            name="cool_controller",
            open_loop_wheel_controller=DifferentialController(
                name="simple_control",
                wheel_radius=0.03,  # 轮子半径
                wheel_base=0.1125   # 轮子间距
            )
        )
        # 添加物理回调函数
        self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
        # 启动仿真
        await self._world.play_async()
        return

    async def setup_post_reset(self):
        # 重置控制器
        self._jetbot_controller.reset()
        # 重新启动仿真
        await self._world.play_async()
        return

    def physics_step(self, step_size):
        # 获取当前观察数据(Jetbot位姿和目标位置)
        current_observations = self._world.get_observations()
        # 计算并应用Jetbot动作
        self._jetbot.apply_action(
            self._jetbot_controller.forward(
                start_position=current_observations[self._jetbot.name]["position"],
                start_orientation=current_observations[self._jetbot.name]["orientation"],
                goal_position=current_observations[self._jetbot.name]["goal_position"]
            )
        )
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Load"按钮后,Jetbot机器人搬运方块至Franka机器人待夹取位置。

Jetbot运输方块

5.3.13 Jetbot运输方块至目标点后往后退¶

JetBot运输方块至目标点后,需要离开目标点,Franka机械臂夹取方块时才不会因Jetbot影响夹取效果(因Jetbot停在目标点时可能与Franka机械臂夹爪进行碰撞)。以下代码将增加Jetbot到达目标点后往后退的逻辑,Hello World扩展代码调整后如下。

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka.tasks import PickPlace
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
from isaacsim.core.utils.nucleus import get_assets_root_path
from isaacsim.robot.wheeled_robots.controllers.wheel_base_pose_controller import WheelBasePoseController
from isaacsim.robot.wheeled_robots.controllers.differential_controller import DifferentialController
from isaacsim.core.api.tasks import BaseTask
from isaacsim.core.utils.types import ArticulationAction
import numpy as np


class RobotsPlaying(BaseTask):                   # 建立名为RobotsPlaying的task类对象
    def __init__(self, name):
        super().__init__(name=name, offset=None)
        # Jetbot的目标位置
        self._jetbot_goal_position = np.array([1.3, 0.3, 0])
        # 任务事件标记(0: Jetbot导航, 1: Jetbot后退, 2: 任务完成)
        self._task_event = 0
        # 初始化PickPlace子任务(Franka抓取立方体)
        self._pick_place_task = PickPlace(
            cube_initial_position=np.array([0.1, 0.3, 0.05]),  # 立方体初始位置
            target_position=np.array([0.7, -0.3, 0.0515 / 2.0])  # 目标放置位置
        )
        return

    def set_up_scene(self, scene):               # 在加载或reset场景的时候执行的操作
        super().set_up_scene(scene)
        # 初始化PickPlace子任务的场景(地面、Franka机械臂、立方体)
        self._pick_place_task.set_up_scene(scene)
        # 获取Jetbot的USD模型路径
        assets_root_path = get_assets_root_path()
        jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        # 添加Jetbot到场景
        self._jetbot = scene.add(
            WheeledRobot(
                prim_path="/World/Fancy_Jetbot",  # USD路径
                name="fancy_jetbot",              # 名称
                wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],  # 轮子关节
                create_robot=True,               # 创建机器人
                usd_path=jetbot_asset_path,      # 模型路径
                position=np.array([0, 0.3, 0])   # 初始位置
            )
        )
        # 获取Franka机械臂对象并调整其默认位置
        pick_place_params = self._pick_place_task.get_params()
        self._franka = scene.get_object(pick_place_params["robot_name"]["value"])
        self._franka.set_world_pose(position=np.array([1.0, 0, 0]))  # 设置当前位置
        self._franka.set_default_state(position=np.array([1.0, 0, 0]))  # 设置重置后的默认位置
        return

    def get_observations(self):                  # 调用world.get_observations函数的时候的具体操作
        # 获取Jetbot的当前位姿(位置和方向)
        current_jetbot_position, current_jetbot_orientation = self._jetbot.get_world_pose()
        # 返回观察数据(包括任务事件和Jetbot状态)
        observations = {
            "task_event": self._task_event,  # 当前任务阶段
            self._jetbot.name: {
                "position": current_jetbot_position,      # 当前位置
                "orientation": current_jetbot_orientation,  # 当前方向
                "goal_position": self._jetbot_goal_position  # 目标位置
            }
        }
        return observations

    def get_params(self):                       # 用于获取task参数的接口,该函数默认并不会自动执行,需要自行使用 BaseTask.get_params() 进行调用
        # 获取子任务参数,并添加Jetbot和Franka的名称
        pick_place_params = self._pick_place_task.get_params()
        params_representation = pick_place_params
        params_representation["jetbot_name"] = {"value": self._jetbot.name, "modifiable": False}
        params_representation["franka_name"] = pick_place_params["robot_name"]
        return params_representation

    def pre_step(self, control_index, simulation_time): # 每次world.step()进行物理步进都会执行的函数
        # 任务阶段0:Jetbot导航到目标位置
        if self._task_event == 0:
            current_jetbot_position, _ = self._jetbot.get_world_pose()
            # 检查是否接近目标位置(二维平面距离<0.04)
            if np.mean(np.abs(current_jetbot_position[:2] - self._jetbot_goal_position[:2])) < 0.04:
                self._task_event += 1  # 进入阶段1
                self._cube_arrive_step_index = control_index  # 记录到达时间步
        # 任务阶段1:Jetbot后退(持续200时间步)
        elif self._task_event == 1:
            if control_index - self._cube_arrive_step_index == 200:
                self._task_event += 1  # 进入阶段2
        return

    def post_reset(self):                        # 定义场景reset的时候的操作,每次world.reset函数执行的时候,都将会执行该函数
        # 重置时打开Franka夹爪,并重置任务阶段
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)
        self._task_event = 0
        return


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        # 添加任务到世界
        world.add_task(RobotsPlaying(name="awesome_task"))
        return

    async def setup_post_load(self):
        self._world = self.get_world()
        # 获取任务参数和对象
        task_params = self._world.get_task("awesome_task").get_params()
        self._jetbot = self._world.scene.get_object(task_params["jetbot_name"]["value"])
        # 初始化Jetbot控制器(位姿控制+差速驱动)
        self._jetbot_controller = WheelBasePoseController(
            name="cool_controller",
            open_loop_wheel_controller=DifferentialController(
                name="simple_control",
                wheel_radius=0.03,  # 轮子半径
                wheel_base=0.1125   # 轮子间距
            )
        )
        # 添加物理回调函数
        self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
        # 启动仿真
        await self._world.play_async()
        return

    async def setup_post_reset(self):
        # 重置控制器并重启仿真
        self._jetbot_controller.reset()
        await self._world.play_async()
        return

    def physics_step(self, step_size):
        # 获取当前观察数据
        current_observations = self._world.get_observations()
        # 根据任务阶段控制Jetbot
        if current_observations["task_event"] == 0:
            # 阶段0:导航到目标位置
            self._jetbot.apply_wheel_actions(
                self._jetbot_controller.forward(
                    start_position=current_observations[self._jetbot.name]["position"],
                    start_orientation=current_observations[self._jetbot.name]["orientation"],
                    goal_position=current_observations[self._jetbot.name]["goal_position"]
                )
            )
        elif current_observations["task_event"] == 1:
            # 阶段1:后退(固定速度)
            self._jetbot.apply_wheel_actions(ArticulationAction(joint_velocities=[-8, -8]))
        elif current_observations["task_event"] == 2:
            # 阶段2:停止
            self._jetbot.apply_wheel_actions(ArticulationAction(joint_velocities=[0.0, 0.0]))
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Load"按钮后,Jetbot机器人将方块运输至目标点后往后退。

5.3.14 Franka夹取目标方块¶

Jetbot机器人把方块运输至目标点后,Franka机器人将目标点的方块夹取且放置至合适位置。以下是实现该部分的Hello World扩展代码。

from isaacsim.examples.interactive.base_sample import BaseSample
from isaacsim.robot.manipulators.examples.franka.tasks import PickPlace
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
from isaacsim.core.utils.nucleus import get_assets_root_path
from isaacsim.robot.wheeled_robots.controllers.wheel_base_pose_controller import WheelBasePoseController
from isaacsim.robot.manipulators.examples.franka.controllers import PickPlaceController
from isaacsim.robot.wheeled_robots.controllers.differential_controller import DifferentialController
from isaacsim.core.api.tasks import BaseTask
from isaacsim.core.utils.types import ArticulationAction
import numpy as np


class RobotsPlaying(BaseTask):           # 建立名为RobotsPlaying的task类对象 
    def __init__(self, name):
        super().__init__(name=name, offset=None)
        # Jetbot的目标位置
        self._jetbot_goal_position = np.array([1.3, 0.3, 0])
        # 任务阶段标记:0-导航,1-后退,2-抓取
        self._task_event = 0
        # 初始化抓取任务(Franka机械臂)
        self._pick_place_task = PickPlace(
            cube_initial_position=np.array([0.1, 0.3, 0.05]),  # 立方体初始位置
            target_position=np.array([0.7, -0.3, 0.0515 / 2.0])  # 目标放置位置
        )
        return

    def set_up_scene(self, scene):       # 在加载或reset场景的时候执行的操作
        super().set_up_scene(scene)
        # 设置抓取任务的场景(地面、Franka、立方体)
        self._pick_place_task.set_up_scene(scene)
        # 加载Jetbot模型
        assets_root_path = get_assets_root_path()
        jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
        # 添加Jetbot到场景
        self._jetbot = scene.add(
            WheeledRobot(
                prim_path="/World/Fancy_Jetbot",  # USD路径
                name="fancy_jetbot",              # 名称
                wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],  # 轮子关节
                create_robot=True,                # 创建机器人
                usd_path=jetbot_asset_path,       # 模型路径
                position=np.array([0, 0.3, 0])    # 初始位置
            )
        )
        # 获取Franka机械臂并设置位置
        pick_place_params = self._pick_place_task.get_params()
        self._franka = scene.get_object(pick_place_params["robot_name"]["value"])
        self._franka.set_world_pose(position=np.array([1.0, 0, 0]))  # 当前位置
        self._franka.set_default_state(position=np.array([1.0, 0, 0]))  # 默认位置
        return

    def get_observations(self):          # 调用world.get_observations函数的时候的具体操作    
        # 获取Jetbot位姿
        current_jetbot_position, current_jetbot_orientation = self._jetbot.get_world_pose()
        # 合并任务观察数据(包括子任务数据)
        observations = {
            "task_event": self._task_event,  # 当前任务阶段
            self._jetbot.name: {
                "position": current_jetbot_position,      # 位置
                "orientation": current_jetbot_orientation,  # 方向
                "goal_position": self._jetbot_goal_position  # 目标位置
            }
        }
        observations.update(self._pick_place_task.get_observations())  # 添加子任务数据
        return observations

    def get_params(self):                # 用于获取task参数的接口,该函数默认并不会自动执行,需要自行使用 BaseTask.get_params() 进行调用
        # 获取任务参数(包括子任务参数)
        pick_place_params = self._pick_place_task.get_params()
        params_representation = pick_place_params
        params_representation["jetbot_name"] = {"value": self._jetbot.name, "modifiable": False}
        params_representation["franka_name"] = pick_place_params["robot_name"]
        return params_representation

    def pre_step(self, control_index, simulation_time): # 每次world.step()进行物理步进都会执行的函数
        # 任务阶段0:Jetbot导航到目标
        if self._task_event == 0:
            current_jetbot_position, _ = self._jetbot.get_world_pose()
            if np.mean(np.abs(current_jetbot_position[:2] - self._jetbot_goal_position[:2])) < 0.04:
                self._task_event += 1  # 进入阶段1
                self._cube_arrive_step_index = control_index  # 记录到达时间步
        # 任务阶段1:Jetbot后退200步
        elif self._task_event == 1:
            if control_index - self._cube_arrive_step_index == 200:
                self._task_event += 1  # 进入阶段2
        return

    def post_reset(self):                # 定义场景reset的时候的操作,每次world.reset函数执行的时候,都将会执行该函数
        # 重置时打开Franka夹爪并重置任务阶段
        self._franka.gripper.set_joint_positions(self._franka.gripper.joint_opened_positions)
        self._task_event = 0
        return


class HelloWorld(BaseSample):
    def __init__(self) -> None:
        super().__init__()
        return

    def setup_scene(self):
        world = self.get_world()
        # 添加任务到世界
        world.add_task(RobotsPlaying(name="awesome_task"))
        return

    async def setup_post_load(self):
        self._world = self.get_world()
        # 获取任务参数和对象
        task_params = self._world.get_task("awesome_task").get_params()
        self._franka = self._world.scene.get_object(task_params["franka_name"]["value"])
        self._jetbot = self._world.scene.get_object(task_params["jetbot_name"]["value"])
        self._cube_name = task_params["cube_name"]["value"]
        # 初始化控制器
        self._franka_controller = PickPlaceController(
            name="pick_place_controller",  # Franka抓取控制器
            gripper=self._franka.gripper,
            robot_articulation=self._franka
        )
        self._jetbot_controller = WheelBasePoseController(
            name="cool_controller",  # Jetbot导航控制器
            open_loop_wheel_controller=DifferentialController(
                name="simple_control",
                wheel_radius=0.03,  # 轮子半径
                wheel_base=0.1125   # 轮距
            )
        )
        # 添加物理回调
        self._world.add_physics_callback("sim_step", callback_fn=self.physics_step)
        await self._world.play_async()  # 启动仿真
        return

    async def setup_post_reset(self):
        # 重置控制器
        self._franka_controller.reset()
        self._jetbot_controller.reset()
        await self._world.play_async()  # 重启仿真
        return

    def physics_step(self, step_size):
        current_observations = self._world.get_observations()
        # 阶段0:Jetbot导航
        if current_observations["task_event"] == 0:
            self._jetbot.apply_wheel_actions(
                self._jetbot_controller.forward(
                    start_position=current_observations[self._jetbot.name]["position"],
                    start_orientation=current_observations[self._jetbot.name]["orientation"],
                    goal_position=current_observations[self._jetbot.name]["goal_position"]
                )
            )
        # 阶段1:Jetbot后退
        elif current_observations["task_event"] == 1:
            self._jetbot.apply_wheel_actions(ArticulationAction(joint_velocities=[-8, -8]))
        # 阶段2:Jetbot停止,Franka抓取
        elif current_observations["task_event"] == 2:
            self._jetbot.apply_wheel_actions(ArticulationAction(joint_velocities=[0.0, 0.0]))
            # Franka执行抓取动作
            actions = self._franka_controller.forward(
                picking_position=current_observations[self._cube_name]["position"],
                placing_position=current_observations[self._cube_name]["target_position"],
                current_joint_positions=current_observations[self._franka.name]["joint_positions"]
            )
            self._franka.apply_action(actions)
        # 抓取完成后暂停仿真
        if self._franka_controller.is_done():
            self._world.pause()
        return

将以上代码变化调整至hello_world.py代码文件,重启Isaac Sim及Hello World扩展,点击"Load"按钮后,Jetbot机器人搬运方块,Franka机器人夹取方块至目标位置,实现多机器人协同任务。

Jetbot、Franka完成搬运任务

5.4 Isaac Sim脚本化开发进阶——Franka机器人夹取放置案例独立脚本开发¶

本节将通过"Franka机器人夹取放置案例"介绍Isaac Sim独立脚本开发过程。这一案例最终效果如下所示。

案例效果

独立脚本与扩展不同,它包含Isaac Sim应用程序启动、角色对象/场景定义、任务逻辑实现。扩展仅包括角色对象/场景定义以及任务逻辑实现。本节将逐一介绍Isaac Sim启动、Jetbot机器人导入、Franka导入等步骤,这个完整脚本将保存至/isaac-sim/course-content/scripts/hello_world.py(注意:这与扩展的hello_world.py文件不同)。

注意:

  1. 如果在学习5.3部分内容时,使用了"runheadless.sh"脚本启动了Isaac Sim应用程序,需要在该脚本对应的终端内键入Ctrl + C停止相关进程,避免该Isaac Sim应用程序与5.4.0启动的Isaac Sim应用程序出现冲突。
  2. 5.4.1及以后的代码需先启动Isaac Sim(即执行5.4.0启动Isaac Sim代码),5.4.1、5.4.2、5.4.3、5.4.4部分代码需连贯执行,不可反复跳动,否则出现代码执行错误等问题。

5.4.0 启动Isaac Sim¶

当以下代码执行后输出"Streaming server started"即代表Isaac Sim启动成功。Isaac Sim启动成功后,但由于后续还有定义角色对象、任务逻辑实现等步骤,通过Isaac Sim WebRTC Streaming Client进行连接无法查看Isaac Sim图形化界面。

In [ ]:
from isaacsim import SimulationApp
import argparse
import sys

import carb

# 配置仿真应用参数
CONFIG = {
    "width": 1280,            # 渲染窗口宽度
    "height": 720,            # 渲染窗口高度
    "window_width": 1920,     # 应用窗口宽度
    "window_height": 1080,    # 应用窗口高度
    "headless": True,         # 无头模式(不显示图形界面)
    "hide_ui": False,         # 显示UI界面
    "renderer": "RaytracedLighting",  # 使用光线追踪渲染器
    "display_options": 3286,  # 显示选项(默认显示网格)
}

# 启动Omniverse仿真应用
kit = SimulationApp(launch_config=CONFIG)

from isaacsim.core.utils.extensions import enable_extension

# 设置Livestream相关参数
kit.set_setting("/app/window/drawMouse", True)  # 在流媒体中显示鼠标光标

# 启用WebRTC Livestream扩展(支持浏览器实时查看)
enable_extension("omni.kit.livestream.webrtc")

from isaacsim.core.api.objects import DynamicCuboid
from isaacsim.core.utils.stage import add_reference_to_stage
from isaacsim.robot.manipulators import SingleManipulator
from isaacsim.robot.manipulators.examples.franka.controllers.pick_place_controller import PickPlaceController
from isaacsim.robot.manipulators.grippers import ParallelGripper
from isaacsim.storage.native import get_assets_root_path

5.4.1 初始化World且定义单位长度¶

World(世界)是仿真全局管理者,它内部已包含Scene(场景属性),初始化World不仅把世界进行初始化,同时也把场景初始化,后续可通过World的scene场景属性进行添加物品。

In [ ]:
import numpy as np
from isaacsim.core.api import World

my_world = World(stage_units_in_meters=1.0, physics_dt=1.0 / 120.0, rendering_dt=1.0 / 60.0)
my_world.initialize_physics()
print(f"物理时间步长: {my_world.get_physics_dt()} 秒")
print(f"渲染时间步长: {my_world.get_rendering_dt()} 秒")

5.4.2 添加角色对象至场景内¶

场景 (Scene) 可以理解为世界中的子集,主要是将关联的物体归组进行管理。

注意:因为世界(World)包含场景(Scene)属性,因此本示例使用World的Scene属性添加角色对象。

  1. 添加地面

    场景(Scene)已包含添加默认地面的方法,可通过World对象的Scene属性直接调用。

In [ ]:
# 添加默认地面
ground_plane = my_world.scene.add_default_ground_plane()
# 输出地面路径
print(f"地平面的路径是: {ground_plane.prim_path}")
  1. 添加立方体

    与5.3扩展部分脚本化相同,也是通过刚体相关API引入带刚体性质的立方体类进行创建对象,创建后的立方体对象直接添加至场景内。

In [ ]:
from isaacsim.core.api.objects import DynamicCuboid

# 添加立方体
cube = my_world.scene.add(
    DynamicCuboid(
        name="cube",
        position=np.array([0.3, 0.3, 0.3]),
        prim_path="/World/Cube",
        scale=np.array([0.0515, 0.0515, 0.0515]),
        size=1.0,
        color=np.array([0, 0, 1]),
    )
)
# 输出物体路径
print(f"物体的路径是: {cube.prim_path}")
  1. 添加Franka机械臂至场景内
In [ ]:
# 获取Isaac Sim 官方资产地址
from isaacsim.storage.native import get_assets_root_path
assets_root_path = get_assets_root_path()
print("assets_root_path:" + assets_root_path)

# 加载机械臂usd模型至场景"/World/Franka"路径
from isaacsim.core.utils.stage import add_reference_to_stage
asset_path = assets_root_path + "/Isaac/Robots/Franka/franka_alt_fingers.usd"
add_reference_to_stage(usd_path=asset_path, prim_path="/World/Franka")
print("机械臂模型加载成功!")

5.4.3 定义Franka机械臂夹爪及控制器¶

  1. 定义夹爪
In [ ]:
# 配置平行夹爪
from isaacsim.robot.manipulators.grippers import ParallelGripper

gripper = ParallelGripper(
    end_effector_prim_path="/World/Franka/panda_rightfinger",  # 夹爪末端效应器路径
    joint_prim_names=["panda_finger_joint1", "panda_finger_joint2"],  # 夹爪关节名称
    joint_opened_positions=np.array([0.05, 0.05]),  # 夹爪张开时关节位置(此处表示夹爪张开时间隙为 5cm)
    joint_closed_positions=np.array([0.0, 0.0]),    # 夹爪闭合时关节位置(此处表示夹爪闭合时间隙为 0cm)
    action_deltas=np.array([0.01, 0.01])            # 每次移动的步长夹爪增量为 1cm
)
  1. 定义控制器

    通过SingleManipulator类定义Franka机械臂控制器。定义控制器时要配置机械臂Prim路径、机械臂名称、机械臂末端执行器Prim名称、夹爪对象。定义控制器且添加至场景后,Franka不仅只是一个模型,也会赋予操控能力。

In [ ]:
from isaacsim.robot.manipulators import SingleManipulator

my_franka = my_world.scene.add(
    SingleManipulator(
        prim_path="/World/Franka",  # 机械臂Prim路径
        name="my_franka", # 机械臂名称
        end_effector_prim_name="panda_rightfinger", #机械臂末端执行器Prim名称
        gripper=gripper # 夹爪对象
    )
)
  1. 配置夹爪初始状态

    赋予Franka机械臂控制器后,可以配置其夹爪默认状态了,后续实现画面更新后,可以通过"Isaac Sim Streaming WebRTC Client"连接至Isaac Sim应用程序,观察Franka加载初始状态按以下配置的打开状态。

In [ ]:
my_franka.gripper.set_default_state(my_franka.gripper.joint_opened_positions)

5.4.4 定义Franka机械臂夹取放置任务控制器¶

5.4.3配置Franka控制器仅让Franka拥有操控能力,但是它未定义具体任务逻辑,因此,类似地,通过Isaac Sim封装的PickPlaceController夹取放置任务控制器,让Franka实现夹取立方体、摆放至目标位置的任务。在后续实现任务执行(即实时渲染)时,可在每一帧让这一控制器计算Franka当前要完成的内容(类似于大语言模型推理,每一帧推理出当前帧要执行的内容),且作用于Franka机械臂上,从而实现任务。

In [ ]:
from isaacsim.robot.manipulators.examples.franka.controllers.pick_place_controller import PickPlaceController

# 初始化夹取和放置控制器
my_controller = PickPlaceController(
    name="pick_place_controller", # 控制器名称
    gripper=my_franka.gripper, # 夹爪
    robot_articulation=my_franka # 关节系统
)

5.4.5 渲染开始¶

以下将实时更新画面,且推进Franka任务执行,执行以下代码后可通过Isaac Sim Streaming WebRTC Client连接至Isaac Sim应用程序,查看渲染结果。

注:由于以下代码执行后,Franka机械臂会马上执行夹取、放置任务。如连接至Isaac Sim应用程序发现Franka未运动,可点击"Play"按钮,让任务重新执行。

In [ ]:
# 获取机械臂控制器
articulation_controller = my_franka.get_articulation_controller()

# 定义一个标识,用于判断是否需要重置仿真场景
reset_needed = False
# 停止仿真,准备进入主循环
my_world.stop()

# 当仿真引擎处于运行状态时,循环持续
while kit.is_running():
    # 每帧推进仿真时间,同时渲染更新场景
    my_world.step(render=True)

    # 如果场景已停止,并且尚未重置
    if my_world.is_stopped() and not reset_needed:
        # 将重置标志置为 True,下一帧进行重置
        reset_needed = True
    # 当仿真正在运行时
    if my_world.is_playing():
        # 如果需要重置场景
        if reset_needed:
            # 重置仿真世界
            my_world.reset() 
            # 重置控制器状态
            my_controller.reset() 
            # 重置完成,标记为 False
            reset_needed = False

        # 获取当前仿真环境的观测数据
        observations = my_world.get_observations()

        # 根据当前状态和目标位置,计算下一步动作
        actions = my_controller.forward(
            # 获取物体抓取点
            picking_position=cube.get_local_pose()[0],  
            # 放置位置
            placing_position=np.array([-0.3, -0.3, 0.0515 / 2.0]), 
            # 当前关节位置
            current_joint_positions=my_franka.get_joint_positions(),  
            # 末端偏移量
            end_effector_offset=np.array([0, 0.005, 0]), 
        )

        # 将计算好的动作应用到机械臂仿真中
        articulation_controller.apply_action(actions)
    # 更新仿真引擎状态(包括渲染、逻辑更新等)
    kit.update()

5.4.6 效果展示¶

通过Isaac Sim WebRTC Streaming Client连接 Isaac Sim(参考 01 章),查看效果。

Franka机械臂加载至仿真世界且夹取方块。

常用API示例代码运行效果

5.4.7 关闭Isaac Sim¶

当效果验证完毕,需关闭Isaac Sim,防止Isaac Sim未能正常停止,启动其他Isaac Sim进程时无法正常连接。

In [ ]:
kit.close()

5.5 Isaac Sim Python API介绍¶

本课程的案例主要介绍了机械臂机器人和轮式机器人相关Python API,但Isaac Sim具有十分完备的Pytho API,Isaac Sim API文档链接如下:https://docs.isaacsim.omniverse.nvidia.com/latest/py/index.html。

在Isaac Sim容器(即本课程运行的容器)中,已提供了Isaac Sim核心API的示例代码,具体目录为/isaac-sim/standalone_examples,遇到实际开发任务但本课程未涉及时,可以先阅读Isaac Sim API文档,确定将要使用的API。再运行相关示例代码学会API使用。

注:示例代码默认启动Isaac Sim的方式不是使用无头模式,在Isaac Sim容器运行可能会出现问题,建议把Isaac Sim应用程序启动部分调整为与5.4.0一致。

以下是调整Isaac Sim应用程序启动部分后的示例。

Isaac Sim提供的示例代码(以isaacsim.robot.wheeled_robots.examples为例)如下。

注:以下代码无法直接在Isaac Sim容器内运行。

import argparse

from isaacsim import SimulationApp

parser = argparse.ArgumentParser()
parser.add_argument("--test", default=False, action="store_true", help="Run in test mode")
args, unknown = parser.parse_known_args()


simulation_app = SimulationApp({"headless": False})

import carb
import numpy as np
from isaacsim.core.api import World
from isaacsim.robot.wheeled_robots.controllers.differential_controller import DifferentialController
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
from isaacsim.storage.native import get_assets_root_path

my_world = World(stage_units_in_meters=1.0)
assets_root_path = get_assets_root_path()
if assets_root_path is None:
    carb.log_error("Could not find Isaac Sim assets folder")
jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
my_jetbot = my_world.scene.add(
    WheeledRobot(
        prim_path="/World/Jetbot",
        name="my_jetbot",
        wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],
        create_robot=True,
        usd_path=jetbot_asset_path,
        position=np.array([0, 0.0, 2.0]),
    )
)
my_world.scene.add_default_ground_plane()
my_controller = DifferentialController(name="simple_control", wheel_radius=0.03, wheel_base=0.1125)
my_world.reset()

i = 0
reset_needed = False
while simulation_app.is_running():
    my_world.step(render=True)
    if my_world.is_stopped() and not reset_needed:
        reset_needed = True
    if my_world.is_playing():
        if reset_needed:
            my_world.reset()
            my_controller.reset()
            reset_needed = False
        if i >= 0 and i < 1000:
            # forward
            my_jetbot.apply_wheel_actions(my_controller.forward(command=[0.05, 0]))
            print(my_jetbot.get_linear_velocity())
        elif i >= 1000 and i < 1300:
            # rotate
            my_jetbot.apply_wheel_actions(my_controller.forward(command=[0.0, np.pi / 12]))
            print(my_jetbot.get_angular_velocity())
        elif i >= 1300 and i < 2000:
            # forward
            my_jetbot.apply_wheel_actions(my_controller.forward(command=[0.05, 0]))
        elif i == 2000:
            i = 0
        i += 1
    if args.test is True:
        break

my_world.stop()
simulation_app.close()

调整后的代码如下。

注:以下代码可以在Isaac Sim容器内运行,主要把SimulationApp对象配置进行调整,设置为无头模式,而且开启鼠标键盘控制和WebRTC连接。

In [ ]:
import argparse

from isaacsim import SimulationApp

parser = argparse.ArgumentParser()
parser.add_argument("--test", default=False, action="store_true", help="Run in test mode")
args, unknown = parser.parse_known_args()

from isaacsim import SimulationApp

# 调整后的配置
CONFIG = {
    "width": 1280,
    "height": 720,
    "window_width": 1920,
    "window_height": 1080,
    "headless": True,
    "hide_ui": False,  # Show the GUI
    "renderer": "RaytracedLighting",
    "display_options": 3286,  # Set display options to show default grid
}

simulation_app = SimulationApp(launch_config=CONFIG)

from isaacsim.core.utils.extensions import enable_extension

# 开启鼠标键盘输入
simulation_app.set_setting("/app/window/drawMouse", True)

# 开启WebRTC连接
enable_extension("omni.kit.livestream.webrtc")

import carb
import numpy as np
from isaacsim.core.api import World
from isaacsim.robot.wheeled_robots.controllers.differential_controller import DifferentialController
from isaacsim.robot.wheeled_robots.robots import WheeledRobot
from isaacsim.storage.native import get_assets_root_path

my_world = World(stage_units_in_meters=1.0)
assets_root_path = get_assets_root_path()
if assets_root_path is None:
    carb.log_error("Could not find Isaac Sim assets folder")
jetbot_asset_path = assets_root_path + "/Isaac/Robots/Jetbot/jetbot.usd"
my_jetbot = my_world.scene.add(
    WheeledRobot(
        prim_path="/World/Jetbot",
        name="my_jetbot",
        wheel_dof_names=["left_wheel_joint", "right_wheel_joint"],
        create_robot=True,
        usd_path=jetbot_asset_path,
        position=np.array([0, 0.0, 2.0]),
    )
)
my_world.scene.add_default_ground_plane()
my_controller = DifferentialController(name="simple_control", wheel_radius=0.03, wheel_base=0.1125)
my_world.reset()

i = 0
reset_needed = False
while simulation_app.is_running():
    my_world.step(render=True)
    if my_world.is_stopped() and not reset_needed:
        reset_needed = True
    if my_world.is_playing():
        if reset_needed:
            my_world.reset()
            my_controller.reset()
            reset_needed = False
        if i >= 0 and i < 1000:
            # forward
            my_jetbot.apply_wheel_actions(my_controller.forward(command=[0.05, 0]))
            print(my_jetbot.get_linear_velocity())
        elif i >= 1000 and i < 1300:
            # rotate
            my_jetbot.apply_wheel_actions(my_controller.forward(command=[0.0, np.pi / 12]))
            print(my_jetbot.get_angular_velocity())
        elif i >= 1300 and i < 2000:
            # forward
            my_jetbot.apply_wheel_actions(my_controller.forward(command=[0.05, 0]))
        elif i == 2000:
            i = 0
        i += 1
    if args.test is True:
        break

my_world.stop()
simulation_app.close()