Isaac Labのインストール方法と四足歩行ロボットの強化学習の方法を解説

1.はじめに(Isaac Labの概要)

NVIDIAがリリースしている3Dシミュレーションに特化したプラットフォームであるOmniverseのサービスの一つとして、Isaac Labというアプリケーションがあります。このIsaac Labは、元々NVIDIAがリリースしていたロボットの強化学習に特化したサービスであるIsaac Gymが改良され、2024年中期にリリースされたアプリケーションであり、より効率的にロボットAIを開発できるアプリケーションとして注目されています。Isaac Labの特徴としては、Isaac Sim上に構築されており、強化学習と模倣学習の両方をサポートしていることです。さらにNVIDIAのGPUの性能を最大限に活用することで、千体以上のロボットを同時に学習させる大規模なシミュレーションを実現しています。
当社では、このIsaac Labの技術を利用した研究・開発に力を入れておりますので、本記事では、Isaac Labのインストール方法と四足歩行ロボット強化学習の方法をご紹介します。

2.Isaac Labのインストール

Isaac Simは、Omniverse版, cloud版, pip版などいくつかの種類が準備されていますが、今回は、Isaac Labを使用する上で推奨されているpip版Isaac Sim上でのIsaac Labのインストール手順を紹介します。

前提環境

2.1 Minicondaのインストール

Isaac Simのインストールは、既存の環境を変えないように仮想環境上で行います。そのため、今回は、Minicondaを導入します。
(1)Minicondaインストーラーをこちらよりダウンロードし、インストーラーを起動

$ bash Miniconda3-latest-○○.sh

(2)インストールが完了したら、Isaac Lab用の新たなconda環境を作成し、起動
(base) ->(isaaclab)とterminal名の先頭が変更される。

$ conda create -n isaaclab python=3.10
$ conda activate isaaclab

2.2 CUDA環境にtorchをインストール

(1)CUDAのバージョンを確認

$ nvidia-smi

