从OmniIsaacGymEnvs迁移#

OmniIsaacGymEnvs 是一个使用 Isaac Sim 平台的强化学习框架。来自 OmniIsaacGymEnvs 的功能已经整合到 Isaac Lab 框架中。我们已经更新了 OmniIsaacGymEnvs 到 Isaac Sim 版本 4.0.0,以支持迁移到 Isaac Lab 的过程。今后,OmniIsaacGymEnvs 将被弃用,未来的开发将继续在 Isaac Lab 中进行。

备注

以下更改针对于 Isaac Lab 1.0 发布版本。请参考 release notes 以获取未来发布版本的任何更改信息。

任务配置设置#

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

下面是任务配置类的示例骨架:

from omni.isaac.lab.envs import DirectRLEnvCfg
from omni.isaac.lab.scene import InteractiveSceneCfg
from omni.isaac.lab.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
   num_actions = 1
   num_observations = 4
   num_states = 0
   # task-specific parameters
   ...

模拟配置#

与模拟相关的参数是作为 SimulationCfg 类的一部分进行定义的,这是一个 configclass 模块,包含模拟参数,如 dtdevicegravity 。每个任务配置必须定义一个名为 sim 的变量,它包含类型 SimulationCfg

关节和刚体的仿真参数,例如 num_position_iterationsnum_velocity_iterationscontact_offsetrest_offsetbounce_threshold_velocitymax_depenetration_velocity ,可以在每个单独的关节和刚体的配置类中以每个角色为基础进行指定。

在使用 GPU 运行仿真时,PhysX 中的缓冲区需要预先分配,用于计算和存储诸如接触、碰撞和聚合对等信息。这些缓冲区可能需要根据环境复杂性、预期接触和碰撞数量以及环境中的演员数量进行调整。PhysxCfg 类提供了设置 GPU 缓冲区尺寸的访问功能。

# OmniIsaacGymEnvs
sim:

  dt: 0.0083 # 1/120 s
  use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
  use_fabric: True
  enable_scene_query_support: False
  disable_contact_processing: False
  gravity: [0.0, 0.0, -9.81]

  default_physics_material:
    static_friction: 1.0
    dynamic_friction: 1.0
    restitution: 0.0

  physx:
    worker_thread_count: ${....num_threads}
    solver_type: ${....solver_type}
    use_gpu: ${contains:"cuda",${....sim_device}}
    solver_position_iteration_count: 4
    solver_velocity_iteration_count: 0
    contact_offset: 0.02
    rest_offset: 0.001
    bounce_threshold_velocity: 0.2
    friction_offset_threshold: 0.04
    friction_correlation_distance: 0.025
    enable_sleeping: True
    enable_stabilization: True
    max_depenetration_velocity: 100.0

    gpu_max_rigid_contact_count: 524288
    gpu_max_rigid_patch_count: 81920
    gpu_found_lost_pairs_capacity: 1024
    gpu_found_lost_aggregate_pairs_capacity: 262144
    gpu_total_aggregate_pairs_capacity: 1024
    gpu_heap_capacity: 67108864
    gpu_temp_buffer_capacity: 16777216
    gpu_max_num_partitions: 8
    gpu_max_soft_body_contacts: 1048576
    gpu_max_particle_contacts: 1048576
# IsaacLab
sim: SimulationCfg = SimulationCfg(
   device = "cuda:0" # can be "cpu", "cuda", "cuda:<device_id>"
   dt=1 / 120,
   # use_gpu_pipeline is deduced from the device
   use_fabric=True,
   enable_scene_query_support=False,
   disable_contact_processing=False,
   gravity=(0.0, 0.0, -9.81),

   physics_material=RigidBodyMaterialCfg(
       static_friction=1.0,
       dynamic_friction=1.0,
       restitution=0.0
   )
   physx: PhysxCfg = PhysxCfg(
       # worker_thread_count 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,
       friction_offset_threshold=0.04,
       friction_correlation_distance=0.025,
       # enable_sleeping is no longer needed
       enable_stabilization=True,
       # moved to RigidBodyPropertiesCfg

       gpu_max_rigid_contact_count=2**23,
       gpu_max_rigid_patch_count=5 * 2**15,
       gpu_found_lost_pairs_capacity=2**21,
       gpu_found_lost_aggregate_pairs_capacity=2**25,
       gpu_total_aggregate_pairs_capacity=2**21,
       gpu_heap_capacity=2**26,
       gpu_temp_buffer_capacity=2**24,
       gpu_max_num_partitions=8,
       gpu_max_soft_body_contacts=2**20,
       gpu_max_particle_contacts=2**20,
   )
)

