编写资产配置#

本指南详细介绍了创建 ArticulationCfg 的过程。 ArticulationCfg 是定义Isaac Lab中 Articulation 属性的配置对象。

备注

在本指南中,我们只涵盖了创建 ArticulationCfg 的过程,但创建任何其他资产配置对象的过程类似。

我们将使用Cartpole示例来演示如何创建 ArticulationCfg 。 Cartpole是一个简单的机器人,由一个连接到杆的小车组成。 小车可以沿着轨道自由移动,杆可以在小车周围自由旋转。该配置示例的文件为

source/isaaclab_assets/isaaclab_assets/robots/cartpole.py.

Cartpole配置代码
 1# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
 2# All rights reserved.
 3#
 4# SPDX-License-Identifier: BSD-3-Clause
 5
 6"""Configuration for a simple Cartpole robot."""
 7
 8
 9import isaaclab.sim as sim_utils
10from isaaclab.actuators import ImplicitActuatorCfg
11from isaaclab.assets import ArticulationCfg
12from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR
13
14##
15# Configuration
16##
17
18CARTPOLE_CFG = ArticulationCfg(
19    spawn=sim_utils.UsdFileCfg(
20        usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Classic/Cartpole/cartpole.usd",
21        rigid_props=sim_utils.RigidBodyPropertiesCfg(
22            rigid_body_enabled=True,
23            max_linear_velocity=1000.0,
24            max_angular_velocity=1000.0,
25            max_depenetration_velocity=100.0,
26            enable_gyroscopic_forces=True,
27        ),
28        articulation_props=sim_utils.ArticulationRootPropertiesCfg(
29            enabled_self_collisions=False,
30            solver_position_iteration_count=4,
31            solver_velocity_iteration_count=0,
32            sleep_threshold=0.005,
33            stabilization_threshold=0.001,
34        ),
35    ),
36    init_state=ArticulationCfg.InitialStateCfg(
37        pos=(0.0, 0.0, 2.0), joint_pos={"slider_to_cart": 0.0, "cart_to_pole": 0.0}
38    ),
39    actuators={
40        "cart_actuator": ImplicitActuatorCfg(
41            joint_names_expr=["slider_to_cart"],
42            effort_limit_sim=400.0,
43            stiffness=0.0,
44            damping=10.0,
45        ),
46        "pole_actuator": ImplicitActuatorCfg(
47            joint_names_expr=["cart_to_pole"], effort_limit_sim=400.0, stiffness=0.0, damping=0.0
48        ),
49    },
50)
51"""Configuration for a simple Cartpole robot."""

定义生成配置#

生成基本物体到场景中 教程中所述,生成配置定义要生成的资产的属性。此生成可能以程序方式进行,也可能通过现有的资产文件(例如USD或URDF)进行。在本例中,我们将从USD文件生成Cartpole。

从USD文件生成资产时,我们定义其 UsdFileCfg 。此配置对象接收以下参数:

最后两个参数是可选的。如果未指定,它们将保持在USD文件中的默认值。

spawn=sim_utils.UsdFileCfg(
    usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Classic/Cartpole/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,
    ),
),

如要从URDF文件中导入关节而不是从USD文件中导入,你可以用 UrdfFileCfg 替换 UsdFileCfg 。更多详情,请查看API文档。

定义初始状态#

每个资产都需要通过其配置在仿真中定义其初始或 默认 状态。此配置存储在资产的默认状态缓冲区中,当需要重置资产状态时,可以访问这些缓冲区。

备注

资产的初始状态是根据其本地环境框架定义的。然后,当重置资产状态时,需要将其转换为全局仿真框架。更多详情,请查看 与关节交互 教程。

对于关节, InitialStateCfg 对象定义了关节根部的初始状态以及所有关节的初始状态。在本例中,我们将在XY平面的原点处生成Cartpole,在Z高度为2.0米处。同时,关节位置和速度设置为0.0。

init_state=ArticulationCfg.InitialStateCfg(
    pos=(0.0, 0.0, 2.0), joint_pos={"slider_to_cart": 0.0, "cart_to_pole": 0.0}
),

定义执行器配置#

执行器是关节中的关键组件。通过此配置,可以定义要使用的执行器模型类型。我们可以使用物理引擎提供的内部执行器模型(即隐式执行器模型),也可以使用用户定义的方程系统控制的自定义执行器模型(即显式执行器模型)。有关执行器的更多详情,请参见 执行器

