从IsaacGymEnvs迁移#

IsaacGymEnvs 是一个为 Isaac Gym 预览版 设计的强化学习框架。由于 IsaacGymEnvs 和 Isaac Gym 预览版目前已经弃用,以下指南将介绍 IsaacGymEnvs 和 Isaac Lab 之间的主要区别,以及 Isaac Gym 预览版和 Isaac Sim 之间 API 的不同之处。

备注

以下更改是针对Isaac Lab 1.0版本的发布。请参考 release notes 查看未来版本的任何更改。

任务配置设置#

在 IsaacGymEnvs 中,任务配置文件是以 .yaml 格式定义的。在 Isaac Lab 中,现在使用专门的 Python 类 configclass 来指定配置。 configclass 模块提供了一个包装器,位于 Python 的 dataclasses 模块之上。每个环境应指定其自己的配置类,该类被 @configclass 注释,其继承自 DirectRLEnvCfg ,其中可以包括仿真参数、环境场景参数、机器人参数和任务特定参数。

以下是一个任务配置类的示例骨架:

from isaaclab.envs import DirectRLEnvCfg
from isaaclab.scene import InteractiveSceneCfg
from isaaclab.sim import SimulationCfg

@configclass
class MyEnvCfg(DirectRLEnvCfg):
   # simulation
   sim: SimulationCfg = SimulationCfg()
   # robot
   robot_cfg: ArticulationCfg = ArticulationCfg()
   # scene
   scene: InteractiveSceneCfg = InteractiveSceneCfg()
   # env
   decimation = 2
   episode_length_s = 5.0
   action_space = 1
   observation_space = 4
   state_space = 0
   # task-specific parameters
   ...

仿真配置#

与仿真有关的参数被定义为 SimulationCfg 类的一部分,这是一个 configclass 模块,包含诸如 dtdevicegravity 等仿真参数。每个任务配置都必须有一个名为 sim 的变量,其类型为 SimulationCfg

在 Isaac Lab 中, substeps 的使用已被仿真 dtdecimation 参数的组合取代。例如,在 IsaacGymEnvs 中,具有 dt=1/60substeps=2 等效于使用 dt=1/120 进行 2 次仿真步骤,但在 1/60 秒运行任务步骤。 decimation 参数是一个任务参数,控制每个任务(或 RL)步骤所需的仿真步骤数量,取代了 IsaacGymEnvs 中的 controlFrequencyInv 参数。因此,在 Isaac Lab 中,相同的设置将变为 dt=1/120decimation=2

在 Isaac Sim 中,物理仿真参数,例如 num_position_iterationsnum_velocity_iterationscontact_offsetrest_offsetbounce_threshold_velocitymax_depenetration_velocity 等都可以针对每个角色进行指定。这些参数已从 physx 仿真配置移到每个单独的关节和刚体配置中。

当在 GPU 上运行仿真时,PhysX 中的缓冲区需要预先分配以计算和存储诸如接触、碰撞和汇总对等信息。这些缓冲区可能需要根据环境的复杂性、预期接触和碰撞数量以及环境中的角色数量进行调整。 PhysxCfg 类提供了访问设置 GPU 缓冲区维度的功能。

# IsaacGymEnvs
sim:

  dt: 0.0166 # 1/60 s
  substeps: 2
  up_axis: "z"
  use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
  gravity: [0.0, 0.0, -9.81]
  physx:
    num_threads: ${....num_threads}
    solver_type: ${....solver_type}
    use_gpu: ${contains:"cuda",${....sim_device}}
    num_position_iterations: 4
    num_velocity_iterations: 0
    contact_offset: 0.02
    rest_offset: 0.001
    bounce_threshold_velocity: 0.2
    max_depenetration_velocity: 100.0
    default_buffer_size_multiplier: 2.0
    max_gpu_contact_pairs: 1048576 # 1024*1024
    num_subscenes: ${....num_subscenes}
    contact_collection: 0
# IsaacLab
sim: SimulationCfg = SimulationCfg(
   device = "cuda:0" # can be "cpu", "cuda", "cuda:<device_id>"
   dt=1 / 120,
   # decimation will be set in the task config
   # up axis will always be Z in isaac sim
   # use_gpu_pipeline is deduced from the device
   gravity=(0.0, 0.0, -9.81),
   physx: PhysxCfg = PhysxCfg(
       # num_threads is no longer needed
       solver_type=1,
       # use_gpu is deduced from the device
       max_position_iteration_count=4,
       max_velocity_iteration_count=0,
       # moved to actor config
       # moved to actor config
       bounce_threshold_velocity=0.2,
       # moved to actor config
       # default_buffer_size_multiplier is no longer needed
       gpu_max_rigid_contact_count=2**23
       # num_subscenes is no longer needed
       # contact_collection is no longer needed
))

场景配置#

