将一个新的呆板人模子导入最新版isaacLab举行练习(以unitree H1_2为例)

[复制链接]
发表于 2025-10-1 23:18:13 | 显示全部楼层 |阅读模式
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”
  1. cd IsaacLab
  2. ./isaaclab.sh -p scripts/tools/convert_urdf.py \
  3. ~/unitree_rl_gym/resources/robots/h1_2/h1_2.urdf \
  4. source/isaaclab_assets/data/Robots/h1_2/h1_2.usd \
  5. --merge-joints --joint-stiffness 0.0 \
  6. --joint-damping 0.0 \
  7. --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{.*}                  .*
  1. H1_2_CFG = ArticulationCfg(
  2.     spawn=sim_utils.UsdFileCfg(
  3.         usd_path=f"/home/swanchan/IsaacLab/source/isaaclab_assets/data/Robots/h1_2/h1_2.usd",
  4.         activate_contact_sensors=True,
  5.         rigid_props=sim_utils.RigidBodyPropertiesCfg(
  6.             disable_gravity=False,
  7.             retain_accelerations=False,
  8.             linear_damping=0.0,
  9.             angular_damping=0.0,
  10.             max_linear_velocity=1000.0,
  11.             max_angular_velocity=1000.0,
  12.             max_depenetration_velocity=1.0,
  13.         ),
  14.         articulation_props=sim_utils.ArticulationRootPropertiesCfg(
  15.             enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=4
  16.         ),
  17.     ),
  18.     init_state=ArticulationCfg.InitialStateCfg(
  19.         pos=(0.0, 0.0, 1.05),
  20.         joint_pos={
  21.             ".*_hip_yaw.*": 0.0,
  22.             ".*_hip_roll.*": 0.0,
  23.             ".*_hip_pitch.*": -0.16,  # -9.17 degrees
  24.             ".*_knee.*": 0.36,  # 20.63 degrees
  25.             ".*_ankle_pitch.*": -0.2,  # -11.46 degrees
  26.             ".*_ankle_roll.*": 0.0,
  27.             "torso.*": 0.0,
  28.             ".*_shoulder_pitch.*": 0.4,  # 22.92 degrees
  29.             ".*_shoulder_roll.*": 0.0,
  30.             ".*_shoulder_yaw.*": 0.0,
  31.             ".*_elbow_pitch.*": 0.3,  # 17.19 degrees
  32.         },
  33.         joint_vel={".*": 0.0},
  34.     ),
  35.     soft_joint_pos_limit_factor=0.9,
  36.     actuators={
  37.         "legs": ImplicitActuatorCfg(
  38.             joint_names_expr=[".*_hip_yaw.*", ".*_hip_roll.*", ".*_hip_pitch.*", ".*_knee.*", "torso.*"],
  39.             effort_limit=300,
  40.             velocity_limit=100.0,
  41.             stiffness={
  42.                 ".*_hip_yaw.*": 200.0,
  43.                 ".*_hip_roll.*": 200.0,
  44.                 ".*_hip_pitch.*": 200.0,
  45.                 ".*_knee.*": 300.0,
  46.                 "torso.*": 200.0,
  47.             },
  48.             damping={
  49.                 ".*_hip_yaw.*": 2.5,
  50.                 ".*_hip_roll.*": 2.5,
  51.                 ".*_hip_pitch.*": 2.5,
  52.                 ".*_knee.*": 4.0,
  53.                 "torso.*": 5.0,
  54.             },
  55.         ),
  56.         "feet": ImplicitActuatorCfg(
  57.             joint_names_expr=[".*_ankle_pitch.*", ".*_ankle_roll.*"],
  58.             effort_limit=100,
  59.             velocity_limit=100.0,
  60.             stiffness={
  61.                 ".*_ankle_pitch.*": 40.0,
  62.                 ".*_ankle_roll.*": 40.0,
  63.             },
  64.             damping={
  65.                 ".*_ankle_pitch.*": 2.0,
  66.                 ".*_ankle_roll.*": 2.0,
  67.             },
  68.         ),
  69.         "arms": ImplicitActuatorCfg(
  70.             joint_names_expr=[".*_shoulder_pitch.*", ".*_shoulder_roll.*", ".*_shoulder_yaw.*", ".*_elbow_pitch.*"],
  71.             effort_limit=300,
  72.             velocity_limit=100.0,
  73.             stiffness={
  74.                 ".*_shoulder_pitch.*": 40.0,
  75.                 ".*_shoulder_roll.*": 40.0,
  76.                 ".*_shoulder_yaw.*": 40.0,
  77.                 ".*_elbow_pitch.*": 40.0,
  78.             },
  79.             damping={
  80.                 ".*_shoulder_pitch.*": 10.0,
  81.                 ".*_shoulder_roll.*": 10.0,
  82.                 ".*_shoulder_yaw.*": 10.0,
  83.                 ".*_elbow_pitch.*": 10.0,
  84.             },
  85.         ),
  86.     },
  87. )
  88. """Configuration for the Unitree H1_2 Humanoid robot."""
  89. H1_2_MINIMAL_CFG = H1_2_CFG.copy()
  90. 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

  1. # Copyright (c) 2022-2025, The Isaac Lab Project Developers.
  2. # All rights reserved.
  3. #
  4. # SPDX-License-Identifier: BSD-3-Clause
  5. import gymnasium as gym
  6. from . import agents
  7. ##
  8. # Register Gym environments.
  9. ##
  10. gym.register(
  11.     id="Isaac-Velocity-Rough-H1_2-v0",
  12.     entry_point="isaaclab.envs:ManagerBasedRLEnv",
  13.     disable_env_checker=True,
  14.     kwargs={
  15.         "env_cfg_entry_point": f"{__name__}.rough_env_cfg:H1_2RoughEnvCfg",
  16.         "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1_2RoughPPORunnerCfg",
  17.         "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
  18.     },
  19. )
  20. gym.register(
  21.     id="Isaac-Velocity-Rough-H1_2-Play-v0",
  22.     entry_point="isaaclab.envs:ManagerBasedRLEnv",
  23.     disable_env_checker=True,
  24.     kwargs={
  25.         "env_cfg_entry_point": f"{__name__}.rough_env_cfg:H1_2RoughEnvCfg_PLAY",
  26.         "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1_2RoughPPORunnerCfg",
  27.         "skrl_cfg_entry_point": f"{agents.__name__}:skrl_rough_ppo_cfg.yaml",
  28.     },
  29. )
  30. gym.register(
  31.     id="Isaac-Velocity-Flat-H1_2-v0",
  32.     entry_point="isaaclab.envs:ManagerBasedRLEnv",
  33.     disable_env_checker=True,
  34.     kwargs={
  35.         "env_cfg_entry_point": f"{__name__}.flat_env_cfg:H1_2FlatEnvCfg",
  36.         "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1_2FlatPPORunnerCfg",
  37.         "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml",
  38.     },
  39. )
  40. gym.register(
  41.     id="Isaac-Velocity-Flat-H1_2-Play-v0",
  42.     entry_point="isaaclab.envs:ManagerBasedRLEnv",
  43.     disable_env_checker=True,
  44.     kwargs={
  45.         "env_cfg_entry_point": f"{__name__}.flat_env_cfg:H1_2FlatEnvCfg_PLAY",
  46.         "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:H1_2FlatPPORunnerCfg",
  47.         "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml",
  48.     },
  49. )