以下参数,如 add_ground_planeadd_distant_light,现在在创建场景时已成为任务逻辑的一部分。enable_cameras 现在作为命令行参数 --enable_cameras 存在,可以直接传递给训练脚本。

场景配置#

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

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

任务配置#

每个环境都应该指定自己的配置类,该类包含特定于任务的参数,比如观察和行动缓冲区的维度。奖励项缩放参数也可以在配置类中进行指定。

在Isaac Lab中, controlFrequencyInv 参数已更名为 decimation ,必须在配置类中作为参数进行指定。

此外,最大的episode长度参数(现在是 episode_length_s )以秒为单位,而不是作为在OmniIsaacGymEnvs中的步数。要在步数和秒数之间转换,使用以下方程: episode_length_s = dt * decimation * num_steps

下面的参数必须为每个环境配置设置:

decimation = 2
episode_length_s = 5.0
num_actions = 1
num_observations = 4
num_states = 0

RL配置设置#

RL游戏库的rl配置文件在Isaac Lab中可以继续使用 .yaml 文件进行定义。配置文件的大部分内容可以直接从OmniIsaacGymEnvs中复制。请注意,在Isaac Lab中,我们不使用hydra来解析配置文件中的相对路径。请用参数的实际值替换任何相对路径,如 ${....device}

此外,观察和行动裁剪范围已经移到RL配置文件中。对于在IsaacGymEnvs任务配置文件中定义的 clipObservationsclipActions 参数,它们应该被移到Isaac Lab的RL配置文件中。

IsaacGymEnvs任务配置

Isaac Lab RL配置

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

环境创建#

在OmniIsaacGymEnvs中,环境创建通常发生在 set_up_scene() API中,其中涉及创建初始环境、克隆环境、过滤碰撞、添加地面和光线,并创建角色的 View 类。

在Isaac Lab中,类似的功能在 _setup_scene() API中执行。主要区别在于基类 _setup_scene() 不再执行克隆环境和添加地面和光线的操作。相反,现在这些操作应该在各个任务的 _setup_scene 实现中进行,以提供更灵活的场景设置过程。

还要注意的是,通过定义 ArticulationRigidObject 对象,将根据角色配置中的 spawn 参数将角色添加到场景中,并且 View 类将自动为角色创建。这样可以避免需要单独为角色定义 ArticulationViewRigidPrimView 对象。

OmniIsaacGymEnvs

Isaac Lab

def set_up_scene(self, scene) -> None:
  self.get_cartpole()
  super().set_up_scene(scene)

  self._cartpoles = ArticulationView(
               prim_paths_expr="/World/envs/.*/Cartpole",
               name="cartpole_view", reset_xform_properties=False
  )
  scene.add(self._cartpoles)
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 articultion 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)

地面#

除了以上示例外,还可以使用 TerrainImporterCfg 类定义更复杂的地面。

from omni.isaac.lab.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,
     ),
 )

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

角色#

在Isaac Lab中,每个关节和刚体角色都可以有自己的配置类。 ArticulationCfg 类可用于定义关节角色的参数,包括文件路径、模拟参数、执行器属性和初始状态。

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

角色是通过简单地调用 self.cartpole = Articulation(self.cfg.robot_cfg) 进行添加到场景的,其中 self.cfg.robot_cfg 是一个 ArticulationCfg 对象。初始化后,它们也应该被添加到 InteractiveScene 中,通过调用 self.scene.articulations["cartpole"] = self.cartpole ,以便 InteractiveScene 可以遍历场景中的角色,以便向模拟写入值并进行重置。

从模拟中获取状态#

在Isaac Lab中,访问物理状态的API需要创建一个 ArticulationRigidObject 对象。可以通过定义相应的 ArticulationCfgRigidObjectCfg 配置来为场景中的不同关节或刚体初始化多个对象,就像在上面的部分中所述的。这取代了以前在OmniIsaacGymEnvs中使用的 ArticulationViewomni.isaac.core.prims.RigidPrimView 类。

然而,这些类之间的功能是类似的:

OmniIsaacGymEnvs

Isaac Lab

dof_pos = self._cartpoles.get_joint_positions(clone=False)
dof_vel = self._cartpoles.get_joint_velocities(clone=False)
self.joint_pos = self._robot.data.joint_pos
self.joint_vel = self._robot.data.joint_vel