InteractiveSceneCfg 类可用于指定与场景相关的参数,例如环境数量和环境之间的间距。每个任务配置必须有一个名为 scene 的变量,其类型为 InteractiveSceneCfg

# IsaacGymEnvs
env:
  numEnvs: ${resolve_default:512,${...num_envs}}
  envSpacing: 4.0
# IsaacLab
scene: InteractiveSceneCfg = InteractiveSceneCfg(
   num_envs=512,
   env_spacing=4.0)

任务配置#

每个环境应指定其自己的配置类,其中包含任务特定参数,例如观测和动作缓冲区的维度。奖励项缩放参数也可以在配置类中指定。

每个环境配置必须设置以下参数:

decimation = 2
episode_length_s = 5.0
action_space = 1
observation_space = 4
state_space = 0

请注意,最大剧集长度参数(现在为 episode_length_s )是以秒为单位,而不是 IsaacGymEnvs 中的步数。要在步数和秒之间转换,请使用以下方程式:episode_length_s = dt * decimation * num_steps

RL 配置设置#

rl_games 库的 RL 配置文件可以继续在 Isaac Lab 中的 .yaml 文件中定义。配置文件的大部分内容可以直接从 IsaacGymEnvs 复制过来。请注意,在 Isaac Lab 中,我们不使用 hydra 来解决配置文件中的相对路径。请将任何相对路径(例如 ${....device} )替换为参数的实际值。

此外,观测和动作的剪裁范围已移动到 RL 配置文件中。所有在 IsaacGymEnvs 任务配置文件中定义的 clipObservationsclipActions 参数都应在 Isaac Lab 的 RL 配置文件中进行移动。

IsaacGymEnvs 任务配置

Isaac Lab RL 配置

# IsaacGymEnvs
env:
  clipObservations: 5.0
  clipActions: 1.0
# IsaacLab
params:
  env:
    clip_observations: 5.0
    clip_actions: 1.0

环境创建#

在 IsaacGymEnvs 中,环境创建通常包括四个组件: 使用 create_sim() 创建 sim 对象,创建地面平面,从 MJCF 或 URDF 文件导入资产,最后通过循环遍历每个环境并将actors添加到环境中创建环境。

Isaac Lab 不再需要调用 create_sim() 方法来检索 sim 对象。相反,仿真上下文会自动由框架检索。也不再需要将 sim 作为仿真 API 的参数使用。

在 Isaac Lab 中,可以通过实现 _setup_scene() 方法来替代 create_sim() 。这种方法可用于向场景中添加actors、添加地面平面、克隆actors,并添加任何其他可选对象到场景中,如灯光。

IsaacGymEnvs

Isaac Lab

def create_sim(self):
  # set the up axis to be z-up
  self.up_axis = self.cfg["sim"]["up_axis"]

  self.sim = super().create_sim(self.device_id, self.graphics_device_id,
                                  self.physics_engine, self.sim_params)
  self._create_ground_plane()
  self._create_envs(self.num_envs, self.cfg["env"]['envSpacing'],
                      int(np.sqrt(self.num_envs)))