复制代码
flat_env_cfg.py

  1. # Copyright (c) 2022-2025, The Isaac Lab Project Developers.
  2. # All rights reserved.
  3. #
  4. # SPDX-License-Identifier: BSD-3-Clause
  5. from isaaclab.utils import configclass
  6. from .rough_env_cfg import H1_2RoughEnvCfg
  7. @configclass
  8. class H1_2FlatEnvCfg(H1_2RoughEnvCfg):
  9.     def __post_init__(self):
  10.         # post init of parent
  11.         super().__post_init__()
  12.         # change terrain to flat
  13.         self.scene.terrain.terrain_type = "plane"
  14.         self.scene.terrain.terrain_generator = None
  15.         # no height scan
  16.         self.scene.height_scanner = None
  17.         self.observations.policy.height_scan = None
  18.         # no terrain curriculum
  19.         self.curriculum.terrain_levels = None
  20.         self.rewards.feet_air_time.weight = 1.0
  21.         self.rewards.feet_air_time.params["threshold"] = 0.6
  22. class H1_2FlatEnvCfg_PLAY(H1_2FlatEnvCfg):
  23.     def __post_init__(self) -> None:
  24.         # post init of parent
  25.         super().__post_init__()
  26.         # make a smaller scene for play
  27.         self.scene.num_envs = 50
  28.         self.scene.env_spacing = 2.5
  29.         # disable randomization for play
  30.         self.observations.policy.enable_corruption = False
  31.         # remove random pushing
  32.         self.events.base_external_force_torque = None
  33.         self.events.push_robot = None