※コマンドが通らない場合は、NVIDIAのGPUドライバをインストールする必要がある(推奨バージョン
※インストールされていない場合、cuDNNのインストールも必要(ダウンロードページ

(2)CUDAのバージョンは11と12に対応しており、対応する方をインストール

■ CUDA11

$ pip install torch==2.4.0 --index-url https://download.pytorch.org/whl/cu118

■ CUDA12

$ pip install torch==2.4.0 --index-url https://download.pytorch.org/whl/cu121

※11.8 or 12.1以外では対応しない可能性もある
※依存関係でエラーが出るが、弊社の環境では、無視しても問題なかった

2.3 pip版Isaac Simのインストール

(1)執筆時点(2024/12)のIsaacSimをインストール

$ pip install –upgrade pip
$ pip install isaacsim==4.2.0.2 --extra-index-url https://pypi.nvidia.com  
$ pip install isaacsim-rl isaacsim-replicator isaacsim-extscache-physics isaacsim-extscache-kit-sdk isaacsim-extscache-kit isaacsim-app --extra-index-url https://pypi.nvidia.com

※torchインストールと同様に依存関係でエラーが出るが、弊社の環境では、無視しても問題なかった

(2)起動時に下記エラーが出たら、condaコマンドを入力

$ conda install -c conda-forge libstdcxx-ng

(3)Isaac Sim起動確認
下記のどちらも試し、GUIを起動できたらインストール成功

$ isaacsim 
$ isaacsim omni.isaac.sim.python.kit

※起動時エラーでcudnn関連のファイルがない場合は、cudnnを再インストールする

2.4 Isaac Labのインストール

(1)Isaac Labは、githubからインストールし、Isaaclabライブラリ特有の—installコマンドを使用すれば完了

$ git clone git@github.com:isaac-sim/IsaacLab.git
$ sudo apt install cmake build-essential
$ cd ~/IsaacLab
$ ./isaaclab.sh –install

(2)Isaac Labインストール確認
空の空間が生成されれば、完了

$ ./isaaclab.sh -p source/standalone/tutorials/00_sim/create_empty.py

3.Isaac Labにて四足歩行ロボットの強化学習を行う

3.1 Isaac Labを用いて強化学習

Isaac Labでの強化学習の仕組みを簡潔に書きますと、強化学習タスク (シミュレーション環境+強化学習タスク)を準備して、強化学習環境を強化学習ライブラリへ与えることで、強化学習を行います。
① 強化学習ライブラリへのラッパー
Isaac Labは、いくつかのメジャーな強化学習ライブラリで強化学習を行えるようにラッパーが実装されています。これらのラッパーが、Isaac Labのルールに沿って準備した強化学習タスクを、強化学習ライブラリにつないでくれます。現在実装されているラッパーは、RL-Games,RSL RL, SKRL, Stable Baselines3の4つとなります。(※2024年12月時点)
以下は、それらの特徴比較です。
例えば、Stable Baselines3を使用したい場合、インストールしたIsaac Lab内に、「source/standalone/workflows/sb3/train.py」というファイルが準備されています。これは、Stable-Baselines3 (SB3)を使って学習を行うためのファイルであり、 「source/standalone/workflows」のフォルダを確認すると、上記4つのライブラリそれぞれで強化学習を行うためのファイルが準備されていることが確認できます。

② 強化学習タスク(シミュレーション環境+強化学習タスク)
Isaac Labでは、強化学習を行うために、強化学習ライブラリに対して、強化学習タスク(シミュレーション環境+強化学習タスク)を与えることで、強化学習を行うことができます。これらは、Isaac LabのGym Registryという機能に沿って、事前に登録を行うことで、簡単に呼び出せる仕組みが整っています。また、Isaac Labは、事前に登録した様々な環境を準備しており、簡単に試すことができます。そのため、1から強化学習環境を作成することもできますが、行いたい強化学習に類似する環境を改築して、スムーズに強化学習を行えるようになっています。

準備された学習一覧はこちら

3.2 実際に学習して、学習後のモデルをテスト

では、実際にIsaac Labで登録されている強化学習環境を1つ動かしてみます。準備された学習一覧から「Isaac-Velocity-Rough-Anymal-D-v0」というタスクをSKRLにて試します。このタスクは、四足歩行ロボットを段差のある環境でこけずに歩けるようにロボットの制御部分(joint)の学習を行う内容となっています。
実際に学習を行う際は、以下のコマンドで簡単に学習を行うことができます。
# SKRLにて強化学習を行うためのpythonモジュールをインストール

$ ./isaaclab.sh -i skrl

# 強化学習の実行

$ ./isaaclab.sh -p source/standalone/workflows/skrl/train.py --task Isaac-Velocity-Rough-Anymal-D-v0  --headless


使用可能な引数はいくつかありますが、基本的には、以下2つを指定します。(※ほかの引数は-hコマンドで詳細を確認できます。)
--task : 登録されている実行タスクを指定する
--headless : Isaac SimのGUIを起動せずに、学習を進行する
デフォルトで、4096体のロボットが平行して強化学習を行っており、Headlessを外すと、GUIで学習の進行を確認することができます。

学習完了後、学習モデルが生成されますので、そちら使用してをテストし、検証します。

$ ./isaaclab.sh -p source/standalone/workflows/skrl/play.py --task Isaac-Velocity-Rough-Anymal-D-v0 --num_envs 32 --checkpoint /PATH /best_agent.pt
テストの際は、2つの引数を使用する。
--num_envs : テスト時のロボットの数
--checkpoint : 学習済みモデルのpath

準備された四足歩行ロボットの学習でもある程度の歩行ができていることが確認できます。

3.3 解説

2.3で四足歩行ロボットの学習によるモデル生成を行いました。今回は、デフォルトで準備されたタスクを使用しましたが、実用的には、自分たちで行いたいタスクを準備する必要があります。しかし、Isaac Labの学習タスクのセットアップは、強化学習のMDP(マルコフ決定過程)というフレームワークに沿った決まった型で作成されていますので、準備されたタスクの仕様を理解すれば、簡単に自分たちの行いたい強化学習タスクのセットアップができます。(※強化学習の基礎知識は必要)
型としては、2つ準備されています。
  • Manager-Based RL Environment
      ► 決まった型が提供され、その型に当てはめていく形で開発する
  • Direct Workflow RL Environment
      ► 抽象化の少ない(より直接的な)フレームワークが提供

今回の強化学習では、(1) Manager-Based RL Environmentの型で作られた学習タスクにてセットアップを行いました。Manager-Based RL Environmentは、8つの設定クラスが準備されており、それらをセットアップすることで、強化学習を行えます。
  • シーン : Isaac Sim上のシーンを定義
  • Observation : エージェントが環境から受け取る情報を定義
  • Action : シミュレーション環境に適用するアクション(学習する制御部分)を定義
  • Event : シミュレーション環境の変化時に起こすイベントを定義
  • Command : エージェントが実行するコマンドを定義(※なくてもよい)
  • Reward : 報酬の定義
  • Termination : エピソード終了の定義
  • Curriculum : 特定のカリキュラムの定義(※なくてもよい)
※用語は、MDPの用語を参照してください。

例えば、今回の学習では、下記ファイルにて8つの設定クラスを準備し、学習タスクの設定を行っています。
 詳細はこちらをクリックしてください

# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause

import math
from dataclasses import MISSING

import omni.isaac.lab.sim as sim_utils
from omni.isaac.lab.assets import ArticulationCfg, AssetBaseCfg
from omni.isaac.lab.envs import ManagerBasedRLEnvCfg
from omni.isaac.lab.managers import CurriculumTermCfg as CurrTerm
from omni.isaac.lab.managers import EventTermCfg as EventTerm
from omni.isaac.lab.managers import ObservationGroupCfg as ObsGroup
from omni.isaac.lab.managers import ObservationTermCfg as ObsTerm
from omni.isaac.lab.managers import RewardTermCfg as RewTerm
from omni.isaac.lab.managers import SceneEntityCfg
from omni.isaac.lab.managers import TerminationTermCfg as DoneTerm
from omni.isaac.lab.scene import InteractiveSceneCfg
from omni.isaac.lab.sensors import ContactSensorCfg, RayCasterCfg, patterns
from omni.isaac.lab.terrains import TerrainImporterCfg
from omni.isaac.lab.utils import configclass
from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR
from omni.isaac.lab.utils.noise import AdditiveUniformNoiseCfg as Unoise

import omni.isaac.lab_tasks.manager_based.locomotion.velocity.mdp as mdp

##
# Pre-defined configs
##
from omni.isaac.lab.terrains.config.rough import ROUGH_TERRAINS_CFG  # isort: skip


##
# Scene definition
##


@configclass
class MySceneCfg(InteractiveSceneCfg):
    """Configuration for the terrain scene with a legged robot."""

    # ground terrain
    terrain = TerrainImporterCfg(
        prim_path="/World/ground",
        terrain_type="generator",
        terrain_generator=ROUGH_TERRAINS_CFG,
        max_init_terrain_level=5,
        collision_group=-1,
        physics_material=sim_utils.RigidBodyMaterialCfg(
            friction_combine_mode="multiply",
            restitution_combine_mode="multiply",
            static_friction=1.0,
            dynamic_friction=1.0,
        ),
        visual_material=sim_utils.MdlFileCfg(
            mdl_path=f"{ISAACLAB_NUCLEUS_DIR}/Materials/TilesMarbleSpiderWhiteBrickBondHoned/TilesMarbleSpiderWhiteBrickBondHoned.mdl",
            project_uvw=True,
            texture_scale=(0.25, 0.25),
        ),
        debug_vis=False,
    )
    # robots
    robot: ArticulationCfg = MISSING
    # sensors
    height_scanner = RayCasterCfg(
        prim_path="{ENV_REGEX_NS}/Robot/base",
        offset=RayCasterCfg.OffsetCfg(pos=(0.0, 0.0, 20.0)),
        attach_yaw_only=True,
        pattern_cfg=patterns.GridPatternCfg(resolution=0.1, size=[1.6, 1.0]),
        debug_vis=False,
        mesh_prim_paths=["/World/ground"],
    )
    contact_forces = ContactSensorCfg(prim_path="{ENV_REGEX_NS}/Robot/.*", history_length=3, track_air_time=True)
    # lights
    sky_light = AssetBaseCfg(
        prim_path="/World/skyLight",
        spawn=sim_utils.DomeLightCfg(
            intensity=750.0,
            texture_file=f"{ISAAC_NUCLEUS_DIR}/Materials/Textures/Skies/PolyHaven/kloofendal_43d_clear_puresky_4k.hdr",
        ),
    )


##
# MDP settings
##


@configclass
class CommandsCfg:
    """Command specifications for the MDP."""

    base_velocity = mdp.UniformVelocityCommandCfg(
        asset_name="robot",
        resampling_time_range=(10.0, 10.0),
        rel_standing_envs=0.02,
        rel_heading_envs=1.0,
        heading_command=True,
        heading_control_stiffness=0.5,
        debug_vis=True,
        ranges=mdp.UniformVelocityCommandCfg.Ranges(
            lin_vel_x=(-1.0, 1.0), lin_vel_y=(-1.0, 1.0), ang_vel_z=(-1.0, 1.0), heading=(-math.pi, math.pi)
        ),
    )


@configclass
class ActionsCfg:
    """Action specifications for the MDP."""

    joint_pos = mdp.JointPositionActionCfg(asset_name="robot", joint_names=[".*"], scale=0.5, use_default_offset=True)


@configclass
class ObservationsCfg:
    """Observation specifications for the MDP."""

    @configclass
    class PolicyCfg(ObsGroup):
        """Observations for policy group."""

        # observation terms (order preserved)
        base_lin_vel = ObsTerm(func=mdp.base_lin_vel, noise=Unoise(n_min=-0.1, n_max=0.1))
        base_ang_vel = ObsTerm(func=mdp.base_ang_vel, noise=Unoise(n_min=-0.2, n_max=0.2))
        projected_gravity = ObsTerm(
            func=mdp.projected_gravity,
            noise=Unoise(n_min=-0.05, n_max=0.05),
        )
        velocity_commands = ObsTerm(func=mdp.generated_commands, params={"command_name": "base_velocity"})
        joint_pos = ObsTerm(func=mdp.joint_pos_rel, noise=Unoise(n_min=-0.01, n_max=0.01))
        joint_vel = ObsTerm(func=mdp.joint_vel_rel, noise=Unoise(n_min=-1.5, n_max=1.5))
        actions = ObsTerm(func=mdp.last_action)
        height_scan = ObsTerm(
            func=mdp.height_scan,
            params={"sensor_cfg": SceneEntityCfg("height_scanner")},
            noise=Unoise(n_min=-0.1, n_max=0.1),
            clip=(-1.0, 1.0),
        )

        def __post_init__(self):
            self.enable_corruption = True
            self.concatenate_terms = True

    # observation groups
    policy: PolicyCfg = PolicyCfg()


@configclass
class EventCfg:
    """Configuration for events."""

    # startup
    physics_material = EventTerm(
        func=mdp.randomize_rigid_body_material,
        mode="startup",
        params={
            "asset_cfg": SceneEntityCfg("robot", body_names=".*"),
            "static_friction_range": (0.8, 0.8),
            "dynamic_friction_range": (0.6, 0.6),
            "restitution_range": (0.0, 0.0),
            "num_buckets": 64,
        },
    )

    add_base_mass = EventTerm(
        func=mdp.randomize_rigid_body_mass,
        mode="startup",
        params={
            "asset_cfg": SceneEntityCfg("robot", body_names="base"),
            "mass_distribution_params": (-5.0, 5.0),
            "operation": "add",
        },
    )

    # reset
    base_external_force_torque = EventTerm(
        func=mdp.apply_external_force_torque,
        mode="reset",
        params={
            "asset_cfg": SceneEntityCfg("robot", body_names="base"),
            "force_range": (0.0, 0.0),
            "torque_range": (-0.0, 0.0),
        },
    )

    reset_base = EventTerm(
        func=mdp.reset_root_state_uniform,
        mode="reset",
        params={
            "pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
            "velocity_range": {
                "x": (-0.5, 0.5),
                "y": (-0.5, 0.5),
                "z": (-0.5, 0.5),
                "roll": (-0.5, 0.5),
                "pitch": (-0.5, 0.5),
                "yaw": (-0.5, 0.5),
            },
        },
    )

    reset_robot_joints = EventTerm(
        func=mdp.reset_joints_by_scale,
        mode="reset",
        params={
            "position_range": (0.5, 1.5),
            "velocity_range": (0.0, 0.0),
        },
    )

    # interval
    push_robot = EventTerm(
        func=mdp.push_by_setting_velocity,
        mode="interval",
        interval_range_s=(10.0, 15.0),
        params={"velocity_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5)}},
    )


@configclass
class RewardsCfg:
    """Reward terms for the MDP."""

    # -- task
    track_lin_vel_xy_exp = RewTerm(
        func=mdp.track_lin_vel_xy_exp, weight=1.0, params={"command_name": "base_velocity", "std": math.sqrt(0.25)}
    )
    track_ang_vel_z_exp = RewTerm(
        func=mdp.track_ang_vel_z_exp, weight=0.5, params={"command_name": "base_velocity", "std": math.sqrt(0.25)}
    )
    # -- penalties
    lin_vel_z_l2 = RewTerm(func=mdp.lin_vel_z_l2, weight=-2.0)
    ang_vel_xy_l2 = RewTerm(func=mdp.ang_vel_xy_l2, weight=-0.05)
    dof_torques_l2 = RewTerm(func=mdp.joint_torques_l2, weight=-1.0e-5)
    dof_acc_l2 = RewTerm(func=mdp.joint_acc_l2, weight=-2.5e-7)
    action_rate_l2 = RewTerm(func=mdp.action_rate_l2, weight=-0.01)
    feet_air_time = RewTerm(
        func=mdp.feet_air_time,
        weight=0.125,
        params={
            "sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*FOOT"),
            "command_name": "base_velocity",
            "threshold": 0.5,
        },
    )
    undesired_contacts = RewTerm(
        func=mdp.undesired_contacts,
        weight=-1.0,
        params={"sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*THIGH"), "threshold": 1.0},
    )
    # -- optional penalties
    flat_orientation_l2 = RewTerm(func=mdp.flat_orientation_l2, weight=0.0)
    dof_pos_limits = RewTerm(func=mdp.joint_pos_limits, weight=0.0)


@configclass
class TerminationsCfg:
    """Termination terms for the MDP."""

    time_out = DoneTerm(func=mdp.time_out, time_out=True)
    base_contact = DoneTerm(
        func=mdp.illegal_contact,
        params={"sensor_cfg": SceneEntityCfg("contact_forces", body_names="base"), "threshold": 1.0},
    )


@configclass
class CurriculumCfg:
    """Curriculum terms for the MDP."""

    terrain_levels = CurrTerm(func=mdp.terrain_levels_vel)


##
# Environment configuration
##


@configclass
class LocomotionVelocityRoughEnvCfg(ManagerBasedRLEnvCfg):
    """Configuration for the locomotion velocity-tracking environment."""

    # Scene settings
    scene: MySceneCfg = MySceneCfg(num_envs=4096, env_spacing=2.5)
    # Basic settings
    observations: ObservationsCfg = ObservationsCfg()
    actions: ActionsCfg = ActionsCfg()
    commands: CommandsCfg = CommandsCfg()
    # MDP settings
    rewards: RewardsCfg = RewardsCfg()
    terminations: TerminationsCfg = TerminationsCfg()
    events: EventCfg = EventCfg()
    curriculum: CurriculumCfg = CurriculumCfg()

    def __post_init__(self):
        """Post initialization."""
        # general settings
        self.decimation = 4
        self.episode_length_s = 20.0
        # simulation settings
        self.sim.dt = 0.005
        self.sim.render_interval = self.decimation
        self.sim.disable_contact_processing = True
        self.sim.physics_material = self.scene.terrain.physics_material
        # update sensor update periods
        # we tick all the sensors based on the smallest update period (physics update period)
        if self.scene.height_scanner is not None:
            self.scene.height_scanner.update_period = self.decimation * self.sim.dt
        if self.scene.contact_forces is not None:
            self.scene.contact_forces.update_period = self.sim.dt

        # check if terrain levels curriculum is enabled - if so, enable curriculum for terrain generator
        # this generates terrains with increasing difficulty and is useful for training
        if getattr(self.curriculum, "terrain_levels", None) is not None:
            if self.scene.terrain.terrain_generator is not None:
                self.scene.terrain.terrain_generator.curriculum = True
        else:
            if self.scene.terrain.terrain_generator is not None:
                self.scene.terrain.terrain_generator.curriculum = False

4.まとめ

本記事では、Isaac Labのインストール手順とIsac Labを使用したシミュレーション環境上での四足歩行ロボットの強化学習をご紹介しました。弊社は、昨今特にOmniverse含め、Isaac Sim、Isaac Lab、シミュレーションでのAI開発などの技術に注目しており、四足歩行ロボットに限らず、アームロボット、ヒューマノイドロボット、また、ロボット以外の機器に対するシミュレーション環境でのAI開発の研究を日々進めています。ロボットに限らず、シミュレーション環境でのAI開発にご興味のある方は、お気軽にご相談ください。

ロボットシミュレータにお困りの方はぜひ、
富士ソフトにご用命ください!

お問い合わせはこちら