将一个新的机器人模型导入最新版isaacLab进行训练(以unitree H1_2为例)

发布于:2025-04-04 ⋅ 阅读:(17) ⋅ 点赞:(0)

1、资产导入

  • isaacgym中,机器人结构文件(.urdf)保存在resources目录下
  • isaaclab的文件结构里有所不同,isaaclab使用USD格式文件,此时导入新机器人需要将urdf文件转换成USD文件。

1.1 文件准备

首先在宇树官方文档中拿到RL例程,把unitree_rl_gym文件夹放在根目录\home\username\

1.2 资产导入

需要调用scripts/tools/convert_urdf.py脚本进行转换,其中涉及到一些参数的设置:

参数名 描述 默认值
--merge-joints 布尔标志,设置为True时,合并由固定关节连接的连杆 False
--fix-base 布尔标志,设置为True时,将机器人基座固定在导入位置 False
--joint-stiffness 关节驱动的刚度,刚度值越大,关节越难变形 100.0
--joint-damping 关节驱动的阻尼,用于减少关节的振动和摆动 1.0
--joint-target-type 关节驱动的控制类型,可选值为"position"、“velocity"或"none” “position”
cd IsaacLab

./isaaclab.sh -p scripts/tools/convert_urdf.py \
~/unitree_rl_gym/resources/robots/h1_2/h1_2.urdf \
source/isaaclab_assets/data/Robots/h1_2/h1_2.usd \
--merge-joints --joint-stiffness 0.0 \
--joint-damping 0.0 \
--joint-target-type none

导入到isaacsim中:
在这里插入图片描述
这个时候USD文件就生成了。

2、机器人属性配置

对标gym中的config,在IsaacLab中也要写一个对应的config
IsaacLab/source/isaaclab_assets/isaaclab_assets/robots/中找到了机器人们的配置文件,其中有一个文件为unitree.py,里面配置了Isaaclab收录的所有宇树机器人,但是H1_2恰好没在其中。

模仿unitree.py中关于H1的配置,再参考H1_2的关节,写一段config插在unitree.py中:
其中有几点需要注意:

  • usd_path需要对应自己的usd文件的路径
  • H1_2相比于H1而言,关节名称有些许变化(具体是名称后面多了“_joint”,以及ankle等部位多加了关节),正则表达式匹配需要在后面也加个 .* \text{.*} .*