复制代码
rough_env_cfg.py

  1. # Copyright (c) 2022-2025, The Isaac Lab Project Developers.
  2. # All rights reserved.
  3. #
  4. # SPDX-License-Identifier: BSD-3-Clause
  5. from isaaclab.managers import RewardTermCfg as RewTerm
  6. from isaaclab.managers import SceneEntityCfg
  7. from isaaclab.utils import configclass
  8. import isaaclab_tasks.manager_based.locomotion.velocity.mdp as mdp
  9. from isaaclab_tasks.manager_based.locomotion.velocity.velocity_env_cfg import LocomotionVelocityRoughEnvCfg, RewardsCfg
  10. ##
  11. # Pre-defined configs
  12. ##
  13. from isaaclab_assets import H1_2_CFG
  14. @configclass
  15. class H1_2Rewards(RewardsCfg):
  16.     """Reward terms for the MDP."""
  17.     termination_penalty = RewTerm(func=mdp.is_terminated, weight=-200.0)
  18.     lin_vel_z_l2 = None
  19.     track_lin_vel_xy_exp = RewTerm(
  20.         func=mdp.track_lin_vel_xy_yaw_frame_exp,
  21.         weight=1.0,
  22.         params={"command_name": "base_velocity", "std": 0.5},
  23.     )
  24.     track_ang_vel_z_exp = RewTerm(
  25.         func=mdp.track_ang_vel_z_world_exp, weight=1.0, params={"command_name": "base_velocity", "std": 0.5}
  26.     )
  27.     feet_air_time = RewTerm(
  28.         func=mdp.feet_air_time_positive_biped,
  29.         weight=0.25,
  30.         params={
  31.             "command_name": "base_velocity",
  32.             "sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*ankle.*"),
  33.             "threshold": 0.4,
  34.         },
  35.     )
  36.     feet_slide = RewTerm(
  37.         func=mdp.feet_slide,
  38.         weight=-0.25,
  39.         params={
  40.             "sensor_cfg": SceneEntityCfg("contact_forces", body_names=".*ankle.*"),
  41.             "asset_cfg": SceneEntityCfg("robot", body_names=".*ankle.*"),
  42.         },
  43.     )
  44.     # Penalize ankle joint limits
  45.     dof_pos_limits = RewTerm(
  46.         func=mdp.joint_pos_limits, weight=-1.0, params={"asset_cfg": SceneEntityCfg("robot", joint_names=".*_ankle.*")}
  47.     )
  48.     # Penalize deviation from default of the joints that are not essential for locomotion
  49.     joint_deviation_hip = RewTerm(
  50.         func=mdp.joint_deviation_l1,
  51.         weight=-0.2,
  52.         params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*_hip_yaw.*", ".*_hip_roll.*"])},
  53.     )
  54.     joint_deviation_arms = RewTerm(
  55.         func=mdp.joint_deviation_l1,
  56.         weight=-0.2,
  57.         params={"asset_cfg": SceneEntityCfg("robot", joint_names=[".*_shoulder_.*", ".*_elbow.*"])},
  58.     )
  59.     joint_deviation_torso = RewTerm(
  60.         func=mdp.joint_deviation_l1, weight=-0.1, params={"asset_cfg": SceneEntityCfg("robot", joint_names="torso.*")}
  61.     )
  62. @configclass
  63. class H1_2RoughEnvCfg(LocomotionVelocityRoughEnvCfg):
  64.     rewards: H1_2Rewards = H1_2Rewards()
  65.     def __post_init__(self):
  66.         # post init of parent
  67.         super().__post_init__()
  68.         # Scene
  69.         self.scene.robot = H1_2_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") # type: ignore
  70.         if self.scene.height_scanner:
  71.             self.scene.height_scanner.prim_path = "{ENV_REGEX_NS}/Robot/torso_link"
  72.         # Randomization
  73.         self.events.push_robot = None
  74.         self.events.add_base_mass = None
  75.         self.events.reset_robot_joints.params["position_range"] = (1.0, 1.0)
  76.         self.events.base_external_force_torque.params["asset_cfg"].body_names = [".*torso_link"]
  77.         self.events.reset_base.params = {
  78.             "pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)},
  79.             "velocity_range": {
  80.                 "x": (0.0, 0.0),
  81.                 "y": (0.0, 0.0),
  82.                 "z": (0.0, 0.0),
  83.                 "roll": (0.0, 0.0),
  84.                 "pitch": (0.0, 0.0),
  85.                 "yaw": (0.0, 0.0),
  86.             },
  87.         }
  88.         # Terminations
  89.         self.terminations.base_contact.params["sensor_cfg"].body_names = [".*torso_link"]
  90.         # Rewards
  91.         self.rewards.undesired_contacts = None
  92.         self.rewards.flat_orientation_l2.weight = -1.0
  93.         self.rewards.dof_torques_l2.weight = 0.0
  94.         self.rewards.action_rate_l2.weight = -0.005
  95.         self.rewards.dof_acc_l2.weight = -1.25e-7
  96.         # Commands
  97.         self.commands.base_velocity.ranges.lin_vel_x = (0.0, 1.0)
  98.         self.commands.base_velocity.ranges.lin_vel_y = (0.0, 0.0)
  99.         self.commands.base_velocity.ranges.ang_vel_z = (-1.0, 1.0)
  100.         # terminations
  101.         self.terminations.base_contact.params["sensor_cfg"].body_names = ".*torso_link"
  102. @configclass
  103. class H1_2RoughEnvCfg_PLAY(H1_2RoughEnvCfg):
  104.     def __post_init__(self):
  105.         # post init of parent
  106.         super().__post_init__()
  107.         # make a smaller scene for play
  108.         self.scene.num_envs = 50
  109.         self.scene.env_spacing = 2.5
  110.         self.episode_length_s = 40.0
  111.         # spawn the robot randomly in the grid (instead of their terrain levels)
  112.         self.scene.terrain.max_init_terrain_level = None
  113.         # reduce the number of terrains to save memory
  114.         if self.scene.terrain.terrain_generator is not None:
  115.             self.scene.terrain.terrain_generator.num_rows = 5
  116.             self.scene.terrain.terrain_generator.num_cols = 5
  117.             self.scene.terrain.terrain_generator.curriculum = False
  118.         self.commands.base_velocity.ranges.lin_vel_x = (1.0, 1.0)
  119.         self.commands.base_velocity.ranges.lin_vel_y = (0.0, 0.0)
  120.         self.commands.base_velocity.ranges.ang_vel_z = (-1.0, 1.0)
  121.         self.commands.base_velocity.ranges.heading = (0.0, 0.0)
  122.         # disable randomization for play
  123.         self.observations.policy.enable_corruption = False
  124.         # remove random pushing
  125.         self.events.base_external_force_torque = None
  126.         self.events.push_robot = None