在Isaac Lab中, ArticulationRigidObject 类都有一个 data 类。数据类( ArticulationDataRigidObjectData )包含用于保存关节和刚体状态的缓冲区,并提供了一种更高效的方式从角色获取状态。

除了一些API的重命名外,设置角色状态的功能在OmniIsaacGymEnvs和Isaac Lab之间也可以进行类似的操作。

OmniIsaacGymEnvs

Isaac Lab

indices = env_ids.to(dtype=torch.int32)
self._cartpoles.set_joint_positions(dof_pos, indices=indices)
self._cartpoles.set_joint_velocities(dof_vel, indices=indices)
self._robot.write_joint_state_to_sim(joint_pos, joint_vel,
                                 joint_ids, env_ids)

在Isaac Lab中, root_poseroot_velocity 已合并为单个缓冲区,并且不再分割为 root_positionroot_orientationroot_linear_velocityroot_angular_velocity

创建一个新环境#

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接口将环境注册到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="omni.isaac.lab_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_reset API。以前在 post_reset 中完成的所有操作都可以在执行基类的 __init__ 方法后在 __init__ 方法中完成。此时,模拟已经开始。

在OmniIsaacGymEnvs中,由于GPU API的限制,不能根据当前步骤的状态进行重置。所以,重置必须在下一个时间步骤的开始时执行。在Isaac Lab中,这个限制被消除了,因此这些任务可以按照正确的工作流程进行操作,包括应用动作、模拟步进、收集状态、计算完成标志、计算奖励、执行重置,最后计算观察。这个工作流程可以被框架自动执行,因此任务不需要 post_physics_step API。但是,各个任务可以覆盖 step() API以控制工作流程。

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

调用的顺序如下:

OmniIsaacGymEnvs

Isaac Lab

pre_physics_step
  |-- reset_idx()
  |-- apply_action

post_physics_step
  |-- get_observations()
  |-- calculate_metrics()
  |-- is_done()
pre_physics_step
  |-- _pre_physics_step(action)
  |-- _apply_action()

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

通过这种方法,重置是基于当前步骤的动作而不是上一个步骤执行的。观察还将根据重置后的正确状态进行计算。

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

  • set_up_scene(self, scene) –> _setup_scene(self)

  • post_reset(self) –> __init__(...)

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

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

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

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

  • is_done(self) –> _get_dones(self) - 现在 _get_dones() 应该返回 2 个缓冲区: resettime_out 缓冲区

将所有内容组合在一起#

Cartpole 环境在这里被完整展示,以充分展示 OmniIsaacGymEnvs 实现和 Isaac Lab 实现之间的比较。

任务配置#

在 Isaac Lab 中,任务配置可以分为主要任务配置类和用于actor的单独配置对象。

OmniIsaacGymEnvs

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
  controlFrequencyInv: 2 # 60 Hz

sim:

  dt: 0.0083 # 1/120 s
  use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
  gravity: [0.0, 0.0, -9.81]
  add_ground_plane: True
  add_distant_light: False
  use_fabric: True
  enable_scene_query_support: False
  disable_contact_processing: False

  enable_cameras: False

  default_physics_material:
    static_friction: 1.0
    dynamic_friction: 1.0
    restitution: 0.0

  physx:
    worker_thread_count: ${....num_threads}
    solver_type: ${....solver_type}
    use_gpu: ${eq:${....sim_device},"gpu"} # set to False to...
    solver_position_iteration_count: 4
    solver_velocity_iteration_count: 0
    contact_offset: 0.02
    rest_offset: 0.001
    bounce_threshold_velocity: 0.2
    friction_offset_threshold: 0.04
    friction_correlation_distance: 0.025
    enable_sleeping: True
    enable_stabilization: True
    max_depenetration_velocity: 100.0

    # GPU buffers
    gpu_max_rigid_contact_count: 524288
    gpu_max_rigid_patch_count: 81920
    gpu_found_lost_pairs_capacity: 1024
    gpu_found_lost_aggregate_pairs_capacity: 262144
    gpu_total_aggregate_pairs_capacity: 1024
    gpu_max_soft_body_contacts: 1048576
    gpu_max_particle_contacts: 1048576
    gpu_heap_capacity: 67108864
    gpu_temp_buffer_capacity: 16777216
    gpu_max_num_partitions: 8

    Cartpole:
      override_usd_defaults: False
      enable_self_collisions: False
      enable_gyroscopic_forces: True
      solver_position_iteration_count: 4
      solver_velocity_iteration_count: 0
      sleep_threshold: 0.005
      stabilization_threshold: 0.001
      density: -1
      max_depenetration_velocity: 100.0
      contact_offset: 0.02
      rest_offset: 0.001