H1_2_CFG = ArticulationCfg(
    spawn=sim_utils.UsdFileCfg(
        usd_path=f"/home/swanchan/IsaacLab/source/isaaclab_assets/data/Robots/h1_2/h1_2.usd",
        activate_contact_sensors=True,
        rigid_props=sim_utils.RigidBodyPropertiesCfg(
            disable_gravity=False,
            retain_accelerations=False,
            linear_damping=0.0,
            angular_damping=0.0,
            max_linear_velocity=1000.0,
            max_angular_velocity=1000.0,
            max_depenetration_velocity=1.0,
        ),
        articulation_props=sim_utils.ArticulationRootPropertiesCfg(
            enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=4
        ),
    ),
    init_state=ArticulationCfg.InitialStateCfg(
        pos=(0.0, 0.0, 1.05),
        joint_pos={
            ".*_hip_yaw.*": 0.0,
            ".*_hip_roll.*": 0.0,
            ".*_hip_pitch.*": -0.16,  # -9.17 degrees
            ".*_knee.*": 0.36,  # 20.63 degrees
            ".*_ankle_pitch.*": -0.2,  # -11.46 degrees
            ".*_ankle_roll.*": 0.0,
            "torso.*": 0.0,
            ".*_shoulder_pitch.*": 0.4,  # 22.92 degrees
            ".*_shoulder_roll.*": 0.0,
            ".*_shoulder_yaw.*": 0.0,
            ".*_elbow_pitch.*": 0.3,  # 17.19 degrees
        },
        joint_vel={".*": 0.0},
    ),
    soft_joint_pos_limit_factor=0.9,
    actuators={
        "legs": ImplicitActuatorCfg(
            joint_names_expr=[".*_hip_yaw.*", ".*_hip_roll.*", ".*_hip_pitch.*", ".*_knee.*", "torso.*"],
            effort_limit=300,
            velocity_limit=100.0,
            stiffness={
                ".*_hip_yaw.*": 200.0,
                ".*_hip_roll.*": 200.0,
                ".*_hip_pitch.*": 200.0,
                ".*_knee.*": 300.0,
                "torso.*": 200.0,
            },
            damping={
                ".*_hip_yaw.*": 2.5,
                ".*_hip_roll.*": 2.5,
                ".*_hip_pitch.*": 2.5,
                ".*_knee.*": 4.0,
                "torso.*": 5.0,
            },
        ),
        "feet": ImplicitActuatorCfg(
            joint_names_expr=[".*_ankle_pitch.*", ".*_ankle_roll.*"],
            effort_limit=100,
            velocity_limit=100.0,
            stiffness={
                ".*_ankle_pitch.*": 40.0,
                ".*_ankle_roll.*": 40.0,
            },
            damping={
                ".*_ankle_pitch.*": 2.0,
                ".*_ankle_roll.*": 2.0,
            },
        ),
        "arms": ImplicitActuatorCfg(
            joint_names_expr=[".*_shoulder_pitch.*", ".*_shoulder_roll.*", ".*_shoulder_yaw.*", ".*_elbow_pitch.*"],
            effort_limit=300,
            velocity_limit=100.0,
            stiffness={
                ".*_shoulder_pitch.*": 40.0,
                ".*_shoulder_roll.*": 40.0,
                ".*_shoulder_yaw.*": 40.0,
                ".*_elbow_pitch.*": 40.0,
            },
            damping={
                ".*_shoulder_pitch.*": 10.0,
                ".*_shoulder_roll.*": 10.0,
                ".*_shoulder_yaw.*": 10.0,
                ".*_elbow_pitch.*": 10.0,
            },
        ),
    },
)
"""Configuration for the Unitree H1_2 Humanoid robot."""


H1_2_MINIMAL_CFG = H1_2_CFG.copy()
H1_2_MINIMAL_CFG.spawn.usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/H1_2/h1_2_minimal.usd"

3、强化学习任务环境配置

/IsaacLab/source/isaaclab_tasks/isaaclab_tasks/manager_based/locomotion/velocity/config/中可以看到宇树的机器人训练环境
在这里插入图片描述
直接把h1文件夹复制为h1_2,然后对里面的文件进行一定的更改。
具体是把所有h1替换为h1_2,所有H1替换为H1_2,再改一下rough_env_cfg.py里面的关节

__init__.py

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

import gymnasium as gym

from . import agents

##
# Register Gym environments.
##

gym.register(
    id="Isaac-Velocity-Rough-H1_2-v0",
    entry_point="isaaclab.envs:ManagerBasedRLEnv",
    disable_env_checker=True,
    kwargs={
        "env_cfg_entry_point": f"{__name__}.rough_env_cfg:H1_2RoughEnvCfg",
        "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1_2RoughPPORunnerCfg",
        "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
    },
)


gym.register(
    id="Isaac-Velocity-Rough-H1_2-Play-v0",
    entry_point="isaaclab.envs:ManagerBasedRLEnv",
    disable_env_checker=True,
    kwargs={
        "env_cfg_entry_point": f"{__name__}.rough_env_cfg:H1_2RoughEnvCfg_PLAY",
        "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1_2RoughPPORunnerCfg",
        "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
    },
)


gym.register(
    id="Isaac-Velocity-Flat-H1_2-v0",
    entry_point="isaaclab.envs:ManagerBasedRLEnv",
    disable_env_checker=True,
    kwargs={
        "env_cfg_entry_point": f"{__name__}.flat_env_cfg:H1_2FlatEnvCfg",
        "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1_2FlatPPORunnerCfg",
        "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml",
    },
)