def _setup_scene(self):
  self.cartpole = Articulation(self.cfg.robot_cfg)
  # add ground plane
  spawn_ground_plane(prim_path="/World/ground", cfg=GroundPlaneCfg()
  # clone, filter, and replicate
  self.scene.clone_environments(copy_from_source=False)
  self.scene.filter_collisions(global_prim_paths=[])
  # add articulation to scene
  self.scene.articulations["cartpole"] = self.cartpole
  # add lights
  light_cfg = sim_utils.DomeLightCfg(intensity=2000.0)
  light_cfg.func("/World/Light", light_cfg)

地面平面#

在 Isaac Lab 中,大多数环境创建过程已简化为使用 configclass 模块中的配置。

可以使用 TerrainImporterCfg 类来定义地面平面。

from isaaclab.terrains import TerrainImporterCfg

terrain = TerrainImporterCfg(
     prim_path="/World/ground",
     terrain_type="plane",
     collision_group=-1,
     physics_material=sim_utils.RigidBodyMaterialCfg(
         friction_combine_mode="multiply",
         restitution_combine_mode="multiply",
         static_friction=1.0,
         dynamic_friction=1.0,
         restitution=0.0,
     ),
 )

然后,可以通过引用 TerrainImporterCfg 对象将地形添加到场景中的 _setup_scene(self) 中:

Actors#

Isaac Lab 和 Isaac Sim 都使用 USD(Universal Scene Description) 库来描述场景。在 MJCF 和 URDF 格式中定义的资产可以使用导入工具导入到 USD,导入工具的使用方法请参见 导入新资产 教程。

每个关节和刚体actors都可以有自己的配置类。 ArticulationCfg 类可用于定义关节actors的参数,包括文件路径、仿真参数、执行器属性和初始状态。

ArticulationCfg 中,可以使用 spawn 属性通过指定机器人文件的路径将机器人添加到场景中。此外,可以使用 RigidBodyPropertiesCfg 来为关节中的刚体指定仿真属性。类似地,可以使用 ArticulationRootPropertiesCfg 类为关节指定仿真属性。关节属性现在作为 actuators 字典的一部分进行指定,其中使用 ImplicitActuatorCfg 。具有相同属性的关节可以分组为正则表达式或作为名称或表达式列表提供。

通过简单调用 self.cartpole = Articulation(self.cfg.robot_cfg) 将actors添加到场景,其中 self.cfg.robot_cfg 是一个 ArticulationCfg 对象。初始化后,还应通过调用 self.scene.articulations["cartpole"] = self.cartpole 将其添加到 InteractiveScene 中,以便 InteractiveScene 可以在场景中遍历actors以向仿真写入值并重置。

Actors的仿真参数#

在 Isaac Gym 预览版和 Isaac Sim 之间,与刚体和关节相关的一些仿真参数可能具有不同的默认值。建议确保 USD 资产的默认值适用于资产。

例如, RigidBodyAPI 中以下参数可能在 Isaac Gym 预览版和 Isaac Sim 中不同:

RigidBodyAPI 参数

Isaac Sim 中的默认值

Isaac Gym 预览版中的默认值

线性阻尼

0.00

0.00

角阻尼

0.05

0.0

最大线性速度

inf

1000

最大角速度

5729.58008 (度/秒)

64.0 (弧度/秒)

最大接触冲量

inf

1e32

JointAPIDriveAPI 的关节参数可以进行修改。请注意,Isaac Sim UI假定角度的单位为度。特别值得注意的是,在Isaac Sim UI中, DriveAPI 中的 DampingStiffness 参数的单位为 1/deg ,但在Isaac Gym Preview Release中为 1/rad

关节参数

Isaac Sim 中的默认值

Isaac Gym Preview Releases中的默认值

最大关节速度

1000000.0 (度)

100.0 (弧度)

For more details on performing thorough simulation comparisons between Isaac Gym and Isaac Lab, please refer to the 比较 Isaac Gym 和 Isaac Lab 之间的仿真 section.

克隆器#

Isaac Sim引入了 克隆器 概念,这是一个专为在场景创建过程中复制而设计的类。在IsaacGymEnvs中,必须通过循环遍历环境的数量来创建场景。在每次迭代中,将actors添加到每个环境中,并需要缓存它们的句柄。Isaac Lab通过使用 克隆器 API来消除循环遍历环境的需求。场景创建过程如下:

  1. 构建单个环境(如果环境数量=1,则场景将是什么样子)

  2. 调用 clone_environments() 来复制单个环境

  3. 调用 filter_collisions() 来过滤环境之间的碰撞(如果需要)

# construct a single environment with the Cartpole robot
self.cartpole = Articulation(self.cfg.robot_cfg)
# clone the environment
self.scene.clone_environments(copy_from_source=False)
# filter collisions
self.scene.filter_collisions(global_prim_paths=[self.cfg.terrain.prim_path])

从仿真中访问状态#

Isaac Lab中访问物理状态的API需要创建 ArticulationRigidObject 对象。可以通过在上面部分概述的相应 ArticulationCfgRigidObjectCfg 配置来初始化不同关节或刚体的多个对象,以定义场景中的关节或刚体。这种方法消除了检索体句柄以为场景中的特定体片段状态的需要。

self._robot = Articulation(self.cfg.robot)
self._cabinet = Articulation(self.cfg.cabinet)
self._object = RigidObject(self.cfg.object_cfg)

在Isaac Lab中,我们还移除了 acquirerefresh APIs。物理状态可以直接使用定义为关节和刚体对象的API进行应用或检索。

在Isaac Lab中提供的API现在不再需要显式地包装和解包底层缓冲区。API现在可以直接使用张量来读取和写入数据。

IsaacGymEnvs

Isaac Lab

dof_state_tensor = self.gym.acquire_dof_state_tensor(self.sim)
self.dof_state = gymtorch.wrap_tensor(dof_state_tensor)
self.gym.refresh_dof_state_tensor(self.sim)
self.joint_pos = self._robot.data.joint_pos
self.joint_vel = self._robot.data.joint_vel

请注意Isaac Gym Preview Release和Isaac Lab中API之间的一些命名差异。大多数与 自由度 有关的API在Isaac Lab中已更名为 joint 。在Isaac Lab中,API也不再遵循在命名中明确的 `` _tensors`` 或 _tensor_indexed 后缀。API的索引版本现在通过可选的 indices 参数隐式发生。

Isaac Lab中的大多数API还提供了指定 indices 参数的选项,该参数可在为一些环境的子集读取或写入数据时使用。请注意,使用 indices 参数设置状态时,状态缓冲区的形状应与 indices 列表的维度相匹配。

IsaacGymEnvs

Isaac Lab

env_ids_int32 = env_ids.to(dtype=torch.int32)
self.gym.set_dof_state_tensor_indexed(self.sim,
    gymtorch.unwrap_tensor(self.dof_state),
    gymtorch.unwrap_tensor(env_ids_int32), len(env_ids_int32))
self._robot.write_joint_state_to_sim(joint_pos, joint_vel,
                                 joint_ids, env_ids)

四元数约定#

Isaac Lab和Isaac Sim都采用 wxyz 作为四元数约定。但是,Isaac Gym Preview Release中使用的四元数约定是 xyzw 。请记住,在索引旋转数据时,将所有四元数切换为使用 xyzw 约定。类似地,在传递给Isaac Lab API之前,请确保所有四元数均为 wxyz

关节顺序#

Isaac Sim和Isaac Lab中的物理仿真假定给定运动树中关节的顺序是广度优先顺序。然而,Isaac Gym Preview Release中假定关节运动树中关节的顺序是深度优先顺序。这意味着根据它们的顺序对关节进行索引在IsaacGymEnvs和Isaac Lab中可能不同。

在Isaac Lab中,可以使用 Articulation.data.joint_names 获取关节名称列表,这也将与Articulation中关节的顺序对应。

创建新环境#

Isaac Lab中的每个环境都应位于其自己的目录中,遵循以下结构:

my_environment/
    - agents/
        - __init__.py
        - rl_games_ppo_cfg.py
    - __init__.py
    my_env.py
  • my_environment 是任务的根目录。

  • my_environment/agents 是包含任务的所有RL配置文件的目录。Isaac Lab支持多个RL库,每个库都可以有自己的配置文件。

  • my_environment/__init__.py 是注册环境到Gymnasium接口的主文件。这允许训练和推理脚本通过名称找到任务。此文件的内容应如下所示:

import gymnasium as gym

from . import agents
from .cartpole_env import CartpoleEnv, CartpoleEnvCfg

##
# Register Gym environments.
##

gym.register(
    id="Isaac-Cartpole-Direct-v0",
    entry_point="isaaclab_tasks.direct_workflow.cartpole:CartpoleEnv",
    disable_env_checker=True,
    kwargs={
        "env_cfg_entry_point": CartpoleEnvCfg,
        "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml"
    },
)
  • my_environment/my_env.py 是实现任务逻辑和环境的任务配置类的主要Python脚本。

任务逻辑#

在Isaac Lab中, post_physics_step 函数已移至基类中的框架。任务不需要实现此方法,但如果需要不同的工作流程,则可以选择覆盖它。

默认情况下,Isaac Lab遵循以下逻辑流程:

IsaacGymEnvs

Isaac Lab

pre_physics_step
  |-- apply_action


post_physics_step
  |-- reset_idx()
  |-- compute_observation()
  |-- compute_reward()
pre_physics_step
  |-- _pre_physics_step(action)
  |-- _apply_action()

post_physics_step
  |-- _get_dones()
  |-- _get_rewards()
  |-- _reset_idx()
  |-- _get_observations()

在Isaac Lab中,我们还将 pre_physics_step API与从策略中处理操作的 apply_action API分开,后者将操作设置到仿真中。当使用 decimation 时,这样可以更灵活地控制何时将操作写入仿真。每步之前将调用一次 pre_physics_step 来处理每个RL步骤, apply_actions 将在每个仿真步骤调用 decimation 次。

采用这种方法,重置是根据当前步骤的操作执行的,而不是前一步骤。在重置后,观测也将使用正确的状态计算。

我们还进行了一些API的重命名:

  • create_sim(self) --> _setup_scene(self)

  • pre_physics_step(self, actions) --> _pre_physics_step(self, actions)_apply_action(self)

  • reset_idx(self, env_ids) --> _reset_idx(self, env_ids)

  • compute_observations(self) --> _get_observations(self) - _get_observations() 现在应返回一个字典 {"policy": obs}

  • compute_reward(self) --> _get_rewards(self) - _get_rewards() 现在应返回奖励缓冲区

  • post_physics_step(self) --> 移至基类

  • 此外,Isaac Lab要求实现 _is_done(self) ,它应返回两个缓冲区: 重置缓冲区和超时缓冲区。

将所有内容整合#

Cartpole环境在此处完整展示,以充分显示IsaacGymEnvs实现与Isaac Lab实现之间的比较。

任务配置#

IsaacGymEnvs

Isaac Lab

# used to create the object
name: Cartpole

physics_engine: ${..physics_engine}

# if given, will override the device setting in gym.
env:
  numEnvs: ${resolve_default:512,${...num_envs}}
  envSpacing: 4.0
  resetDist: 3.0
  maxEffort: 400.0

  clipObservations: 5.0
  clipActions: 1.0

  asset:
    assetRoot: "../../assets"
    assetFileName: "urdf/cartpole.urdf"

  enableCameraSensors: False

sim:
  dt: 0.0166 # 1/60 s
  substeps: 2
  up_axis: "z"
  use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
  gravity: [0.0, 0.0, -9.81]
  physx:
    num_threads: ${....num_threads}
    solver_type: ${....solver_type}
    use_gpu: ${contains:"cuda",${....sim_device}}
    num_position_iterations: 4
    num_velocity_iterations: 0
    contact_offset: 0.02
    rest_offset: 0.001
    bounce_threshold_velocity: 0.2
    max_depenetration_velocity: 100.0
    default_buffer_size_multiplier: 2.0
    max_gpu_contact_pairs: 1048576 # 1024*1024
    num_subscenes: ${....num_subscenes}
    contact_collection: 0
@configclass
class CartpoleEnvCfg(DirectRLEnvCfg):

    # simulation
    sim: SimulationCfg = SimulationCfg(dt=1 / 120)
    # robot
    robot_cfg: ArticulationCfg = CARTPOLE_CFG.replace(
        prim_path="/World/envs/env_.*/Robot")
    cart_dof_name = "slider_to_cart"
    pole_dof_name = "cart_to_pole"
    # scene
    scene: InteractiveSceneCfg = InteractiveSceneCfg(
        num_envs=4096, env_spacing=4.0, replicate_physics=True)
    # env
    decimation = 2
    episode_length_s = 5.0
    action_scale = 100.0  # [N]
    action_space = 1
    observation_space = 4
    state_space = 0
    # reset
    max_cart_pos = 3.0
    initial_pole_angle_range = [-0.25, 0.25]
    # reward scales
    rew_scale_alive = 1.0
    rew_scale_terminated = -2.0
    rew_scale_pole_pos = -1.0
    rew_scale_cart_vel = -0.01
    rew_scale_pole_vel = -0.005

任务设置#

Isaac Lab不再需要通过在IsaacGymEnvs中使用的 acquire_* APIs预初始化缓冲区。也不再需要 wrapunwrap 张量。

IsaacGymEnvs

Isaac Lab

class Cartpole(VecTask):

  def __init__(self, cfg, rl_device, sim_device, graphics_device_id,
   headless, virtual_screen_capture, force_render):
      self.cfg = cfg

      self.reset_dist = self.cfg["env"]["resetDist"]

      self.max_push_effort = self.cfg["env"]["maxEffort"]
      self.max_episode_length = 500

      self.cfg["env"]["numObservations"] = 4
      self.cfg["env"]["numActions"] = 1

      super().__init__(config=self.cfg,
         rl_device=rl_device, sim_device=sim_device,
         graphics_device_id=graphics_device_id, headless=headless,
         virtual_screen_capture=virtual_screen_capture,
         force_render=force_render)

      dof_state_tensor = self.gym.acquire_dof_state_tensor(self.sim)
      self.dof_state = gymtorch.wrap_tensor(dof_state_tensor)
      self.dof_pos = self.dof_state.view(
          self.num_envs, self.num_dof, 2)[..., 0]
      self.dof_vel = self.dof_state.view(
          self.num_envs, self.num_dof, 2)[..., 1]
class CartpoleEnv(DirectRLEnv):
  cfg: CartpoleEnvCfg
  def __init__(self, cfg: CartpoleEnvCfg,
          render_mode: str | None = None, **kwargs):

      super().__init__(cfg, render_mode, **kwargs)

      self._cart_dof_idx, _ = self.cartpole.find_joints(
          self.cfg.cart_dof_name)
      self._pole_dof_idx, _ = self.cartpole.find_joints(
          self.cfg.pole_dof_name)
      self.action_scale = self.cfg.action_scale

      self.joint_pos = self.cartpole.data.joint_pos
      self.joint_vel = self.cartpole.data.joint_vel

场景设置#

现在通过 Cloner API和在配置对象中指定角色属性来设置场景,以替代循环设置环境数量和设置任务实施中角色仿真参数的需求。

IsaacGymEnvs

Isaac Lab

def create_sim(self):
    # set the up axis to be z-up given that assets are y-up by default
    self.up_axis = self.cfg["sim"]["up_axis"]

    self.sim = super().create_sim(self.device_id,
        self.graphics_device_id, self.physics_engine,
        self.sim_params)
    self._create_ground_plane()
    self._create_envs(self.num_envs,
        self.cfg["env"]['envSpacing'],
        int(np.sqrt(self.num_envs)))

def _create_ground_plane(self):
    plane_params = gymapi.PlaneParams()
    # set the normal force to be z dimension
    plane_params.normal = (gymapi.Vec3(0.0, 0.0, 1.0)
        if self.up_axis == 'z'
        else gymapi.Vec3(0.0, 1.0, 0.0))
    self.gym.add_ground(self.sim, plane_params)

def _create_envs(self, num_envs, spacing, num_per_row):
    # define plane on which environments are initialized
    lower = (gymapi.Vec3(0.5 * -spacing, -spacing, 0.0)
        if self.up_axis == 'z'
        else gymapi.Vec3(0.5 * -spacing, 0.0, -spacing))
    upper = gymapi.Vec3(0.5 * spacing, spacing, spacing)

    asset_root = os.path.join(os.path.dirname(
        os.path.abspath(__file__)), "../../assets")
    asset_file = "urdf/cartpole.urdf"

    if "asset" in self.cfg["env"]:
        asset_root = os.path.join(os.path.dirname(
            os.path.abspath(__file__)),
            self.cfg["env"]["asset"].get("assetRoot", asset_root))
        asset_file = self.cfg["env"]["asset"].get(
            "assetFileName", asset_file)

    asset_path = os.path.join(asset_root, asset_file)
    asset_root = os.path.dirname(asset_path)
    asset_file = os.path.basename(asset_path)

    asset_options = gymapi.AssetOptions()
    asset_options.fix_base_link = True
    cartpole_asset = self.gym.load_asset(self.sim,
        asset_root, asset_file, asset_options)
    self.num_dof = self.gym.get_asset_dof_count(
        cartpole_asset)

    pose = gymapi.Transform()
    if self.up_axis == 'z':
        pose.p.z = 2.0
        pose.r = gymapi.Quat(0.0, 0.0, 0.0, 1.0)
    else:
        pose.p.y = 2.0
        pose.r = gymapi.Quat(
            -np.sqrt(2)/2, 0.0, 0.0, np.sqrt(2)/2)

    self.cartpole_handles = []
    self.envs = []
    for i in range(self.num_envs):
        # create env instance
        env_ptr = self.gym.create_env(
            self.sim, lower, upper, num_per_row
        )
        cartpole_handle = self.gym.create_actor(
            env_ptr, cartpole_asset, pose,
            "cartpole", i, 1, 0)

        dof_props = self.gym.get_actor_dof_properties(
            env_ptr, cartpole_handle)
        dof_props['driveMode'][0] = gymapi.DOF_MODE_EFFORT
        dof_props['driveMode'][1] = gymapi.DOF_MODE_NONE
        dof_props['stiffness'][:] = 0.0
        dof_props['damping'][:] = 0.0
        self.gym.set_actor_dof_properties(env_ptr, c
            artpole_handle, dof_props)

        self.envs.append(env_ptr)
        self.cartpole_handles.append(cartpole_handle)
def _setup_scene(self):
    self.cartpole = Articulation(self.cfg.robot_cfg)
    # add ground plane
    spawn_ground_plane(prim_path="/World/ground",
        cfg=GroundPlaneCfg())
    # clone, filter, and replicate
    self.scene.clone_environments(
        copy_from_source=False)
    self.scene.filter_collisions(
        global_prim_paths=[])
    # add articulation to scene
    self.scene.articulations["cartpole"] = self.cartpole
    # add lights
    light_cfg = sim_utils.DomeLightCfg(
        intensity=2000.0, color=(0.75, 0.75, 0.75))
    light_cfg.func("/World/Light", light_cfg)

CARTPOLE_CFG = ArticulationCfg(
    spawn=sim_utils.UsdFileCfg(
        usd_path=f"{ISAACLAB_NUCLEUS_DIR}/.../cartpole.usd",
        rigid_props=sim_utils.RigidBodyPropertiesCfg(
            rigid_body_enabled=True,
            max_linear_velocity=1000.0,
            max_angular_velocity=1000.0,
            max_depenetration_velocity=100.0,
            enable_gyroscopic_forces=True,
        ),
        articulation_props=sim_utils.ArticulationRootPropertiesCfg(
            enabled_self_collisions=False,
            solver_position_iteration_count=4,
            solver_velocity_iteration_count=0,
            sleep_threshold=0.005,
            stabilization_threshold=0.001,
        ),
    ),
    init_state=ArticulationCfg.InitialStateCfg(
        pos=(0.0, 0.0, 2.0),
        joint_pos={"slider_to_cart": 0.0, "cart_to_pole": 0.0}
    ),
    actuators={
        "cart_actuator": ImplicitActuatorCfg(
            joint_names_expr=["slider_to_cart"],
            effort_limit_sim=400.0,
            velocity_limit_sim=100.0,
            stiffness=0.0,
            damping=10.0,
        ),
        "pole_actuator": ImplicitActuatorCfg(
            joint_names_expr=["cart_to_pole"],
            effort_limit_sim=400.0, velocity_limit_sim=100.0,
            stiffness=0.0, damping=0.0
        ),
    },
)

物理步骤前后#

在IsaacGymEnvs中,由于GPU API的限制,当环境执行重置时,观测数据变得陈旧。在Isaac Lab中消除了这一限制,因此,任务遵循正确的工作流程,即应用行动、仿真步进、收集状态、计算结束、计算奖励、执行重置,最后计算观测。这个工作流程由框架自动完成,因此任务中不需要 post_physics_step API。但是,单个任务可以重写 step() API以控制工作流程。

IsaacGymEnvs

IsaacLab

def pre_physics_step(self, actions):
    actions_tensor = torch.zeros(
        self.num_envs * self.num_dof,
        device=self.device, dtype=torch.float)
    actions_tensor[::self.num_dof] = actions.to(
        self.device).squeeze() * self.max_push_effort
    forces = gymtorch.unwrap_tensor(actions_tensor)
    self.gym.set_dof_actuation_force_tensor(
        self.sim, forces)

def post_physics_step(self):
    self.progress_buf += 1

    env_ids = self.reset_buf.nonzero(
        as_tuple=False).squeeze(-1)
    if len(env_ids) > 0:
        self.reset_idx(env_ids)

    self.compute_observations()
    self.compute_reward()
def _pre_physics_step(self, actions: torch.Tensor) -> None:
    self.actions = self.action_scale * actions

def _apply_action(self) -> None:
    self.cartpole.set_joint_effort_target(
         self.actions, joint_ids=self._cart_dof_idx)

结束和重置#

在Isaac Lab中, dones_get_dones() 方法中计算,应返回两个变量:resetstime_out 。跟踪 progress_buf 已经移动到基类,并且现在被框架自动递增和重置。 progress_buf 变量也已重命名为 episode_length_buf

IsaacGymEnvs

Isaac Lab

def reset_idx(self, env_ids):
    positions = 0.2 * (torch.rand((len(env_ids), self.num_dof),
        device=self.device) - 0.5)
    velocities = 0.5 * (torch.rand((len(env_ids), self.num_dof),
        device=self.device) - 0.5)

    self.dof_pos[env_ids, :] = positions[:]
    self.dof_vel[env_ids, :] = velocities[:]

    env_ids_int32 = env_ids.to(dtype=torch.int32)
    self.gym.set_dof_state_tensor_indexed(self.sim,
        gymtorch.unwrap_tensor(self.dof_state),
        gymtorch.unwrap_tensor(env_ids_int32), len(env_ids_int32))
    self.reset_buf[env_ids] = 0
    self.progress_buf[env_ids] = 0
def _get_dones(self) -> tuple[torch.Tensor, torch.Tensor]:
    self.joint_pos = self.cartpole.data.joint_pos
    self.joint_vel = self.cartpole.data.joint_vel

    time_out = self.episode_length_buf >= self.max_episode_length - 1
    out_of_bounds = torch.any(torch.abs(
        self.joint_pos[:, self._cart_dof_idx]) > self.cfg.max_cart_pos,
        dim=1)
    out_of_bounds = out_of_bounds | torch.any(
        torch.abs(self.joint_pos[:, self._pole_dof_idx]) > math.pi / 2,
        dim=1)
    return out_of_bounds, time_out

def _reset_idx(self, env_ids: Sequence[int] | None):
    if env_ids is None:
        env_ids = self.cartpole._ALL_INDICES
    super()._reset_idx(env_ids)

    joint_pos = self.cartpole.data.default_joint_pos[env_ids]
    joint_pos[:, self._pole_dof_idx] += sample_uniform(
        self.cfg.initial_pole_angle_range[0] * math.pi,
        self.cfg.initial_pole_angle_range[1] * math.pi,
        joint_pos[:, self._pole_dof_idx].shape,
        joint_pos.device,
    )
    joint_vel = self.cartpole.data.default_joint_vel[env_ids]

    default_root_state = self.cartpole.data.default_root_state[env_ids]
    default_root_state[:, :3] += self.scene.env_origins[env_ids]

    self.joint_pos[env_ids] = joint_pos

    self.cartpole.write_root_pose_to_sim(
        default_root_state[:, :7], env_ids)
    self.cartpole.write_root_velocity_to_sim(
        default_root_state[:, 7:], env_ids)
    self.cartpole.write_joint_state_to_sim(
        joint_pos, joint_vel, None, env_ids)

观测#

在Isaac Lab中, _get_observations() API现在应返回一个包含 policy 键及观测缓冲为值的字典。对于非对称策略,字典还应包括一个包含状态缓冲的 critic 键。

IsaacGymEnvs

Isaac Lab

def compute_observations(self, env_ids=None):
    if env_ids is None:
        env_ids = np.arange(self.num_envs)

    self.gym.refresh_dof_state_tensor(self.sim)

    self.obs_buf[env_ids, 0] = self.dof_pos[env_ids, 0]
    self.obs_buf[env_ids, 1] = self.dof_vel[env_ids, 0]
    self.obs_buf[env_ids, 2] = self.dof_pos[env_ids, 1]
    self.obs_buf[env_ids, 3] = self.dof_vel[env_ids, 1]

    return self.obs_buf
def _get_observations(self) -> dict:
    obs = torch.cat(
        (
            self.joint_pos[:, self._pole_dof_idx[0]],
            self.joint_vel[:, self._pole_dof_idx[0]],
            self.joint_pos[:, self._cart_dof_idx[0]],
            self.joint_vel[:, self._cart_dof_idx[0]],
        ),
        dim=-1,
    )
    observations = {"policy": obs}
    return observations

奖励#

在Isaac Lab中,奖励方法 _get_rewards 应返回奖励缓冲区作为返回值。与IsaacGymEnvs类似,奖励函数中的计算也可以通过添加 @torch.jit.script 注释来使用pytorch jit执行。

IsaacGymEnvs

Isaac Lab

def compute_reward(self):
    # retrieve environment observations from buffer
    pole_angle = self.obs_buf[:, 2]
    pole_vel = self.obs_buf[:, 3]
    cart_vel = self.obs_buf[:, 1]
    cart_pos = self.obs_buf[:, 0]

    self.rew_buf[:], self.reset_buf[:] = compute_cartpole_reward(
        pole_angle, pole_vel, cart_vel, cart_pos,
        self.reset_dist, self.reset_buf,
        self.progress_buf, self.max_episode_length
    )

@torch.jit.script
def compute_cartpole_reward(pole_angle, pole_vel,
                            cart_vel, cart_pos,
                            reset_dist, reset_buf,
                            progress_buf, max_episode_length):

    reward = (1.0 - pole_angle * pole_angle -
        0.01 * torch.abs(cart_vel) -
        0.005 * torch.abs(pole_vel))

    # adjust reward for reset agents
    reward = torch.where(torch.abs(cart_pos) > reset_dist,
        torch.ones_like(reward) * -2.0, reward)
    reward = torch.where(torch.abs(pole_angle) > np.pi / 2,
        torch.ones_like(reward) * -2.0, reward)

    reset = torch.where(torch.abs(cart_pos) > reset_dist,
        torch.ones_like(reset_buf), reset_buf)
    reset = torch.where(torch.abs(pole_angle) > np.pi / 2,
        torch.ones_like(reset_buf), reset_buf)
    reset = torch.where(progress_buf >= max_episode_length - 1,
        torch.ones_like(reset_buf), reset)
def _get_rewards(self) -> torch.Tensor:
    total_reward = compute_rewards(
        self.cfg.rew_scale_alive,
        self.cfg.rew_scale_terminated,
        self.cfg.rew_scale_pole_pos,
        self.cfg.rew_scale_cart_vel,
        self.cfg.rew_scale_pole_vel,
        self.joint_pos[:, self._pole_dof_idx[0]],
        self.joint_vel[:, self._pole_dof_idx[0]],
        self.joint_pos[:, self._cart_dof_idx[0]],
        self.joint_vel[:, self._cart_dof_idx[0]],
        self.reset_terminated,
    )
    return total_reward

@torch.jit.script
def compute_rewards(
    rew_scale_alive: float,
    rew_scale_terminated: float,
    rew_scale_pole_pos: float,
    rew_scale_cart_vel: float,
    rew_scale_pole_vel: float,
    pole_pos: torch.Tensor,
    pole_vel: torch.Tensor,
    cart_pos: torch.Tensor,
    cart_vel: torch.Tensor,
    reset_terminated: torch.Tensor,
):
    rew_alive = rew_scale_alive * (1.0 - reset_terminated.float())
    rew_termination = rew_scale_terminated * reset_terminated.float()
    rew_pole_pos = rew_scale_pole_pos * torch.sum(
        torch.square(pole_pos), dim=-1)
    rew_cart_vel = rew_scale_cart_vel * torch.sum(
        torch.abs(cart_vel), dim=-1)
    rew_pole_vel = rew_scale_pole_vel * torch.sum(
        torch.abs(pole_vel), dim=-1)
    total_reward = (rew_alive + rew_termination
                     + rew_pole_pos + rew_cart_vel + rew_pole_vel)
    return total_reward

启动训练#

在Isaac Lab中启动训练,请使用以下命令:

python scripts/reinforcement_learning/rl_games/train.py --task=Isaac-Cartpole-Direct-v0 --headless

启动推理#

在Isaac Lab中启动推理,请使用以下命令:

python scripts/reinforcement_learning/rl_games/play.py --task=Isaac-Cartpole-Direct-v0 --num_envs=25 --checkpoint=<path/to/checkpoint>

Additional Resources#