@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]
    num_actions = 1
    num_observations = 4
    num_states = 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


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=400.0,
       velocity_limit=100.0,
       stiffness=0.0,
       damping=10.0,
    ),
    "pole_actuator": ImplicitActuatorCfg(
       joint_names_expr=["cart_to_pole"], effort_limit=400.0,
       velocity_limit=100.0, stiffness=0.0, damping=0.0
    ),
  },
)

任务设置#

在Isaac Lab中,不再需要 post_reset API。以前在 post_reset 中完成的所有操作都可以在执行基类的 __init__ 方法后在 __init__ 方法中完成。此时,模拟已经开始。

OmniIsaacGymEnvs

Isaac Lab

class CartpoleTask(RLTask):

    def __init__(self, name, sim_config, env, offset=None) -> None:

        self.update_config(sim_config)
        self._max_episode_length = 500

        self._num_observations = 4
        self._num_actions = 1

        RLTask.__init__(self, name, env)

        def update_config(self, sim_config):
            self._sim_config = sim_config
            self._cfg = sim_config.config
            self._task_cfg = sim_config.
            task_config

            self._num_envs = self._task_cfg["env"]["numEnvs"]
            self._env_spacing = self._task_cfg["env"]["envSpacing"]
            self._cartpole_positions = torch.tensor([0.0, 0.0, 2.0])

            self._reset_dist = self._task_cfg["env"]["resetDist"]
            self._max_push_effort = self._task_cfg["env"]["maxEffort"]


        def post_reset(self):
            self._cart_dof_idx = self._cartpoles.get_dof_index(
                "cartJoint")
            self._pole_dof_idx = self._cartpoles.get_dof_index(
                "poleJoint")
            # randomize all envs
            indices = torch.arange(
                self._cartpoles.count, dtype=torch.int64,
                device=self._device)
            self.reset_idx(indices)
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

场景设置#

在 OmniIsaacGymEnvs 中, set_up_scene 方法已被 Isaac Lab 中任务类中的 _setup_scene API 替换。此外,还提供了场景克隆和碰撞过滤作为任务类在必要时调用的 API。同样,添加地平面和光源也应在任务类中处理。向场景添加actor已被替换为 self.scene.articulations["cartpole"] = self.cartpole

OmniIsaacGymEnvs

Isaac Lab

def set_up_scene(self, scene) -> None:

    self.get_cartpole()
    super().set_up_scene(scene)
    self._cartpoles = ArticulationView(
        prim_paths_expr="/World/envs/.*/Cartpole",
        name="cartpole_view",
        reset_xform_properties=False
    )
    scene.add(self._cartpoles)
    return

def get_cartpole(self):
    cartpole = Cartpole(
        prim_path=self.default_zero_env_path+"/Cartpole",
        name="Cartpole",
        translation=self._cartpole_positions
    )
    # applies articulation settings from the
    # task configuration yaml file
    self._sim_config.apply_articulation_settings(
        "Cartpole", get_prim_at_path(cartpole.prim_path),
        self._sim_config.parse_actor_config("Cartpole")
    )
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 articultion 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)

预物理步骤#

请注意,重置不再在 pre_physics_step API 中执行。此外, _pre_physics_step_apply_action 方法的分离允许更灵活地处理动作缓冲区并将动作设置到仿真中。

OmniIsaacGymEnvs

IsaacLab

def pre_physics_step(self, actions) -> None:
    if not self.world.is_playing():
        return

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

    actions = actions.to(self._device)

    forces = torch.zeros((self._cartpoles.count,
        self._cartpoles.num_dof),
        dtype=torch.float32, device=self._device)
    forces[:, self._cart_dof_idx] =
        self._max_push_effort * actions[:, 0]

    indices = torch.arange(self._cartpoles.count,
        dtype=torch.int32, device=self._device)
    self._cartpoles.set_joint_efforts(
        forces, indices=indices)
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_reset_idx() 方法也在仿真后而不是在 OmniIsaacGymEnvs 中之前调用。 progress_buf 张量在 Isaac Lab 中已更名为 episode_length_buf ,框架现在会自动处理记录。任务实现不再需要递增或重置 episode_length_buf

OmniIsaacGymEnvs

Isaac Lab