cartpole的关节具有两个执行器,分别对应于它的每个关节:cart_to_poleslider_to_cart 。我们对这些执行器使用两种不同的执行器模型作为示例。但是,由于它们都使用相同的执行器模型,可以将它们组合成一个单独的执行器模型。

使用分开的执行器模型进行执行器模型配置
actuators={
    "cart_actuator": ImplicitActuatorCfg(
        joint_names_expr=["slider_to_cart"],
        effort_limit_sim=400.0,
        stiffness=0.0,
        damping=10.0,
    ),
    "pole_actuator": ImplicitActuatorCfg(
        joint_names_expr=["cart_to_pole"], effort_limit_sim=400.0, stiffness=0.0, damping=0.0
    ),
},
使用单个执行器模型进行执行器模型配置
actuators={
   "all_joints": ImplicitActuatorCfg(
      joint_names_expr=[".*"],
      effort_limit=400.0,
      velocity_limit=100.0,
      stiffness={"slider_to_cart": 0.0, "cart_to_pole": 0.0},
      damping={"slider_to_cart": 10.0, "cart_to_pole": 0.0},
   ),
},

ActuatorCfg 速度/力矩限制考虑#

在 IsaacLab v1.4.0 中,普通的 velocity_limiteffort_limit 属性 没有 被一致地传入物理求解器中:

  • 隐式执行器 - 速度限制被忽略(在仿真中从未设置) - effort_limit 已设置到仿真中

  • 显式执行器 - velocity_limit 和 effort_limit 仅由驱动模型使用,而不是由求解器使用

在 v2.0.1 中,我们意外地更改了这一点: 所有 velocity_limit 和 effort_limit ,无论是隐式还是显式,都被应用到了求解器上。这导致许多在旧的默认无上限求解器限制下进行训练的任务出现问题。

为了恢复原始行为,同时仍然给用户完全控制求解器限制,我们引入了两个新标志:

  • velocity_limit_sim 设置物理求解器在仿真中的最大关节速度上限。

  • effort_limit_sim 设置仿真中物理求解器的最大关节力矩上限。

这些明确定义了求解器在仿真级别上的关节速度和关节力矩的限制。

另一方面, velocity_limit 和 effort_limit 对所有显式执行器中的扭矩计算仿真了电机的硬件级约束,而不是限制仿真级约束。对于隐式执行器,由于它们不仿真电动机硬件限制,velocity_limit 在 v2.1.1 版本中被移除,并标记为不推荐使用。这保持了与 v1.4.0 版本相同的行为。 最终,对于隐式执行器,velocity_limiteffort_limit 将被标记为不推荐使用,仅保留 velocity_limit_simeffort_limit_sim

限制选项比较#

属性

隐式执行器

显式执行器

velocity_limit

已弃用( velocity_limit_sim 的别名)

被模型(例如直流电机)使用,未设置到仿真中

effort_limit

已弃用( effort_limit_sim 的别名)

被模型使用,未设置到仿真中。

velocity_limit_sim

设置到仿真中

设置到仿真中

effort_limit_sim

设置到仿真中

设置到仿真中

想要调整基础物理求解器限制的用户应当设置 _sim 标志。

USD vs. ActuatorCfg 差异解决#

USD 具有默认值,并且 ActuatorCfg 可以指定为 None,或者有时会令人困惑的是覆盖值实际写入仿真中的规则。解决方案遵循这些简单规则,每个关节和每个属性:

USD vs. ActuatorCfg 的分辨率规则#

条件

驱动器配置值

应用

未提供覆盖

未指定

USD Value

提供覆盖

用户的 ActuatorCfg

与 ActuatorCfg 相同

深入研究 USD 有时可能是不方便的,为了帮助弄清所写的确切值,我们设计了一个标志: actuator_value_resolution_debug_print ,以帮助用户弄清楚在仿真中使用了哪个确切值。

每当在用户的 ActuatorCfg(或未指定)中覆盖执行器参数时,我们将其与从USD定义中读取的值进行比较,并记录任何差异。对于每个关节和每个属性,如果找到不匹配的值,我们记录下解决方案:

  1. USD 值 USD资产解析的默认限制或增益。

  2. ActuatorCfg 值 用户提供的覆盖值(如果没有提供则为 “未指定” )。

  3. 应用 实际用于仿真的最终数值: 如果用户没有覆盖它,这将与USD值匹配;否则,它将反映用户的设置。

此解决方案信息仅在存在差异时作为警告表格发出。以下是您将看到的示例:

+----------------+--------------------+---------------------+----+-------------+--------------------+----------+
|     Group      |      Property      |         Name        | ID |  USD Value  | ActuatorCfg Value  | Applied  |
+----------------+--------------------+---------------------+----+-------------+--------------------+----------+
| panda_shoulder | velocity_limit_sim |    panda_joint1     |  0 |    2.17e+00 |   Not Specified    | 2.17e+00 |
|                |                    |    panda_joint2     |  1 |    2.17e+00 |   Not Specified    | 2.17e+00 |
|                |                    |    panda_joint3     |  2 |    2.17e+00 |   Not Specified    | 2.17e+00 |
|                |                    |    panda_joint4     |  3 |    2.17e+00 |   Not Specified    | 2.17e+00 |
|                |     stiffness      |    panda_joint1     |  0 |    2.29e+04 |      8.00e+01      | 8.00e+01 |
|                |                    |    panda_joint2     |  1 |    2.29e+04 |      8.00e+01      | 8.00e+01 |
|                |                    |    panda_joint3     |  2 |    2.29e+04 |      8.00e+01      | 8.00e+01 |
|                |                    |    panda_joint4     |  3 |    2.29e+04 |      8.00e+01      | 8.00e+01 |
|                |      damping       |    panda_joint1     |  0 |    4.58e+03 |      4.00e+00      | 4.00e+00 |
|                |                    |    panda_joint2     |  1 |    4.58e+03 |      4.00e+00      | 4.00e+00 |
|                |                    |    panda_joint3     |  2 |    4.58e+03 |      4.00e+00      | 4.00e+00 |
|                |                    |    panda_joint4     |  3 |    4.58e+03 |      4.00e+00      | 4.00e+00 |
|                |      armature      |    panda_joint1     |  0 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |                    |    panda_joint2     |  1 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |                    |    panda_joint3     |  2 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |                    |    panda_joint4     |  3 |    0.00e+00 |   Not Specified    | 0.00e+00 |
| panda_forearm  | velocity_limit_sim |    panda_joint5     |  4 |    2.61e+00 |   Not Specified    | 2.61e+00 |
|                |                    |    panda_joint6     |  5 |    2.61e+00 |   Not Specified    | 2.61e+00 |
|                |                    |    panda_joint7     |  6 |    2.61e+00 |   Not Specified    | 2.61e+00 |
|                |     stiffness      |    panda_joint5     |  4 |    2.29e+04 |      8.00e+01      | 8.00e+01 |
|                |                    |    panda_joint6     |  5 |    2.29e+04 |      8.00e+01      | 8.00e+01 |
|                |                    |    panda_joint7     |  6 |    2.29e+04 |      8.00e+01      | 8.00e+01 |
|                |      damping       |    panda_joint5     |  4 |    4.58e+03 |      4.00e+00      | 4.00e+00 |
|                |                    |    panda_joint6     |  5 |    4.58e+03 |      4.00e+00      | 4.00e+00 |
|                |                    |    panda_joint7     |  6 |    4.58e+03 |      4.00e+00      | 4.00e+00 |
|                |      armature      |    panda_joint5     |  4 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |                    |    panda_joint6     |  5 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |                    |    panda_joint7     |  6 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |      friction      |    panda_joint5     |  4 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |                    |    panda_joint6     |  5 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |                    |    panda_joint7     |  6 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|  panda_hand    | velocity_limit_sim | panda_finger_joint1 |  7 |    2.00e-01 |   Not Specified    | 2.00e-01 |
|                |                    | panda_finger_joint2 |  8 |    2.00e-01 |   Not Specified    | 2.00e-01 |
|                |     stiffness      | panda_finger_joint1 |  7 |    1.00e+06 |      2.00e+03      | 2.00e+03 |
|                |                    | panda_finger_joint2 |  8 |    1.00e+06 |      2.00e+03      | 2.00e+03 |
|                |      armature      | panda_finger_joint1 |  7 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |                    | panda_finger_joint2 |  8 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |      friction      | panda_finger_joint1 |  7 |    0.00e+00 |   Not Specified    | 0.00e+00 |
|                |                    | panda_finger_joint2 |  8 |    0.00e+00 |   Not Specified    | 0.00e+00 |
+----------------+--------------------+---------------------+----+-------------+--------------------+----------+

为保持日志的清晰, actuator_value_resolution_debug_print 默认为 False,请在需要时记得将其打开。