gym.register(
    id="Isaac-Velocity-Flat-H1_2-Play-v0",
    entry_point="isaaclab.envs:ManagerBasedRLEnv",
    disable_env_checker=True,
    kwargs={
        "env_cfg_entry_point": f"{__name__}.flat_env_cfg:H1_2FlatEnvCfg_PLAY",
        "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1_2FlatPPORunnerCfg",
        "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml",
    },
)

flat_env_cfg.py

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

from isaaclab.utils import configclass

from .rough_env_cfg import H1_2RoughEnvCfg


@configclass
class H1_2FlatEnvCfg(H1_2RoughEnvCfg):
    def __post_init__(self):
        # post init of parent
        super().__post_init__()

        # change terrain to flat
        self.scene.terrain.terrain_type = "plane"
        self.scene.terrain.terrain_generator = None
        # no height scan
        self.scene.height_scanner = None
        self.observations.policy.height_scan = None
        # no terrain curriculum
        self.curriculum.terrain_levels = None
        self.rewards.feet_air_time.weight = 1.0
        self.rewards.feet_air_time.params["threshold"] = 0.6


class H1_2FlatEnvCfg_PLAY(H1_2FlatEnvCfg):
    def __post_init__(self) -> None:
        # post init of parent
        super().__post_init__()

        # make a smaller scene for play
        self.scene.num_envs = 50
        self.scene.env_spacing = 2.5
        # disable randomization for play
        self.observations.policy.enable_corruption = False
        # remove random pushing
        self.events.base_external_force_torque = None
        self.events.push_robot = None

rough_env_cfg.py

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

from isaaclab.managers import RewardTermCfg as RewTerm
from isaaclab.managers import SceneEntityCfg
from isaaclab.utils import configclass

import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp
from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg, RewardsCfg

##
# Pre-defined configs
##
from isaaclab_assets import H1_2_CFG


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

    termination_penalty = RewTerm(func=mdp.is_terminated, weight=-200.0)
    lin_vel_z_l2 = None
    track_lin_vel_xy_exp = RewTerm(
        func=mdp.track_lin_vel_xy_yaw_frame_exp,
        weight=1.0,
        params={"command_name": "base_velocity", "std": 0.5},
    )
    track_ang_vel_z_exp = RewTerm(
        func=mdp.track_ang_vel_z_world_exp, weight=1.0, params={"command_name": "base_velocity", "std": 0.5}
    )
    feet_air_time = RewTerm(
        func=mdp.feet_air_time_positive_biped,
        weight=0.25,
        params={
            "command_name": "base_velocity",
            "sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*ankle.*"),
            "threshold": 0.4,
        },
    )
    feet_slide = RewTerm(
        func=mdp.feet_slide,
        weight=-0.25,
        params={
            "sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*ankle.*"),
            "asset_cfg": SceneEntityCfg("robot", body_names=".*ankle.*"),
        },
    )
    # Penalize ankle joint limits
    dof_pos_limits = RewTerm(
        func=mdp.joint_pos_limits, weight=-1.0, params={"asset_cfg": SceneEntityCfg("robot", joint_names=".*_ankle.*")}
    )
    # Penalize deviation from default of the joints that are not essential for locomotion
    joint_deviation_hip = RewTerm(
        func=mdp.joint_deviation_l1,
        weight=-0.2,
        params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*_hip_yaw.*", ".*_hip_roll.*"])},
    )
    joint_deviation_arms = RewTerm(
        func=mdp.joint_deviation_l1,
        weight=-0.2,
        params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*_shoulder_.*", ".*_elbow.*"])},
    )
    joint_deviation_torso = RewTerm(
        func=mdp.joint_deviation_l1, weight=-0.1, params={"asset_cfg": SceneEntityCfg("robot", joint_names="torso.*")}
    )