复制代码
rsl_rl_ppo_cfg.py

  1. # Copyright (c) 2022-2025, The Isaac Lab Project Developers.
  2. # All rights reserved.
  3. #
  4. # SPDX-License-Identifier: BSD-3-Clause
  5. from isaaclab.utils import configclass
  6. from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg
  7. @configclass
  8. class H1_2RoughPPORunnerCfg(RslRlOnPolicyRunnerCfg):
  9.     num_steps_per_env = 24
  10.     max_iterations = 3000
  11.     save_interval = 50
  12.     experiment_name = "H1_2_rough"
  13.     empirical_normalization = False
  14.     policy = RslRlPpoActorCriticCfg(
  15.         init_noise_std=1.0,
  16.         actor_hidden_dims=[512, 256, 128],
  17.         critic_hidden_dims=[512, 256, 128],
  18.         activation="elu",
  19.     )
  20.     algorithm = RslRlPpoAlgorithmCfg(
  21.         value_loss_coef=1.0,
  22.         use_clipped_value_loss=True,
  23.         clip_param=0.2,
  24.         entropy_coef=0.01,
  25.         num_learning_epochs=5,
  26.         num_mini_batches=4,
  27.         learning_rate=1.0e-3,
  28.         schedule="adaptive",
  29.         gamma=0.99,
  30.         lam=0.95,
  31.         desired_kl=0.01,
  32.         max_grad_norm=1.0,
  33.     )
  34. @configclass
  35. class H1_2FlatPPORunnerCfg(H1_2RoughPPORunnerCfg):
  36.     def __post_init__(self):
  37.         super().__post_init__()
  38.         self.max_iterations = 1000
  39.         self.experiment_name = "H1_2_flat"
  40.         self.policy.actor_hidden_dims = [128, 128, 128]
  41.         self.policy.critic_hidden_dims = [128, 128, 128]
复制代码
末了,在IsaacLab目次下实行练习脚本,就可以开始练习啦
  1. ./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task Isaac-Velocity-Rough-H1_2-v0 --headless
复制代码
免责声明:如果侵犯了您的权益,请联系站长,我们会及时删除侵权内容,谢谢合作!更多信息从访问主页:qidao123.com:ToB企服之家,中国第一个企服评测及商务社交产业平台。

本帖子中包含更多资源

您需要 登录 才可以下载或查看,没有账号?立即注册

×
回复

使用道具 举报

登录后关闭弹窗

登录参与点评抽奖  加入IT实名职场社区
去登录
快速回复 返回顶部 返回列表