def is_done(self) -> None:
  resets = torch.where(
    torch.abs(self.cart_pos) > self._reset_dist, 1, 0)
  resets = torch.where(
    torch.abs(self.pole_pos) > math.pi / 2, 1, resets)
  resets = torch.where(
    self.progress_buf >= self._max_episode_length, 1, resets)
  self.reset_buf[:] = resets





def reset_idx(self, env_ids):
  num_resets = len(env_ids)

  # randomize DOF positions
  dof_pos = torch.zeros((num_resets, self._cartpoles.num_dof),
      device=self._device)
  dof_pos[:, self._cart_dof_idx] = 1.0 * (
      1.0 - 2.0 * torch.rand(num_resets, device=self._device))
  dof_pos[:, self._pole_dof_idx] = 0.125 * math.pi * (
      1.0 - 2.0 * torch.rand(num_resets, device=self._device))

  # randomize DOF velocities
  dof_vel = torch.zeros((num_resets, self._cartpoles.num_dof),
      device=self._device)
  dof_vel[:, self._cart_dof_idx] = 0.5 * (
      1.0 - 2.0 * torch.rand(num_resets, device=self._device))
  dof_vel[:, self._pole_dof_idx] = 0.25 * math.pi * (
      1.0 - 2.0 * torch.rand(num_resets, device=self._device))

  # apply resets
  indices = env_ids.to(dtype=torch.int32)
  self._cartpoles.set_joint_positions(dof_pos, indices=indices)
  self._cartpoles.set_joint_velocities(dof_vel, indices=indices)

  # bookkeeping
  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.joint_vel[env_ids] = joint_vel

    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_rewards API 中实现的,应该返回奖励缓冲区,而不是直接赋值给 self.rew_buf 。还可以使用 PyTorch jit 通过定义带有 @torch.jit.script 注释的函数来执行奖励函数的计算。

OmniIsaacGymEnvs

Isaac Lab

def calculate_metrics(self) -> None:
    reward = (1.0 - self.pole_pos * self.pole_pos
        - 0.01 * torch.abs(self.cart_vel) - 0.005
        * torch.abs(self.pole_vel))
    reward = torch.where(
        torch.abs(self.cart_pos) > self._reset_dist,
        torch.ones_like(reward) * -2.0, reward)
    reward = torch.where(
        torch.abs(self.pole_pos) > np.pi / 2,
        torch.ones_like(reward) * -2.0, reward)

    self.rew_buf[:] = reward
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 中, _get_observations() API 必须返回一个带有键 policy 且值为观察缓冲区的字典。当使用非对称的actor-critic状态时,评论者的状态应该有键 critic ,并与观察缓冲区一起返回在同一个字典中。

OmniIsaacGymEnvs

Isaac Lab

def get_observations(self) -> dict:
    dof_pos = self._cartpoles.get_joint_positions(clone=False)
    dof_vel = self._cartpoles.get_joint_velocities(clone=False)

    self.cart_pos = dof_pos[:, self._cart_dof_idx]
    self.cart_vel = dof_vel[:, self._cart_dof_idx]
    self.pole_pos = dof_pos[:, self._pole_dof_idx]
    self.pole_vel = dof_vel[:, self._pole_dof_idx]
    self.obs_buf[:, 0] = self.cart_pos
    self.obs_buf[:, 1] = self.cart_vel
    self.obs_buf[:, 2] = self.pole_pos
    self.obs_buf[:, 3] = self.pole_vel

    observations = {self._cartpoles.name:
        {"obs_buf": self.obs_buf}}
    return observations
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

领域随机化#

在 OmniIsaacGymEnvs 中,域随机化是通过任务的 .yaml 配置文件指定的。而在 Isaac Lab 中,域随机化配置使用 configclass 模块来指定一个由 EventTermCfg 变量组成的配置类。

以下是一个领域随机化的配置类示例:

@configclass
class EventCfg:
  robot_physics_material = EventTerm(
      func=mdp.randomize_rigid_body_material,
      mode="reset",
      params={
          "asset_cfg": SceneEntityCfg("robot", body_names=".*"),
          "static_friction_range": (0.7, 1.3),
          "dynamic_friction_range": (1.0, 1.0),
          "restitution_range": (1.0, 1.0),
          "num_buckets": 250,
      },
  )
  robot_joint_stiffness_and_damping = EventTerm(
      func=mdp.randomize_actuator_gains,
      mode="reset",
      params={
          "asset_cfg": SceneEntityCfg("robot", joint_names=".*"),
          "stiffness_distribution_params": (0.75, 1.5),
          "damping_distribution_params": (0.3, 3.0),
          "operation": "scale",
          "distribution": "log_uniform",
      },
  )
  reset_gravity = EventTerm(
      func=mdp.randomize_physics_scene_gravity,
      mode="interval",
      is_global_time=True,
      interval_range_s=(36.0, 36.0),  # time_s = num_steps * (decimation * dt)
      params={
          "gravity_distribution_params": ([0.0, 0.0, 0.0], [0.0, 0.0, 0.4]),
          "operation": "add",
          "distribution": "gaussian",
      },
  )