@configclass
class H1_2RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
    rewards: H1_2Rewards = H1_2Rewards()

    def __post_init__(self):
        # post init of parent
        super().__post_init__()
        # Scene
        self.scene.robot = H1_2_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") # type: ignore
        if self.scene.height_scanner:
            self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torso_link"

        # Randomization
        self.events.push_robot = None
        self.events.add_base_mass = None
        self.events.reset_robot_joints.params["position_range"] = (1.0, 1.0)
        self.events.base_external_force_torque.params["asset_cfg"].body_names = [".*torso_link"]
        self.events.reset_base.params = {
            "pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
            "velocity_range": {
                "x": (0.0, 0.0),
                "y": (0.0, 0.0),
                "z": (0.0, 0.0),
                "roll": (0.0, 0.0),
                "pitch": (0.0, 0.0),
                "yaw": (0.0, 0.0),
            },
        }

        # Terminations
        self.terminations.base_contact.params["sensor_cfg"].body_names = [".*torso_link"]

        # Rewards
        self.rewards.undesired_contacts = None
        self.rewards.flat_orientation_l2.weight = -1.0
        self.rewards.dof_torques_l2.weight = 0.0
        self.rewards.action_rate_l2.weight = -0.005
        self.rewards.dof_acc_l2.weight = -1.25e-7

        # Commands
        self.commands.base_velocity.ranges.lin_vel_x = (0.0, 1.0)
        self.commands.base_velocity.ranges.lin_vel_y = (0.0, 0.0)
        self.commands.base_velocity.ranges.ang_vel_z = (-1.0, 1.0)

        # terminations
        self.terminations.base_contact.params["sensor_cfg"].body_names = ".*torso_link"


@configclass
class H1_2RoughEnvCfg_PLAY(H1_2RoughEnvCfg):
    def __post_init__(self):
        # post init of parent
        super().__post_init__()

        # make a smaller scene for play
        self.scene.num_envs = 50
        self.scene.env_spacing = 2.5
        self.episode_length_s = 40.0
        # spawn the robot randomly in the grid (instead of their terrain levels)
        self.scene.terrain.max_init_terrain_level = None
        # reduce the number of terrains to save memory
        if self.scene.terrain.terrain_generator is not None:
            self.scene.terrain.terrain_generator.num_rows = 5
            self.scene.terrain.terrain_generator.num_cols = 5
            self.scene.terrain.terrain_generator.curriculum = False

        self.commands.base_velocity.ranges.lin_vel_x = (1.0, 1.0)
        self.commands.base_velocity.ranges.lin_vel_y = (0.0, 0.0)
        self.commands.base_velocity.ranges.ang_vel_z = (-1.0, 1.0)
        self.commands.base_velocity.ranges.heading = (0.0, 0.0)
        # disable randomization for play
        self.observations.policy.enable_corruption = False
        # remove random pushing
        self.events.base_external_force_torque = None
        self.events.push_robot = None

rsl_rl_ppo_cfg.py

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

from isaaclab.utils import configclass

from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg


@configclass
class H1_2RoughPPORunnerCfg(RslRlOnPolicyRunnerCfg):
    num_steps_per_env = 24
    max_iterations = 3000
    save_interval = 50
    experiment_name = "H1_2_rough"
    empirical_normalization = False
    policy = RslRlPpoActorCriticCfg(
        init_noise_std=1.0,
        actor_hidden_dims=[512, 256, 128],
        critic_hidden_dims=[512, 256, 128],
        activation="elu",
    )
    algorithm = RslRlPpoAlgorithmCfg(
        value_loss_coef=1.0,
        use_clipped_value_loss=True,
        clip_param=0.2,
        entropy_coef=0.01,
        num_learning_epochs=5,
        num_mini_batches=4,
        learning_rate=1.0e-3,
        schedule="adaptive",
        gamma=0.99,
        lam=0.95,
        desired_kl=0.01,
        max_grad_norm=1.0,
    )


@configclass
class H1_2FlatPPORunnerCfg(H1_2RoughPPORunnerCfg):
    def __post_init__(self):
        super().__post_init__()

        self.max_iterations = 1000
        self.experiment_name = "H1_2_flat"
        self.policy.actor_hidden_dims = [128, 128, 128]
        self.policy.critic_hidden_dims = [128, 128, 128]

最后,在IsaacLab目录下执行训练脚本,就可以开始训练啦

./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task Isaac-Velocity-Rough-H1_2-v0 --headless


网站公告

今日签到

点亮在社区的每一天
去签到