每个 EventTerm 对象都是 EventTermCfg 类的实例,并使用 func 参数来指定在随机化期间调用的函数,使用 mode 参数来指定 startupresetintervalparams 字典应提供给函数的必要参数,这些函数作为 EventTermfunc 参数在 events 模块中找到。

请注意,在 "asset_cfg": SceneEntityCfg("robot", body_names=".*") 参数中,提供了actor "robot" 的名称,以及作为正则表达式表达的主体或关节名称,这些将是将随机化应用于的actor和主体/关节。

与 OmniIsaacGymEnvs 的一个区别是,现在 interval 随机化是以秒而不是步数指定的。当 mode="interval" 时,还必须提供 interval_range_s 参数,该参数指定应用随机化的秒数范围。然后将随机选择此范围,以确定下一个术语的特定时间。要将步长转换为秒,请使用等式 time_s = num_steps * (decimation * dt)

与 OmniIsaacGymEnvs 类似,随机化 API 可用于随机化关节刚度和阻尼、关节限制、刚体材料、固定肌腱属性以及质量和刚体材料等刚体属性。物理场景重力的随机化也受支持。请注意,Isaac Lab 目前不支持scale的随机化。要随机化scale,请以每种环境以不同scale容纳actor的方式设置场景。

一旦设置了随机化术语的 configclass 类,该类必须添加到任务的基本配置类中,并分配给变量 events

@configclass
class MyTaskConfig:
  events: EventCfg = EventCfg()

动作和观察噪声#

使用 configclass 模块也可以添加动作和观察噪声。必须将动作和观察噪声配置添加到主要任务配置中,使用 action_noise_modelobservation_noise_model 变量:

@configclass
class MyTaskConfig:
    # at every time-step add gaussian noise + bias. The bias is a gaussian sampled at reset
    action_noise_model: NoiseModelWithAdditiveBiasCfg = NoiseModelWithAdditiveBiasCfg(
      noise_cfg=GaussianNoiseCfg(mean=0.0, std=0.05, operation="add"),
      bias_noise_cfg=GaussianNoiseCfg(mean=0.0, std=0.015, operation="abs"),
    )
    # at every time-step add gaussian noise + bias. The bias is a gaussian sampled at reset
    observation_noise_model: NoiseModelWithAdditiveBiasCfg = NoiseModelWithAdditiveBiasCfg(
      noise_cfg=GaussianNoiseCfg(mean=0.0, std=0.002, operation="add"),
      bias_noise_cfg=GaussianNoiseCfg(mean=0.0, std=0.0001, operation="abs"),
    )

NoiseModelWithAdditiveBiasCfg 可以用于每个步骤产生不相关的噪声,以及在重置时重新采样的相关噪声。 noise_cfg 术语指定将在每个步骤为所有环境采样的高斯分布。此噪声将在每一步添加到相应的动作和观察缓冲区中。 bias_noise_cfg 术语指定在被重置的环境的重置时间采样的相关噪声的高斯分布。相同的噪声将在剩余的剧集每一步应用,并在下一次重置时重新采样。

这取代了 OmniIsaacGymEnvs 中的以下设置:

domain_randomization:
randomize: True
randomization_params:
 observations:
   on_reset:
     operation: "additive"
     distribution: "gaussian"
     distribution_parameters: [0, .0001]
   on_interval:
     frequency_interval: 1
     operation: "additive"
     distribution: "gaussian"
     distribution_parameters: [0, .002]
 actions:
   on_reset:
     operation: "additive"
     distribution: "gaussian"
     distribution_parameters: [0, 0.015]
   on_interval:
     frequency_interval: 1
     operation: "additive"
     distribution: "gaussian"
     distribution_parameters: [0., 0.05]

启动训练#

要在 Isaac Lab 中启动训练,使用该命令:

python source/standalone/workflows/rl_games/train.py --task=Isaac-Cartpole-Direct-v0 --headless

启动推理#

要在 Isaac Lab 中启动推理,使用该命令:

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