建模#

引言#

MuJoCo 可以加载其原生的 MJCF 格式以及流行但功能受限的 URDF 格式的 XML 模型文件。本章是 MJCF 建模指南。参考手册可在 XML 参考 章中找到。URDF 文档可在其他地方找到;这里我们仅描述 MuJoCo 特有的 URDF 扩展

MJCF 模型可以表示具有广泛特性和模型元素的复杂动力学系统。访问所有这些特性需要丰富的建模格式,如果设计时未考虑可用性,这可能会变得繁琐。因此,我们努力将 MJCF 设计为一种可扩展的格式,允许用户从小处着手,稍后再构建更详细的模型。在这方面特别有用的是受 HTML 中内联层叠样式表 (CSS) 思想启发的广泛的 默认设置 机制。它使用户能够快速创建新模型并进行实验。通过可用于重新配置仿真管道的众多 选项 以及使模型编辑成为交互式过程的快速重新加载功能,进一步有助于实验。

可以将 MJCF 视为建模格式和编程语言的混合体。它有一个内置编译器,这是通常与编程语言相关的概念。虽然 MJCF 不具备通用编程语言的功能,但会根据模型的构建方式自动调用一些复杂的编译时计算。

加载模型#

如概述章中 模型实例 中所述,MuJoCo 模型可以从 MJCF 或 URDF 格式的纯文本 XML 文件加载,然后编译成低级 mjModel。或者,也可以直接从二进制 MJB 文件加载先前保存的 mjModel - 其格式未文档化,但本质上是 mjModel 内存缓冲区的副本。MJCF 和 URDF 文件使用 mj_loadXML 加载,而 MJB 文件使用 mj_loadModel 加载。

加载 XML 文件时,它首先在内部使用 TinyXML 解析器解析成文档对象模型 (DOM)。然后处理此 DOM 并将其转换为高级 mjSpec 对象。转换取决于模型格式 - 模型格式是从 XML 文件中的顶级元素推断出来的,而不是从文件扩展名推断出来的。请记住,有效的 XML 文件具有唯一的顶级元素。对于 MJCF,此元素必须是 mujoco,对于 URDF,必须是 robot

编译模型#

一旦创建了高级 mjSpec — 通过加载 MJCF 文件或 URDF 文件,或 编程方式 — 它就会被编译成 mjModel。编译独立于加载,这意味着无论如何创建 mjSpec,编译器都以相同的方式工作。解析器和编译器都会执行大量的错误检查,并在遇到第一个错误时中止。生成的错误消息包含 XML 文件中的行号和列号,并且是自解释的,因此我们在此不对此进行文档说明。解析器使用自定义模式以确保文件结构、元素和属性有效。然后,编译器会应用许多额外的语义检查。最后,执行编译模型的仿真一步,并拦截任何运行时错误。后者通过(临时)将 mju_user_error 设置为指向一个抛出 C++ 异常的函数来完成;如果需要,用户可以在运行时实现类似的错误拦截功能。

整个解析和编译过程非常快——如果模型不包含大型网格或需要通过仿真计算的执行器长度范围,则不到一秒。这使得交互式设计模型成为可能,通过频繁重新加载和可视化更改。请注意,simulate.cc 代码示例有一个用于重新加载当前模型的键盘快捷键 (Ctrl+L)。

保存模型#

一个 MJCF 模型可以由多个(包含的)XML 文件以及从 XML 中引用的网格、高度场和纹理组成。编译后,所有这些文件的内容会组装到 mjModel 中,可以使用 mj_saveModel 将其保存到二进制 MJB 文件中。MJB 是一个独立的文件,不引用任何其他文件。它加载也更快。因此,我们建议将常用模型保存为 MJB,并在需要进行仿真时加载它们。

也可以使用 mj_saveLastXML 将编译后的 mjSpec 保存为 MJCF。如果在编译后修改了相应 mjModel 中的任何实数值字段(这不常见,但例如在系统辨识应用中可能发生),则在保存前会自动将修改复制回 mjSpec 中。请注意,不能在编译模型中进行结构更改。XML 编写器试图生成最小的 MJCF 文件,该文件保证编译成相同的模型,仅存在由实数值的纯文本表示引起的微不足道的数字差异。生成的文件可能与原始文件结构不同,因为 MJCF 具有许多用户便利功能,允许以不同的方式指定同一模型。XML 编写器使用 MJCF 的一个“规范”子集,其中所有坐标都是局部的,并且所有物体位置、方向和惯性属性都明确指定。在计算章中,我们展示了一个 示例 MJCF 文件和相应的 已保存示例

编辑模型#

从 MuJoCo 3.2 版本开始,可以使用 mjSpec 结构体和相关 API 创建和修改模型。有关更多文档,请参阅 模型编辑 章。

MJCF 机制#

MJCF 使用了几种跨越多个模型元素的模型创建机制。为避免重复,我们仅在本节中详细介绍它们一次。这些机制不对应于计算章中引入的新仿真概念。它们的作用是简化 MJCF 模型的创建,并使使用不同数据格式成为可能,而无需手动转换为规范格式。

运动学树#

MJCF 文件的主要部分是嵌套的 body 元素创建的 XML 树。顶级 body 是特殊的,称为 worldbody。这种树组织与 URDF 不同,URDF 中创建链接集合,然后使用指定子链接和父链接的关节连接它们。在 MJCF 中,子 body 在 XML 意义上实际上是父 body 的子节点。

当在 body 内部定义 joint 时,其功能不是连接父子节点,而是在它们之间创建运动自由度。如果在给定 body 中未定义关节,则该 body 将焊接到其父节点。MJCF 中的一个 body 可以包含多个关节,因此无需引入虚拟 body 来创建复合关节。只需在同一 body 中定义构成所需复合关节的所有基本关节即可。例如,可以使用两个滑动关节和一个铰链关节来模拟在平面中运动的 body。

其他 MJCF 元素可以在嵌套 body 元素创建的树中定义,特别是 jointgeomsitecameralight。当在 body 中定义元素时,它固定在该 body 的局部坐标系中并始终随之移动。引用多个 body 或根本不引用 body 的元素在运动学树外部的单独部分中定义。

默认设置#

MJCF 具有一套完善的默认属性值设置机制。这使得我们可以拥有大量展示软件丰富功能所需的元素和属性,同时编写简短易读的模型文件。该机制进一步使用户能够在一个地方进行更改,并使其在整个模型中传播。我们先从一个示例开始。

<mujoco>
  <default class="main">
    <geom rgba="1 0 0 1"/>
    <default class="sub">
      <geom rgba="0 1 0 1"/>
    </default>
  </default>

  <worldbody>
    <geom type="box"/>
    <body childclass="sub">
      <geom type="ellipsoid"/>
      <geom type="sphere" rgba="0 0 1 1"/>
      <geom type="cylinder" class="main"/>
    </body>
  </worldbody>
</mujoco>

此示例实际上无法编译,因为缺少一些必需信息,但此处我们仅关注 geom rgba 值的设置。上面创建的四个 geom 将通过默认设置机制获得以下 rgba 值

geom 类型

geom rgba

box

1 0 0 1

ellipsoid

0 1 0 1

sphere

0 0 1 1

cylinder

1 0 0 1

box 使用顶级默认类“main”来设置其未定义属性的值,因为未指定其他类。body 指定了 childclass “sub”,导致此 body 的所有子节点(以及它们的所有子节点等)都使用类“sub”,除非另有指定。因此 ellipsoid 使用类“sub”。sphere 显式定义了 rgba,这会覆盖默认设置。cylinder 指定了默认类“main”,因此它使用“main”而不是“sub”,即使后者是在包含 geom 的 body 的 childclass 属性中指定的。

现在我们描述一般规则。MuJoCo 支持无限数量的默认类,这些类由 XML 中可能嵌套的 default 元素创建。每个类都有一个唯一名称——这是一个必需的属性,除了顶级类,如果未定义其名称则为“main”。每个类还具有一套完整的虚拟模型元素,其属性设置如下。当在一个默认类中定义另一个默认类时,子类会自动继承父类的所有属性值。然后,它可以通过定义相应的属性来覆盖其中一些或全部属性。顶级默认类没有父类,因此其属性被初始化为内部默认值,这些值在 参考章节 中显示。

默认类中包含的虚拟元素不是模型的一部分;它们仅用于初始化实际模型元素的属性值。当实际元素首次创建时,其所有属性都从当前活动的默认类中的相应虚拟元素复制。始终存在一个活动的默认类,可以通过以下三种方式之一确定。如果在当前元素或其任何祖先 body 中未指定类,则使用顶级类(无论其名称是“main”还是其他)。如果当前元素中未指定类,但其一个或多个祖先 body 指定了 childclass,则使用最近祖先 body 的 childclass。如果当前元素指定了类,则无论其祖先 body 中的任何 childclass 属性如何,都使用该类。

一些属性,例如 body 惯性,可以处于特殊的未定义状态。这指示编译器从其他信息推断相应的值,在此例中是附加到 body 的 geom 的惯性。未定义状态不能在 XML 文件中输入。因此,一旦在给定类中定义了属性,则在该类或其任何子类中都不能将其设置为未定义。因此,如果目标是使给定模型元素中的某个属性未定义,则它必须在活动的默认类中是未定义的。

这里还有一个最后的转折点是执行器。它们是不同的,因为一些执行器相关的元素实际上是快捷方式,而快捷方式以不明显的方式与默认设置机制交互。这将在下面的 执行器快捷方式 部分中解释。

坐标系#

在运动学树中定义的所有元素的位置和方向都以局部坐标表示,对于 body,是相对于父 body 的局部坐标,对于 geom、joint、site、camera 和 light,是相对于包含该元素的 body 的局部坐标。

一个相关属性是 compiler/angle。它指定 MJCF 文件中的角度是以度还是弧度表示(编译后,角度始终以弧度表示)。

位置使用以下方式指定

pos: real(3), “0 0 0”

相对于父节点的位置。

框架方向#

一些模型元素与其关联有右手空间框架。这些是运动学树中定义的所有元素,除了关节。空间框架由其位置和方向定义。指定 3D 位置是直观的,但指定 3D 方向可能具有挑战性。这就是 MJCF 提供几种替代机制的原因。无论用户选择哪种机制,框架方向在内部始终被转换为单位四元数。回顾一下,围绕单位向量 \((x, y, z)\) 定义的轴旋转角度 \(a\) 的 3D 旋转对应于四元数 \((\cos(a/2), \: \sin(a/2) \cdot (x, y, z))\)。另请记住,每个 3D 方向都可以通过围绕某个轴的单个 3D 旋转唯一指定。

所有具有空间框架的 MJCF 元素都允许以下列出的五个属性。框架方向最多使用其中一个属性指定。quat 属性的默认值对应于零旋转,而其他属性在特殊的未定义状态下初始化。因此,如果用户未指定这些属性中的任何一个,则框架不旋转。

quat: real(4), “1 0 0 0”

如果已知四元数,这是指定框架方向的首选方法,因为它不涉及转换。相反,它会在编译期间归一化为单位长度并复制到 mjModel 中。当模型保存为 MJCF 时,所有框架方向都使用此属性表示为四元数。

axisangle: real(4), optional

这些是上面提到的量 \((x, y, z, a)\)。最后一个数是旋转角度,以度或弧度为单位,具体取决于 compilerangle 属性的指定。前三个数确定一个 3D 向量,该向量是旋转轴。此向量在编译期间被归一化为单位长度,因此用户可以指定任意非零长度的向量。请记住旋转是右手的;如果向量 \((x, y, z)\) 的方向反转,将导致相反的旋转。改变 \(a\) 的符号也可以用于指定相反的旋转。

euler: real(3), optional

绕三个坐标轴的旋转角度。应用这些旋转的轴的顺序由 compilereulerseq 属性确定,并且对整个模型相同。

xyaxes: real(6), optional

前 3 个数是框架的 X 轴。后 3 个数是框架的 Y 轴,它会自动与 X 轴正交。然后 Z 轴定义为 X 轴和 Y 轴的叉积。

zaxis: real(3), optional

框架的 Z 轴。编译器找到将向量 \((0, 0, 1)\) 映射到此处指定的向量的最小旋转。这隐式确定了框架的 X 轴和 Y 轴。这对于绕 Z 轴具有旋转对称性的 geom 以及灯光很有用 - 灯光沿其框架的 Z 轴定向。

求解器参数#

计算章的求解器 参数 部分解释了确定 MuJoCo 中约束行为的量 \(d, b, k\) 的数学和算法意义。此处我们解释如何设置它们。设置通过属性 solrefsolimp 间接完成,这些属性可在所有涉及约束的 MJCF 元素中使用。这些参数可以按约束或按默认类进行调整,或者保持未定义状态——在这种情况下,MuJoCo 使用下面显示的内部默认值。另请注意 option 中提供的覆盖机制;它可以在运行时更改所有与接触相关的求解器参数,以便交互式地尝试参数设置或实现数值优化的连续方法。

此处我们重点关注单个标量约束。使用与计算章略有不同的符号,设 \(\ac\) 表示加速度,\(v\) 表示速度,\(r\) 表示位置或残差(在摩擦维度中定义为 0),\(k\)\(b\) 是用于定义参考加速度 \(\ar = -b v - k r\) 的虚拟弹簧的刚度和阻尼。设 \(d\) 是约束阻抗,\(\au\) 是没有约束力时的加速度。我们之前的分析表明,约束空间的动力学近似为

(1)#\[\ac + d \cdot (b v + k r) = (1 - d)\cdot \au \]

再次,用户控制的参数是 \(d, b, k\)。其余量是系统状态的函数,并在每个时间步自动计算。

阻抗#

我们首先解释约束阻抗 \(d\)

阻抗的直观描述

阻抗 \(d \in (0, 1)\) 对应于约束的产生力的能力。较小的 \(d\) 值对应于弱约束,而较大的 \(d\) 值对应于强约束。阻抗始终影响约束,尤其是在系统静止时。阻抗使用 solimp 属性设置。

回想一下,\(d\) 必须介于 0 和 1 之间;MuJoCo 在内部将其限制在 [mjMINIMP mjMAXIMP] 范围,目前设置为 [0.0001 0.9999]。它使求解器在无力加速度 \(\au\) 和参考加速度 \(\ar\) 之间进行插值。用户可以将 \(d\) 设置为常数,或者利用其插值属性使其依赖于位置,即作为约束违反 \(r\) 的函数。依赖于位置的阻抗可用于模拟物体周围的软接触层,或定义随着违反程度增大而增强的等式约束(例如,用于近似回弹间隙)。\(d(r)\) 函数的形状由特定元素的参数向量 solimp 确定。

solimp : real(5), “0.9 0.95 0.001 0.5 2”

这五个数字(\(d_0\), \(d_\text{width}\), \(\text{width}\), \(\text{midpoint}\), \(\text{power}\))参数化 \(d(r)\) – 作为约束违反 \(r\) 的函数的阻抗 \(d\)

前 3 个值表明,当 \(r\)\(0\) 变化到 \(\text{width}\) 时,阻抗将平滑变化

\[d(0) = d_0, \quad d(\text{width}) = d_\text{width} \]

第 4 个和第 5 个值,\(\text{midpoint}\)\(\text{power}\),控制介于 \(d_0\)\(d_\text{width}\) 之间的 Sigmoid 函数的形状,如下面图所示。图显示了两个反射的 Sigmoid 函数,因为阻抗 \(d(r)\) 取决于 \(r\) 的绝对值。\(\text{power}\)(用于生成函数的曲线的次数)必须大于等于 1。\(\text{midpoint}\)(指定拐点)必须介于 0 和 1 之间,并以 \(\text{width}\) 为单位表示。请注意,当 \(\text{power}\) 为 1 时,函数是线性的,与 \(\text{midpoint}\) 无关。

_images/impedance.png _images/impedance_dark.png

这些图显示了垂直轴上的阻抗 \(d(r)\),作为水平轴上的约束违反 \(r\) 的函数。

对于等式约束,\(r\) 是约束违反。对于限位、椭圆锥的法线方向和棱锥的所有方向,\(r\) 是(限位或接触)距离减去约束激活的边距;对于接触,此边距是 margin-gap。当 \(r < 0\)(穿透)时,限位和接触约束激活。

对于摩擦损失或椭圆锥的摩擦维度,违反 \(r\) 恒定为零,因此只有 \(d(0)\) 影响这些约束,所有其他 solimp 值都将被忽略。

平滑性和可微性

对于完全平滑(可微)的动力学,限位和接触应具有 \(d_0=0\)solimp[0]=0)。特别是对于接触,应牢记与 geom 相关的求解器参数的 混合规则。另请参阅 计算章mjd_transitionFD 文档中关于导数的讨论。

参考#

接下来,我们解释刚度 \(k\) 和阻尼 \(b\) 的设置,它们控制参考加速度 \(\ar\)

参考加速度的直观描述

参考加速度 \(\ar\) 决定了约束为了纠正违反而试图实现的运动。想象一个物体落到平面上。撞击时,约束将产生一个法向力,试图使用特定运动来纠正穿透;此运动就是参考加速度。

理解参考加速度的另一种方法是考虑 计算章 中描述的未建模变形变量。想象两个物体被压在一起,导致接触处发生变形。现在快速将物体拉开;变形恢复到未变形状态的运动就是参考加速度。

此加速度由两个数字定义:刚度 \(k\) 和阻尼 \(b\),它们可以直接设置,或重新参数化为质量-弹簧-阻尼系统(一个 谐振子)的时间常数和阻尼比。参考加速度由 solref 属性控制。

此属性有两种格式,由数字的符号决定。如果两个数字都为正,则视为 \((\text{timeconst}, \text{dampratio})\) 格式。如果为负,则为“直接” \((-\text{stiffness}, -\text{damping})\) 格式。

残差恒定为 0 的摩擦约束具有一阶动力学,下面质量-弹簧-阻尼分析不适用。在这种情况下,时间常数是约束速度指数衰减的速率,阻尼比被忽略。等效地,在直接格式中,\(\text{stiffness}\) 被忽略。

solref : real(2), “0.02 1”

我们首先描述默认的正数值格式,其中两个数字是 \((\text{timeconst}, \text{dampratio})\)

这里的想法是根据质量-弹簧-阻尼系统的时间常数和阻尼比重新参数化模型。我们所说的“时间常数”是指固有频率的倒数乘以阻尼比。在这种情况下,我们使用质量-弹簧-阻尼模型在适当缩放后计算 \(k, b\)。请注意,有效刚度 \(d(r) \cdot k\) 和阻尼 \(d(r) \cdot b\) 由阻抗 \(d(r)\) 缩放,后者是距离 \(r\) 的函数。因此,除非我们完全撤销由 \(d\) 进行的缩放,否则我们无法始终实现指定的质量-弹簧-阻尼特性。但后者是不希望的,因为它会破坏插值特性,特别是 \(d=0\) 的极限将不再禁用约束。相反,我们缩放刚度和阻尼,以便阻尼比保持恒定,而时间常数在 \(d(r)\) 变小时增加。缩放公式为

\[\begin{aligned} b &= 2 / (d_\text{width}\cdot \text{timeconst}) \\ k &= d(r) / (d_\text{width}^2 \cdot \text{timeconst}^2 \cdot \text{dampratio}^2) \\ \end{aligned} \]

timeconst 参数应至少是仿真时间步的两倍大,否则系统相对于数值积分器(特别是在使用 Euler 积分时)可能会变得太硬,仿真可能会变得不稳定。这是内部强制执行的,除非 flagrefsafe 属性设置为 false。\(\text{dampratio}\) 参数通常设置为 1,对应于临界阻尼。较小的值会导致欠阻尼或弹性约束,而较大的值会导致过阻尼约束。将上述公式与 (1) 结合,我们可以得出以下结果。如果使用正数格式给出参考加速度且阻抗为常数 \(d = d_0 = d_\text{width}\),则静止时的穿透深度为

\[r = \au \cdot (1 - d) \cdot \text{timeconst}^2 \cdot \text{dampratio}^2 \]

接下来,我们描述直接格式,其中两个数字为 \((-\text{stiffness}, -\text{damping})\)。这尤其允许直接控制恢复系数。我们仍然应用一些缩放,以便在不同阻抗下使用相同的数字,但缩放不再取决于 \(r\),并且这两个数字也不再相互作用。缩放公式为

\[\begin{aligned} b &= \text{damping} / d_\text{width} \\ k &= \text{stiffness} \cdot d(r) / d_\text{width}^2 \\ \end{aligned} \]

与上述推导类似,如果使用负数格式给出参考加速度且阻抗为常数,则静止时的穿透深度为

\[r = \frac{\au (1 - d)}{\text{stiffness}} \]

提示

在正数值默认格式中,\(\text{timeconst}\) 参数控制约束的柔软度。它以时间为单位指定,表示“约束尝试解决违规的速度”。较大的值对应于更软的约束。

负数值的“直接”格式更灵活,例如允许完全弹性碰撞(\(\text{damping} = 0\))。它是系统辨识的推荐格式。

正数值格式中 \(\text{dampratio}\) 为 1 等效于直接格式中 \(\text{damping} = 2 \sqrt{ \text{stiffness} }\)

接触参数#

计算章的 接触 部分描述了每个接触的参数。此处我们解释如何设置这些参数。如果 geom 对通过 XML 元素 pair 显式定义,则它具有直接指定所有接触参数的属性。在这种情况下,单个 geom 的参数将被忽略。另一方面,如果接触是由动力学机制生成的,则其参数需要从接触对中的两个 geom 推断。如果两个 geom 具有相同的参数,则无需执行任何操作,但如果它们的参数不同呢?在这种情况下,我们使用 geom 属性 solmixpriority 来决定如何组合它们。每个接触参数的组合规则如下

condim

如果两个 geom 中的一个具有更高的优先级,则使用其 condim。如果两个 geom 具有相同的优先级,则使用两个 condim 中的最大值。这样,一个无摩擦 geom 和一个有摩擦 geom 会形成一个摩擦接触,除非无摩擦 geom 具有更高的优先级。后者在粒子系统中是可取的,例如,我们可能不希望粒子粘附到任何物体上。

friction

回想一下,接触最多可以有 5 个摩擦系数:两个切向、一个扭转、两个滚动。mjData.contact 中的每个接触实际上都具有所有这 5 个系数,即使 condim 小于 6 并且并非所有系数都使用。相比之下,geom 只有 3 个摩擦系数:切向(两个轴相同)、扭转、滚动(两个轴相同)。通过复制切向和滚动分量,将这些 3D 摩擦系数向量扩展为 5D 摩擦系数向量。有关切向、扭转和滚动系数语义的直观描述,请参见计算章的 接触 部分。

然后根据以下规则计算接触摩擦系数:如果两个 geom 中的一个具有更高的优先级,则使用其摩擦系数。否则,使用两个 geom 中每个摩擦系数的**元素级最大值**。

每个接触有 5 个系数而每个 geom 只有 3 个系数的原因如下。对于接触对,我们希望允许求解器能够处理的最灵活的模型。如前所述,可以利用各向异性摩擦来模拟滑冰等效应。然而,这需要知道接触切平面的两个轴是如何定向的。对于预定义的接触对,我们提前知道两个 geom 类型,并且相应的碰撞函数总是生成以相同方式定向的接触框架——这里我们不描述它,但在可视化器中可以看到。然而,对于单个 geom,我们不知道它们可能与哪些其他 geom 发生碰撞以及它们的 geom 类型可能是什么,因此在指定单个 geom 时无法知道接触切平面将如何定向。这就是 MuJoCo 不允许在单个 geom 规范中使用各向异性摩擦,而仅允许在显式接触对规范中使用的原因。

margin, gap

使用两个 geom margin(或 gap)的最大值。此处忽略 geom 优先级,因为 margin 和 gap 是距离属性,单方面指定意义不大。

solref, solimp

如果两个 geom 中的一个具有更高的 priority,则使用其 solref 和 solimp 参数。如果两个 geom 具有相同的优先级,则使用加权平均值。权重与 solmix 属性成比例,即 weight1 = solmix1 / (solmix1 + solmix2),weight2 类似。此加权平均规则有一个重要例外。如果任一 geom 的 solref 为非正值,即依赖于直接格式,则无论 solmix 如何,都使用元素级最小值。这是因为对不同格式的 solref 参数进行平均没有意义。

接触覆盖#

MuJoCo 使用计算章中描述的精心设计且新颖的 约束模型。要直观了解此模型如何工作,需要进行一些实验。为了方便此过程,我们提供了一种机制,可以在不更改实际模型的情况下覆盖某些求解器参数。禁用覆盖后,仿真将恢复模型中指定的参数。此机制还可用于在数值优化(例如最优控制或状态估计)中实现连续方法。这是通过在优化早期阶段允许接触从远处作用来实现的——以帮助优化器找到梯度并接近良好解决方案——然后在后期减小此效应,使最终解决方案更符合物理实际。

此处的相关设置是 flagoverride 属性,用于启用和禁用此机制,以及 optiono_margino_solrefo_solimp 属性,用于指定新的求解器参数。请注意,此覆盖仅适用于接触,不适用于其他类型的约束。原则上,MuJoCo 模型中有许多实数值参数可以从类似的覆盖机制中受益。但是,我们必须划定界限,而接触是自然的最佳选择,因为它们产生最丰富但也最难调优的行为。此外,接触动力学在数值优化方面通常带来挑战,经验表明,对接触参数进行连续化有助于避免局部最小值。

用户参数#

许多 MJCF 元素都具有可选属性 user,它定义了一个自定义的、特定于元素的参数数组。这与 size 元素的相应“nuser_XXX”属性相互作用。例如,如果我们设置 nuser_geom 为 5,那么 mjModel 中的每个 geom 都将有一个包含 5 个实数值参数的自定义数组。这些特定于 geom 的参数要么在 MJCF 文件中通过 geomuser 属性定义,要么如果省略此属性则由编译器设置为 0。所有“nuser_XXX”属性的默认值为 -1,这指示编译器自动将此值设置为模型中定义的关联 user 属性的最大长度。MuJoCo 在任何内部计算中都不使用这些参数;相反,它们可用于自定义计算。解析器允许 XML 中任意长度的数组,编译器稍后会将它们重设为长度 nuser_XXX。

一些通常在内部计算中使用的特定元素参数也可以用于自定义计算。这通过安装用户回调函数来实现,这些回调函数会覆盖仿真管道的部分功能。例如,general 执行器元素具有属性 dyntypedynprm。如果 dyntype 设置为“user”,则 MuJoCo 将调用 mjcb_act_dyn 来计算执行器动力学,而不是调用其内部函数。mjcb_act_dyn 指向的用户函数可以根据需要解释 dynprm 中定义的参数。但是,此参数数组的长度无法更改(与前面描述的自定义数组不同,后者的长度在 MJCF 文件中定义)。这同样适用于其他回调函数。

除了上面描述的特定元素用户参数外,还可以通过 custom 元素在模型中包含全局数据。对于在仿真过程中更改的数据,还有 mjData.userdata 数组,其大小由 size 元素的 nuserdata 属性确定。

求解器设置#

约束力和约束加速度的计算涉及数值求解优化问题。MuJoCo 有三种算法来求解此优化问题:CG、Newton、PGS。每种算法都可以应用于摩擦锥的棱锥或椭圆模型,并使用密集或稀疏的约束雅可比矩阵。此外,用户可以指定最大迭代次数以及控制提前终止的容差水平。还有第二个 Noslip 求解器,这是一个通过指定正数次 noslip 迭代启用的后处理步骤。所有这些算法设置都可以在 option 元素中指定。

默认设置适用于大多数模型,但在某些情况下需要调整算法。最佳方法是尝试相关设置并使用 simulate.cc 中的可视化分析器,它显示不同计算的时间以及每次迭代的求解器统计信息。我们可以提供以下一般性指导和观察

  • 对于小型模型,约束雅可比矩阵应为密集型;对于大型模型,应为稀疏型。默认设置为“auto”;当自由度数小于等于 60 时解析为密集型,大于 60 时解析为稀疏型。但请注意,该阈值最好根据活动约束的数量来定义,活动约束的数量取决于模型和行为。

  • 棱锥和椭圆摩擦锥之间的选择是建模选择而不是算法选择,即它导致使用相同算法解决不同的优化问题。椭圆锥更接近物理实际。然而,棱锥可以提高算法的性能——但不一定如此。虽然默认是棱锥,我们建议尝试椭圆锥。当接触滑动是一个问题时,抑制它的最佳方法是使用椭圆锥、大的 impratio,以及容差非常小的 Newton 算法。如果这还不够,请启用 Noslip 求解器。

  • 对于大多数模型,Newton 算法是最佳选择。它在全局最小值附近具有二次收敛性,并且迭代次数惊人地少——通常在 5 次左右,很少超过 20 次。它应该与激进的容差值一起使用,例如 1e-10,因为它能够在不增加延迟的情况下实现高精度(由于最后阶段的二次收敛)。我们看到它变慢的唯一情况是具有椭圆锥和许多滑动接触的大型模型。在该情景下,Hessian 分解需要大量更新。在某些大型模型中,由于模型元素的排序不当导致填充率很高(计算最优消元顺序是 NP-hard 问题,因此我们依赖于启发式方法),它也可能会变慢。请注意,因子化 Hessian 中的非零元素数量可以在分析器中监控。

  • CG 算法在上述 Newton 变慢的情况下表现良好。通常,CG 具有良好速率的线性收敛性,但在迭代次数方面无法与 Newton 竞争,尤其是在需要高精度时。然而,它的迭代速度快得多,并且不受填充或椭圆锥引起的复杂性增加的影响。如果 Newton 证明太慢,接下来尝试 CG。

  • 当自由度数大于约束数时,PGS 求解器是最佳选择。根据我们的经验,PGS 求解约束优化问题,具有亚线性收敛性,但在前几次迭代中通常会取得快速进展。因此,当可以容忍不精确的解决方案时,这是一个不错的选择。对于质量比大或导致条件差的其他模型属性的系统,PGS 收敛往往很慢。请记住,PGS 执行顺序更新,因此在物理学应具有对称性的系统中会打破对称性。相比之下,CG 和 Newton 执行并行更新并保持对称性。

  • Noslip 求解器是经过修改的 PGS 求解器。它在主求解器(可以是 Newton、CG 或 PGS)之后作为后处理步骤执行。主求解器更新所有未知量。相比之下,Noslip 求解器仅更新摩擦维度中的约束力,并忽略约束正则化。这具有抑制软约束模型引起的漂移或滑动的作用。然而,这种优化步骤的级联不再求解明确定义的优化问题(或任何其他问题);相反,它只是一种临时机制。虽然它通常能够完成任务,但我们在涉及多个接触之间更复杂交互的模型中发现了一些不稳定性。

  • PGS 在计算约束空间中的逆惯性方面有设置成本(以 CPU 时间计)。类似地,Newton 在初始 Hessian 分解方面有设置成本,并根据后续需要多少次分解更新而产生额外的分解成本。CG 没有设置成本。由于 Noslip 求解器也是 PGS 求解器,因此无论主求解器是 CG 还是 Newton,只要启用 Noslip,都会支付 PGS 设置成本。主 PGS 和 Noslip PGS 的设置操作相同,因此在两者都启用时只支付一次设置成本。

执行器#

本节介绍在 MuJoCo 中使用执行器的各个方面。有关计算模型,请参阅 驱动模型

分组禁用#

actuatorgroupdisable 属性(可通过设置 mjOption.disableactuator 整型位字段在运行时更改)允许用户根据执行器的 group 禁用执行器组。当需要为同一运动学树使用多种类型的执行器时,此功能很方便。例如,考虑一个固件支持多种控制模式(如扭矩控制和位置控制)的机器人。在这种情况下,可以在同一个 MJCF 模型中定义这两种类型的执行器,将一种类型的执行器分配到组 0,另一种分配到组 1。

actuatorgroupdisable MJCF 属性选择默认禁用哪些组,并且可以在运行时设置 mjOption.disableactuator 来切换活动组。请注意,执行器的总数 mjModel.nu 和执行器索引保持不变,因此用户需要知道被禁用的执行器相应的 mjData.ctrl 值将被忽略且不产生力。此示例模型 具有三个执行器组,可以在 simulate 交互式查看器中在运行时切换。请参阅右侧的 示例模型 及相关屏幕截图。

快捷方式#

如计算章的 驱动模型 部分所述,MuJoCo 提供了一个灵活的执行器模型,其中传动、激活动力学和力生成组件可以独立指定。通过 XML 元素 general 可以访问全部功能,它允许用户创建各种自定义执行器。此外,MJCF 为配置常用执行器提供了快捷方式。这是通过 XML 元素 motorpositionvelocityintvelocitydampercylindermuscleadhesion 完成的。这些**不是**单独的模型元素。MuJoCo 内部只支持一种执行器类型——这就是为什么保存 MJCF 模型时,所有执行器都写成 general。快捷方式隐式创建 general 执行器,将其属性设置为适当的值,并暴露部分属性,这些属性可能具有不同的名称。例如,position 创建一个位置伺服,其属性 kp 是伺服增益。然而,general 没有属性 kp。相反,解析器会协调调整 general 执行器的增益和偏置参数,以模拟位置伺服。通过直接使用 general 并将其属性设置为下面描述的某些值,也可以达到相同的效果。

执行器快捷方式也与默认设置相互作用。回想一下,默认设置 机制涉及类,每个类都包含一套完整的虚拟元素(每种元素类型一个),用于初始化实际模型元素的属性。特别是,每个默认类只有一个 general 执行器元素。如果在同一个默认类中先指定 position 后指定 velocity 会发生什么?XML 元素按顺序处理,每当遇到执行器相关元素时,都会设置单个 general 执行器的属性。因此,velocity 具有优先权。但是,如果我们在默认类中指定 general,它只会设置显式给定的属性,而保留其余属性不变。创建实际模型元素时也会出现类似的复杂情况。假设活动默认类指定了 position,现在我们使用 general 创建一个执行器并省略其部分属性。缺失的属性将被设置为用于模拟位置伺服的任何值,即使该执行器可能并非旨在作为位置伺服。

考虑到这些潜在的复杂性,我们建议采用一种简单的方法:在默认类和创建实际模型元素时使用相同的执行器快捷方式。如果给定模型需要不同的执行器,要么创建多个默认类,要么避免对执行器使用默认设置,而是显式指定其所有属性。

力限#

执行器力通常在下限和上限之间受到限制。这些限制可以通过三种方式强制执行

使用 ctrlrange 进行控制钳位

如果设置此执行器属性,输入控制值将被钳位。对于简单的 motor,钳位控制输入等效于钳位力输出。

使用 forcerange 在执行器输出处钳位力

如果设置此执行器属性,执行器的输出力将被钳位。此属性对于例如 位置执行器 很有用,可将力保持在界限内。请注意,位置执行器通常也需要进行控制范围钳位,以避免触及关节限位。

使用 joint/actuatorfrcrange 在关节输入处钳位力

此关节属性在通过 传动装置 后,对作用于该关节的所有执行器的输入力进行钳位。如果传动装置是微不足道的(执行器与关节之间存在一对一关系),则在关节处钳位执行器力等效于在执行器处钳位。然而,在多个执行器作用于一个关节或一个执行器作用于多个关节—但实际扭矩是由关节处的单个物理执行器施加—的情况下,最好在关节本身处钳位力。以下是三个最好在关节而不是执行器处钳位执行器力的示例

  • 此示例模型 中,两个执行器,一个 motor 和一个 damper,作用于单个关节。

  • 此示例模型(类似于“杜宾汽车”)中,两个执行器通过 固定肌腱 传动装置作用于两个轮子,以施加对称(向前/向后滚动)和反对称(向右/向左转动)扭矩。

  • 此示例模型 中,site 传动装置 实现了机械臂末端执行器的笛卡尔控制器。为了使计算出的扭矩能够由单独的、扭矩受限的关节电机实现,需要在关节处对它们进行钳位。

请注意,在这种传动装置组合力/扭矩的情况下,应使用 jointactuatorfrc 传感器报告作用于关节的总执行器力。标准 actuatorfrc 传感器将继续报告钳位前的执行器力。

使用 tendon/actuatorfrcrange 在肌腱输入处钳位力

此肌腱属性对作用于该肌腱的所有执行器的输入力进行钳位。

上述钳位选项并非互斥,可以根据需要组合使用。

长度范围#

字段 mjModel.actuator_lengthrange 包含可行执行器长度的范围(或更准确地说,是执行器传动装置的长度)。这是模拟 肌肉执行器 所必需的。此处我们重点介绍 actuator_lengthrange 的含义以及如何设置它。

与 mjModel 的所有其他字段都是精确的物理或几何量不同,actuator_lengthrange 是一个近似值。直观上,它对应于执行器传动装置在模型所有“可行”配置下可以达到的最小和最大长度。然而,MuJoCo 约束是软的,因此原则上任何配置都是可行的。但我们需要一个明确定义的范围来进行肌肉建模。设置此范围有三种方法:(1) 使用所有执行器中可用的新属性 lengthrange 显式提供;(2) 从执行器附加的关节或肌腱的限位复制;(3) 自动计算,如下面其余部分所述。此处有许多选项,通过新的 XML 元素 lengthrange 控制。

执行器长度范围的自动计算在编译时完成,结果存储在编译模型的 mjModel.actuator_lengthrange 中。如果随后保存模型(无论是 XML 还是 MJB),则在下次加载时无需重复计算。这一点很重要,因为对于大型肌肉骨骼模型,计算可能会减慢模型编译器。实际上,我们已经使编译器多线程化,以加快此操作(不同的执行器在不同的线程中并行处理)。

自动计算依赖于修改后的物理仿真。对于每个执行器,我们通过执行器的传动装置施加力(计算最小值时为负,计算最大值时为正),在阻尼状态下推进仿真以避免不稳定,给予足够的时间使其稳定并记录结果。这与带有动量的梯度下降有关,实际上我们已经尝试了基于梯度的显式优化,但问题是,考虑到软约束的混合,不清楚我们应该优化什么目标。通过使用仿真,我们本质上是让物理学告诉我们应该优化什么。但请记住,这仍然是一个优化过程,因此它具有可能需要调整的参数。我们提供了保守的默认值,这些默认值应该适用于大多数模型,但如果不起作用,请使用 lengthrange 的属性进行微调。

使用此功能时,重要的是要牢记模型的几何结构。此处隐含的假设是可行执行器长度确实受到限制。此外,我们不将接触视为限制因素(实际上在此仿真中,我们在内部禁用了接触,以及被动力、重力、摩擦损失和执行器力)。这是因为带有接触的模型可能会纠缠在一起并产生许多局部最小值。因此,执行器应受到限制,要么是因为模型中定义的关节或肌腱限位(在仿真期间启用),要么是因为几何结构。为了说明后者,考虑一个肌腱,一端连接到世界,另一端连接到一个围绕连接到世界的铰链关节旋转的物体。在这种情况下,肌腱的最小和最大长度是明确定义的,并且取决于附着点在空间中描绘的圆的大小,即使关节和肌腱都没有用户定义的限位。但是,如果执行器连接到关节,或者连接到等于关节的固定肌腱,则它是无限制的。编译器在这种情况下会返回错误,但它无法判断错误是由于缺乏收敛性还是因为执行器长度是无限制的。所有这些听起来都过于复杂,但从我们在考虑所有可能的边缘情况来看确实如此。实际上,长度范围几乎总是与附着到空间肌腱的肌肉执行器一起使用,并且模型中会定义关节限位,从而有效地限制肌肉执行器的长度。如果在这样的模型中遇到收敛错误,最可能的解释是您忘记了包含关节限位。

有状态执行器#

如计算章的 驱动模型 部分所述,MuJoCo 支持具有内部动力学的执行器,其状态称为“激活量”。

激活量限位#

有状态执行器的一个有用应用是“积分速度”执行器,它通过 intvelocity 快捷方式实现。与实现对传动目标速度直接反馈的 纯速度 执行器不同,*积分速度*执行器将*积分器*与*位置反馈*执行器耦合。在这种情况下,激活状态的语义是“位置执行器的设定点”,控制信号的语义是“位置执行器设定点的速度”。请注意,在真实的机器人系统中,这种积分速度执行器是具有速度语义的执行器最常见的实现方式,而不是纯粹的速度反馈,后者在现实生活和仿真中通常都非常不稳定。

在使用积分速度执行器的情况下,通常希望对激活状态进行*钳位*,因为否则位置目标将继续积分超出关节限位,导致失去控制性。要查看激活量钳位的效果,请加载下面的示例模型

带有激活量限位的示例模型
<mujoco>
<default>
   <joint axis="0 0 1" limited="true" range="-90 90" damping="0.3"/>
   <geom size=".1 .1 .1" type="box"/>
</default>

<worldbody>
   <body>
      <joint name="joint1"/>
      <geom/>
   </body>
   <body pos=".3 0 0">
      <joint name="joint2"/>
      <geom/>
   </body>
</worldbody>

<actuator>
   <general name="unclamped" joint="joint1" gainprm="1" biastype="affine"
      biasprm="0 -1" dyntype="integrator"/>
   <intvelocity name="clamped" joint="joint2" actrange="-1.57 1.57"/>
</actuator>
</mujoco>

请注意,actrange 属性始终以原生单位(弧度)指定,即使关节范围可以是度(默认)或弧度,具体取决于 compiler/angle 属性。

肌肉#

我们提供了一套用于模拟生物肌肉的工具。希望以最小努力添加肌肉的用户可以在执行器部分使用一行 XML 完成此操作

<actuator>
    <muscle name="mymuscle" tendon="mytendon">
</actuator>

生物肌肉彼此之间看起来非常不同,但一旦应用某种缩放,它们的行为方式就非常相似。我们的默认设置应用了这种缩放,这就是为什么无需调整任何参数就可以获得合理的肌肉模型。构建更详细的模型当然需要参数调整,如本节所述。

请记住,尽管肌肉模型相当复杂,但它仍然是 MuJoCo 执行器的一种类型,并且遵循与其他所有执行器相同的约定。可以使用 general 定义肌肉,但快捷方式 muscle 更方便。与所有其他执行器一样,力生成机制和传动装置是独立定义的。尽管如此,只有当肌肉连接到肌腱或关节传动装置时,它们才具有(生物)物理意义。为了具体起见,我们此处将假设使用肌腱传动装置。

首先,我们讨论长度和长度缩放。传动装置(即 MuJoCo 肌腱)的可行长度范围将扮演重要角色;参见上面的 长度范围 部分。在生物力学中,肌肉和肌腱串联连接形成肌肉-肌腱执行器。我们的约定有所不同:在 MuJoCo 中,具有空间特性(特别是长度和速度)的实体是肌腱,而肌肉是拉动肌腱的抽象力生成机制。因此,MuJoCo 中的肌腱长度对应于生物力学中的肌肉+肌腱长度。我们假设生物肌腱是无弹性的,具有恒定长度 \(L_T\),而生物肌肉长度 \(L_M\) 随时间变化。MuJoCo 肌腱长度是生物肌肉长度和肌腱长度之和

\[\texttt{actuator\_length} = L_T + L_M \]

另一个重要常数是肌肉的最佳静息长度,记为 \(L_0\)。它等于肌肉在零速度下产生最大主动力时的长度 \(L_M\)。我们不要求用户直接指定 \(L_0\)\(L_T\),因为考虑到肌腱布线和缠绕的空间复杂性,很难知道它们的数值。相反,我们自动计算 \(L_0\)\(L_T\) 如下。上面描述的长度范围计算已经提供了 \(L_T+L_M\) 的操作范围。此外,我们要求用户指定肌肉长度 \(L_M\) 缩放后(仍未知)常数 \(L_0\) 的操作范围。这通过属性 range 完成;默认缩放范围是 \((0.75, 1.05)\)。现在我们可以计算这两个常数,利用实际范围和缩放范围必须相互映射的事实

\[\begin{aligned} (\texttt{actuator\_lengthrange[0]} - L_T) / L_0 &= \texttt{range[0]} \\ (\texttt{actuator\_lengthrange[1]} - L_T) / L_0 &= \texttt{range[1]} \\ \end{aligned} \]

在运行时,我们计算缩放后的肌肉长度和速度,如下所示

\[\begin{aligned} L &= (\texttt{actuator\_length} - L_T) / L_0 \\ V &= \texttt{actuator\_velocity} / L_0 \\ \end{aligned} \]

缩放量的优势在于所有肌肉在该表示中表现相似。其行为由许多实验论文中测得的力-长度-速度(\(\text{\small FLV}\))函数捕获。我们按如下方式近似此函数

_images/musclemodel.png _images/musclemodel_dark.png

该函数形式为

\[\text{\small FLV}(L, V, \texttt{act}) = F_L(L)\cdot F_V(V)\cdot \texttt{act} + F_P(L) \]

与 MuJoCo 执行器的通用形式相比,我们看到 \(F_L\cdot F_V\) 是执行器增益,\(F_P\) 是执行器偏置。\(F_L\) 是作为长度函数的活动力,而 \(F_V\) 是作为速度函数的活动力。它们相乘得到总的活动力(注意按执行器激活量 act 进行缩放)。\(F_P\) 是被动力,无论激活量如何始终存在。\(\text{\small FLV}\) 函数的输出是缩放后的肌肉力。我们将缩放后的力乘以肌肉特有的常数 \(F_0\) 来获得实际力

\[\texttt{actuator\_force} = -\text{\small FLV}(L, V, \texttt{act}) \cdot F_0 \]

负号是因为正向肌肉激活产生拉力。常数 \(F_0\) 是零速度下的峰值主动力。它与肌肉厚度(即生理横截面积或 PCSA)有关。如果已知,可以使用 muscle 元素的 force 属性进行设置。如果未知,我们将其设置为默认值 \(-1\)。在这种情况下,我们依赖于较大的肌肉往往作用于移动更多重量的关节这一事实。属性 scale 将此关系定义为

\[F_0 = \text{scale} / \texttt{actuator\_acc0} \]

\(\texttt{actuator\_acc0}\) 由模型编译器预计算。它是单位力作用于执行器传动装置引起的关节加速度的范数。直观地说,\(\text{scale}\) 决定了肌肉“平均”有多强,而其实际强度取决于整个模型的几何和惯性属性。

到目前为止,我们遇到了三个定义单个肌肉属性的常量:\(L_T, L_0, F_0\)。此外,函数\(\text{\small FLV}\)本身有几个参数,如上图所示:\(l_\text{min}, l_\text{max}, v_\text{max}, f_\text{pmax}, f_\text{vmax}\)。这些参数被认为是所有肌肉都相同的,但不同的实验论文提出了不同形状的FLV函数,因此熟悉相关文献的用户可能希望调整它们。我们提供了MATLAB函数FLV.m,用于生成上图并展示了我们如何计算\(\text{\small FLV}\)函数。

在着手设计更精确的\(\text{\small FLV}\)函数之前,请考虑这样一个事实:肌肉的工作范围比\(\text{\small FLV}\)函数的形状影响更大,而且在许多情况下,这个参数是未知的。下面是一个图形说明

_images/musclerange.png _images/musclerange_dark.png

这种图形格式在生物力学文献中很常见,显示了每块肌肉的工作范围叠加在归一化\(\text{FL}\)曲线上(忽略垂直位移)。我们的默认范围以黑色显示。蓝色曲线是两块手臂肌肉的实验数据。可以找到范围小的肌肉、范围大的肌肉、范围跨越\(\text{FL}\)曲线上升段、下降段或两者兼有的肌肉。现在假设您有一个包含50块肌肉的模型。您相信有人做了仔细的实验,测量了模型中每块肌肉的工作范围,并考虑了肌肉跨越的所有关节吗?如果不信,那么最好将肌肉骨骼模型视为与生物系统具有相同的总体行为,但在各种细节上有所不同——包括一些研究社区非常感兴趣的细节。对于大多数建模者认为是常数且已知的肌肉属性,都有实验论文表明它们在某些条件下会发生变化。这并非要阻止人们构建精确的模型,而是要阻止人们过分相信他们的模型。

回到我们的肌肉模型,有一个肌肉激活状态act。这是控制信号输入的非线性一阶滤波器的状态。滤波器的动力学方程为

\[\frac{\partial}{\partial t}\texttt{act} = \frac{\texttt{ctrl} - \texttt{act}}{\tau(\texttt{ctrl}, \texttt{act})} \]

即使执行器没有指定控制范围,内部控制信号也会被限制在[0, 1]。有两个通过属性timeconst指定的时间常数,即\(\text{timeconst} = (\tau_\text{act}, \tau_\text{deact})\),默认值为\((0.01, 0.04)\)。根据Millard et al. (2013),有效时间常数\(\tau\)在运行时计算如下

\[\tau(\texttt{ctrl}, \texttt{act}) = \begin{cases} \tau_\text{act} \cdot (0.5 + 1.5\cdot\texttt{act}) & \texttt{ctrl}-\texttt{act} \gt 0 \\ \tau_\text{deact} / (0.5 + 1.5\cdot\texttt{act}) & \texttt{ctrl} - \texttt{act} \leq 0 \end{cases} \]

由于上述方程描述了不连续的切换,这在使用基于梯度的优化时可能不受欢迎,我们引入了可选的平滑参数tausmooth。当该值大于0时,切换将由mju_sigmoid代替,它会在范围\((\texttt{ctrl}-\texttt{act}) \pm \text{tausmooth}/2\)内平滑地在两个值之间插值。

现在我们总结一下用户可能希望根据其对生物力学文献的熟悉程度以及特定模型的详细测量数据的可用性来调整的muscle元素属性

默认值

在所有地方使用内置的默认值。您只需将肌肉连接到肌腱,如本节开头所示。这将产生一个通用而合理的模型。

scale

如果您不知道单个肌肉的力量,但想让所有肌肉变得更强或更弱,请调整scale。这可以为每块肌肉单独调整,但在default元素中设置一次更有意义。

force

如果您知道单个肌肉的峰值主动力\(F_0\),请在此输入。许多实验论文包含此数据。

range

一些论文中也提供了肌肉的缩放长度工作范围。尚不清楚此类测量的可靠性如何(考虑到肌肉作用于许多关节),但它们确实存在。请注意,不同肌肉之间的范围差异很大。

timeconst

肌肉由慢肌纤维和快肌纤维组成。典型的肌肉是混合的,但有些肌肉某种纤维类型的比例更高,使其更快或更慢。这可以通过调整时间常数来建模。\(\text{\small FLV}\)函数的vmax参数也应相应调整。

tausmooth

当该值为正时,平滑激活和去激活时间常数之间的过渡。虽然单个运动单位要么正在激活,要么正在去激活,但整块肌肉会混合许多运动单位,从而导致相应的时间尺度混合。

lmin, lmax, vmax, fpmax, fvmax

这些参数控制着\(\text{\small FLV}\)函数的形状。高级用户可以尝试调整它们;请参见MATLAB函数FLV.m。与scale设置类似,如果您想更改所有肌肉的\(\text{\small FLV}\)参数,请在default元素中进行。

自定义模型

用户无需调整我们的肌肉模型参数,而是可以通过将general执行器的gaintypebiastypedyntype设置为“user”并在运行时提供回调函数来实现不同的模型。或者,可以将其中一些类型设置为“muscle”,并使用我们的模型,同时替换其他组件。请注意,肌腱几何计算仍然由标准的MuJoCo流程处理,提供actuator_lengthactuator_velocityactuator_lengthrange作为用户肌肉模型的输入。自定义回调函数可以模拟弹性肌腱或我们选择省略的任何其他细节。

与OpenSim的关系

生物力学研究人员使用的标准软件是OpenSim。我们设计的肌肉模型在可能的情况下与OpenSim模型相似,同时进行了简化,从而显着提高了模拟速度和稳定性。为了帮助MuJoCo用户转换OpenSim模型,我们在此总结相似之处和不同之处。

激活动力学模型与OpenSim完全相同,包括默认时间常数。

\(\text{\small FLV}\)函数并非完全相同,但MuJoCo和OpenSim都近似于相同的实验数据,因此非常接近。有关OpenSim模型和相关实验数据的摘要,请参见Millard et al. (2013)

我们假设肌腱是无弹性的,而OpenSim可以模拟肌腱弹性。我们在这里决定不这样做,因为肌腱弹性需要快速平衡假设,这反过来需要各种调整并容易导致模拟不稳定。实际上,肌腱相当僵硬,其效果可以通过拉伸对应于无弹性情况的\(\text{FL}\)曲线来近似捕捉(Zajac (1989))。这可以在MuJoCo中通过缩短肌肉工作范围来实现。

MuJoCo中没有建模羽状角(即肌肉与受力方向之间的夹角),并假定为0。可以通过缩放肌肉力和调整工作范围来近似此效应。

MuJoCo中的肌腱缠绕功能也更有限。我们允许球体和无限圆柱体作为缠绕对象,并要求两个缠绕对象之间通过肌腱路径中的固定站点隔开。这是为了避免迭代计算肌腱路径的需要。我们还允许将“侧站点”放置在球体或圆柱体内,这会导致反向缠绕:肌腱路径被约束为穿过对象而不是绕过它。这可以替代OpenSim中使用的圆环缠绕对象,以将肌腱路径保持在给定区域内。总的来说,肌腱缠绕是将OpenSim模型转换为MuJoCo模型最具挑战性的部分,需要一些手动工作。从好的方面看,高质量的OpenSim模型数量不多,因此一旦它们被转换完成即可。

下面我们演示了四种可用的肌腱缠绕类型。请注意,缠绕肌腱的弯曲部分渲染为直线,但几何管道使用实际曲线并分析计算其长度和力矩

image3

传感器#

MuJoCo可以模拟各种传感器,如下面的sensor元素所述。也可以定义用户传感器类型,并通过回调函数mjcb_sensor进行评估。传感器不影响模拟。相反,它们的输出被复制到数组mjData.sensordata中,可供用户处理。

这里我们描述所有传感器类型共有的XML属性,以避免后续重复。

name: 字符串,可选

传感器的名称。

noise: 实数,“0”

此传感器噪声模型的标准差。在3.1.4版本之前,这会导致噪声被添加到传感器中。在3.1.4版本中此功能被移除,详细理由请参见3.1.4版本更新日志。从后续版本开始,此属性作为保存标准差信息的便捷位置供以后使用。

cutoff: 实数,“0”

当该值为正时,它会限制传感器输出的绝对值。它还用于在simulate.cc中的传感器数据图表中归一化传感器输出。

user: 实数(nuser_sensor), “0 0 …”

请参见用户参数

摄像机#

除了默认的可由用户控制的自由摄像机外,“固定”摄像机可以附加到运动学树上。

外部参数

默认情况下,摄像机坐标系附加到包含它的主体上。可选的modetarget属性可用于指定跟踪(随动)或目标(看向)一个主体或子树的摄像机。摄像机看向摄像机坐标系的负Z轴方向,而正X轴和正Y轴分别对应于图像平面中的“右”和“上”。

内部参数

摄像机内部参数使用ipd(瞳距,立体渲染和VR所需)和fovy(垂直视野,以度为单位)指定。

上述规范意味着一个完美的点摄像机,没有像差。然而,在校准真实摄像机时,两种线性像差可以使用标准渲染管线表示。第一种是垂直和水平方向焦距不同(轴向散光)。第二种是非中心的相机主点。这些可以使用focalprincipal属性指定。当使用这些与校准相关的属性时,还必须指定物理传感器尺寸和摄像机分辨率。在这种情况下,渲染视锥体可以被可视化。

复合对象#

复合对象不是新的模型元素。相反,它们是现有元素的集合,最初设计用于模拟粒子系统、绳索、布料和软体。随着时间的推移,大多数这些类型已被replicate(用于重复对象)和flexcomp(用于软体对象)取代。因此,现在唯一支持的复合类型是cable,它生成由球形关节连接的不可伸长的主体链。

复合对象由常规的MuJoCo主体组成,在这种上下文中我们称之为“元素主体”。元素主体的集合由模型编译器自动生成。用户使用新的XML元素composite及其属性和子元素在高级别配置自动生成器,如XML参考章节所述。如果编译后的模型随后被保存,composite元素将不再存在,而被自动生成的常规模型元素集合所取代。所以可以将其视为由模型编译器展开的宏。元素主体被创建为包含composite元素的主体的子元素;因此,复合对象出现在XML中可以定义常规子主体的相同位置。每个自动生成的元素主体都附加了一个单独的geom。我们设计的复合对象生成器尽可能具有直观的高级控制,但同时它也暴露了大量相互作用并可能深刻影响结果物理的选项。因此,用户应该仔细阅读参考文档

除了设置物理属性外,复合对象生成器还会创建合适的渲染。对象可以渲染为皮肤。皮肤是自动生成的,可以进行纹理贴图以及使用双三次插值进行细分。实际的物理属性,特别是碰撞检测,基于元素主体及其geom,而皮肤纯粹是可视化对象。然而,在某些情况下,我们更喜欢查看皮肤表示,例如这个模型,其皮肤是连续的柔性表面,而不是不连续的薄盒子集合。然而,在微调模型并试图理解其背后的物理原理时,能够渲染geom是有用的。要切换渲染样式,请禁用皮肤渲染并启用geomtendon的第3组。

Cable.

作为快速入门,MuJoCo提供了复合电缆的示例。在所有示例中,我们都有一个包含在模型中的静态场景,然后是一个单独的复合对象。下面的XML片段只是复合对象的定义;完整的示例请参见发行版中的XML模型文件。

coil

<extension>
   <plugin plugin="mujoco.elasticity.cable"/>
</extension>

<worldbody>
   <composite prefix="actuated" type="cable" curve="cos(s) sin(s) s" count="41 1 1"
              size="0.25 .1 4" offset="0.25 0 .05" initial="none">
      <plugin plugin="mujoco.elasticity.cable">
         <!--Units are in Pa (SI)-->
         <config key="twist" value="5e8"/>
         <config key="bend" value="15e8"/>
         <config key="vmax" value="0"/>
      </plugin>
      <joint kind="main" damping="0.15" armature="0.01"/>
      <geom type="capsule" size=".005" rgba=".8 .2 .1 1"/>
   </composite>
</worldbody>

电缆模拟一个不可伸长的弹性一维对象,具有扭转和弯曲刚度。它使用一系列胶囊或盒子进行离散化。其刚度和惯性特性直接从给定参数和横截面形状计算得出,从而允许各向异性行为,这可以在皮带或计算机电缆中找到。它是一个单一的运动学树,因此在不使用额外约束的情况下是完全不可伸长的,从而可以使用大的时间步长。弹性模型在几何上是精确的,基于计算中心线的Bishop或无扭转坐标系,即穿过横截面中心线的线。几何体的方向是相对于该坐标系表示的,然后分解为扭转和弯曲分量,因此可以独立设置不同的刚度。此外,可以指定无应力配置是平的还是弯曲的,例如在螺旋弹簧的情况下。电缆需要使用第三方引擎插件,该插件将来可能会直接集成到引擎中。

Particle.

粒子类型已被弃用。建议改用更通用的replicate,例如这个模型

Grid.

网格复合类型已移除。建议使用二维柔性可变形对象来模拟薄弹性结构。

Rope and loop.

绳索和环类型已被弃用。建议使用电缆来模拟弯曲和扭转的不可伸长弹性杆,并使用一维柔性可变形对象来模拟受拉伸载荷(例如拉伸的橡皮筋)下的可伸长绳索。

Cloth.

布料类型已被弃用。建议使用二维柔性可变形对象来模拟薄弹性结构。

Box, cylinder and ellipsoid.

盒子类型以及圆柱体和椭球体类型现已弃用,推荐使用三维柔性可变形对象元素。

可变形对象#

前面描述的复合对象旨在在本质上是刚体模拟器中模拟软体。这之所以可能,是因为MuJoCo的约束是软的,但其功能和建模能力仍然有限。在MuJoCo 3.0中,我们引入了真正的可变形对象,包括新的模型元素。前面描述的皮肤实际上就是这样一个元素,但它仅用于可视化。我们现在有一个相关的元素flex,它根据需要生成接触力、约束力和被动力,以模拟各种可变形实体。现在,皮肤和柔体都定义在XML中的一个新分组元素deformable内。柔体是一个低级元素,指定了运行时所需的一切,但在建模时很难设计。为了辅助建模,我们进一步引入了元素flexcomp,它自动化了低级柔体的创建,类似于composite自动化了创建(集合)用于模拟软体的MuJoCo对象。柔体最终可能会取代复合对象,但目前两者对于略有不同的目的都是有用的。

柔体是MuJoCo主体的集合,这些主体通过无质量可伸长元素连接。这些元素可以是胶囊(一维柔体)、三角形(二维柔体)或四面体(三维柔体)。在所有情况下,我们都允许设置半径,这使得元素在二维和一维中变得光滑且体积化。基本元素如下所示

_images/flexelem.png

到目前为止,这些看起来像geom。但关键区别在于它们是可变形的:随着主体(顶点)相互独立移动,元素的形状会实时变化。碰撞和接触力现在已泛化以处理这些可变形的几何元素。请注意,当两个这样的元素碰撞时,接触不再只涉及两个主体,而可能涉及多达8个主体(如果两个元素都是四面体)。接触力像以前一样计算,给定接触坐标系和在该坐标系中表示的相关量。但是,接触力会分配给所有相互作用的主体。接触雅可比矩阵的概念很复杂,因为接触点不能被视为固定在任何主体坐标系中。相反,我们使用加权方案将每个接触点“分配”给多个主体。还可以通过将所有顶点分配给同一个主体来创建刚性柔体。这是一种重新利用新的柔体碰撞机制来实现刚性非凸网格碰撞的方法(与碰撞时凸化的网格geom不同)。

变形模型.

为了(在软意义上)保持柔体的形状,我们需要生成被动力或约束力。在MuJoCo 3.0之前,这将涉及大量的肌腱以及对肌腱和关节的约束。这在这里仍然可能,但当柔体很大时,在建模和模拟方面效率低下。相反,设计理念是使用一组参数并提供两种建模选择:一种新的(软)相等约束类型,适用于给定柔体的所有边,允许较大的时间步长;或一种离散化连续体表示,其中每个元素处于恒定应力状态,这等效于分段线性有限元,并提高了真实性和准确性。基于边模型可以看作是一种“集中”刚度模型,其中变形模式(例如剪切和体积变形)的正确耦合在一个单一量中进行平均。连续体模型则允许使用材料的泊松比独立指定剪切刚度和体积刚度。更多细节,请参见Saint Venant-Kirchhoff超弹性模型。

创建和可视化.

<option timestep=".001"/>

<worldbody>
   <flexcomp type="grid" count="24 4 4" spacing=".1 .1 .1" pos=".1 0 1.5"
             radius=".0" rgba="0 .7 .7 1" name="softbody" dim="3" mass="7">
      <contact condim="3" solref="0.01 1" solimp=".95 .99 .0001" selfcollide="none"/>
      <edge damping="1"/>
      <elasticity poisson="0.2" young="5e4">
   </flexcomp>
</worldbody>

使用flexcomp元素,我们可以从网格(包括四面体网格)创建柔体,并自动生成所有主体/顶点,并将它们与合适的元素连接。我们还可以自动创建网格和其他拓扑结构。这个机制使得创建非常大的柔体变得容易,涉及数千甚至数万个主体、元素和边。显然,这样的模拟不会很快。即使是中等大小的柔体,碰撞对的修剪也是必不可少的。这就是为什么我们开发了精心设计的方法来修剪自碰撞;请参见XML参考。

对于由四面体组成的三维柔体,检查柔体内部如何“三角化”可能很有用。我们有一个特殊的可视化模式,可以剥离外层。下面是斯坦福兔的例子。注意它是如何外面是较小的四面体,里面是较大的四面体。这种网格设计是有意义的,因为我们希望碰撞表面准确,但在内部我们只需要软材料特性——这需要较低的空间分辨率。为了将表面网格转换为四面体网格,我们推荐使用开源工具,例如fTetWild库

bunny1 bunny2

包含文件#

MJCF文件可以使用include元素包含其他XML文件。从机制上讲,解析器将主文件中对应于include元素的DOM节点替换为包含文件中顶层元素的子XML元素列表。顶层元素本身被丢弃,因为它出于XML目的是一个分组元素,如果包含进来会违反MJCF格式。

此功能支持模块化MJCF模型;请参见模型库中的MPL系列模型。模块化的一个例子是构建机器人模型(通常比较复杂),然后将其包含在多个“场景”中,即定义机器人环境中对象的MJCF模型。另一个例子是创建一个包含常用资产的文件(例如具有仔细调整的rgba值的材质),并将其包含在引用这些资产的多个模型中。

包含的文件本身不要求是有效的MJCF文件,但通常是。实际上,我们设计此机制是为了允许MJCF模型包含在其他MJCF模型中。为了实现这一点,即使在单个模型的上下文中语义上没有意义,也允许重复的MJCF节。例如,我们允许运动学树有多个根(即多个worldbody元素),它们会被解析器自动合并。否则,将机器人包含到场景中将是不可能的。

重复MJCF节的灵活性是有代价的:适用于整个模型的全局设置,例如compilerangle属性,可以被定义多次。MuJoCo允许这样做,并使用在包含所有include元素后,复合模型中遇到的最后一次定义。因此,如果模型A以度为单位定义,模型B以弧度为单位定义,并且A包含在B中位于B的compiler元素之后,那么整个复合模型将被视为以度为单位定义——在这种情况下会导致不良后果。用户必须确保相互包含的模型在此意义上兼容;局部坐标与全局坐标是另一个兼容性要求。

最后,如下所述,元素名称在所有同类型元素中必须是唯一的。因此,例如,如果在两个模型中使用了相同的geom名称,并且一个模型包含在另一个模型中,这将导致编译错误。多次包含同一个XML文件是解析错误。此限制的原因是我们要避免重复的元素名称以及包含导致的无限递归。

命名元素#

MJCF中的大多数模型元素都可以有名称。它们通过相应XML元素的name属性定义。当给定模型元素被命名时,其名称在所有同类型元素中必须是唯一的。名称区分大小写。它们在编译时用于引用相应元素,并在运行时保存在mjModel中,方便用户使用。

名称通常是一个可选属性。我们建议将其留空(以使模型文件更短),除非有特定原因需要定义它。可能有几个这样的原因

  • 有些模型元素在创建时需要引用其他元素。例如,空间肌腱需要引用站点来指定其经过的中间点。引用只能通过名称进行。请注意,资产存在的唯一目的是被引用,因此它们必须有名称,但可以省略并隐式地从相应的文件名设置。

  • 可视化器提供了标记给定类型的所有模型元素的选项。当名称可用时,它会显示在3D视图中对象旁边;否则会显示一个通用标签,格式为“body 7”。

  • 函数mj_name2id返回给定类型和名称的模型元素的索引。反之,函数mj_id2name根据索引返回名称。这对于涉及通过其名称(而不是依赖固定索引,后者在模型编辑时可能改变)在XML中标识的模型元素的自定义计算非常有用。

  • 原则上,通过命名某些元素可以使模型文件更具可读性。但是请记住,XML本身具有注释机制,并且该机制更适合提高可读性——特别是考虑到大多数文本编辑器提供检测XML注释的语法高亮功能。

URDF扩展#

统一机器人描述格式(URDF)是一种流行的XML文件格式,许多现有机器人已用它建模。因此,即使它只能表示MuJoCo中可用模型元素的一个子集,我们也实现了对URDF的支持。除了标准的URDF文件外,MuJoCo还可以加载具有自定义(从URDF角度看)mujoco元素作为顶层元素robot的子元素的XML文件。这个自定义元素可以有子元素compileroptionsize,功能与MJCF中的相同,只是修改了默认的编译器设置以适应URDF建模约定。compiler扩展已被证明非常有用,实际上,它的几个属性被引入是因为许多现有URDF模型具有非物理动力学参数,如果未经修改,MuJoCo的内置编译器会拒绝它们。此扩展还需要指定网格目录。另请注意,编译器属性strippathanglefusestaticdiscardvisual对于URDF和MJCF具有不同的默认值。

请注意,MJCF模型由解析器根据自定义XML schema进行检查,而URDF模型则不进行检查。即使嵌入在URDF文件中的MuJoCo特定元素也不进行检查。因此,属性名称拼写错误会被静默忽略,如果拼写错误未被注意到,可能会导致严重的混乱。

以下是URDF模型的示例扩展部分

<robot name="darwin">
  <mujoco>
    <compiler meshdir="../mesh/darwin/" balanceinertia="true" discardvisual="false"/>
  </mujoco>
  <link name="MP_BODY">
    ...
</robot>

上述扩展使得URDF更易用但仍然有限。如果用户想构建充分利用MuJoCo优势的模型,同时保持URDF兼容性,我们建议采用以下步骤。根据需要引入URDF扩展,加载它并将其保存为MJCF。然后,尽可能使用include元素将信息添加到MJCF中。这样,如果URDF被修改,相应的MJCF可以轻松重新创建。然而,根据我们的经验,URDF文件往往是静态的,而MJCF文件则经常被编辑。因此,实际上通常只需将URDF转换为MJCF一次,之后只使用MJCF即可。

运动捕捉主体#

mocap主体是世界的静态子元素(即没有关节),并且它们的mocap属性设置为“true”。它们可用于将运动捕捉设备的数据流输入到MuJoCo模拟中。假设您拿着VR控制器,或者一个装有运动捕捉标记(例如Vicon)的物体,并希望模拟的物体以相同的方式移动,同时与其他模拟物体交互。这里存在一个困境:虚拟物体无法推动您的物理手,因此您的手(以及您控制的物体)可以违反模拟物理规则。但同时我们希望 resulting simulation to be reasonable。我们如何做到这一点?

第一步是在MJCF模型中定义一个mocap主体,并实现代码在运行时读取数据流,并将mjModel.mocap_posmjModel.mocap_quat设置为从运动捕捉系统接收到的位置和方向。simulate.cc代码示例使用鼠标作为运动捕捉设备,允许用户移动mocap主体

particle

关于运动捕捉主体,关键要理解的是模拟器将其视为固定的。我们通过直接更新它们的位置和方向,使其在一个模拟时间步到下一个模拟时间步之间移动,但就物理模型而言,它们的位置和方向是恒定的。那么,如果我们与一个常规动态主体发生接触会发生什么,就像MuJoCo发行版提供的粒子示例一样(回想一下,在这些示例中,我们有一个作为运动捕捉主体并通过鼠标移动的胶囊探针)。两个常规主体之间的接触将经历穿透和相对速度,而与运动捕捉主体的接触则缺少相对速度分量,因为模拟器不知道运动捕捉主体本身正在移动。因此,resulting contact force is smaller并且 contact takes longer to push the dynamic object away。此外,在更复杂的模拟中,我们正在做一些与物理规则不一致的事情,这可能导致不稳定。

然而,还有一种表现更好的替代方案。除了运动捕捉主体外,我们还包含第二个常规主体,并使用焊接相等约束将其连接到运动捕捉主体。在下面的图中,粉红色框是运动捕捉主体,它连接到手的底部。在没有其他约束的情况下,手几乎完美地跟踪运动捕捉主体(比弹簧-阻尼器好得多),因为约束是隐式处理的,可以产生很大的力而不会使模拟不稳定。但是,如果手被迫与桌子接触(右图),它无法同时满足接触约束和跟踪运动捕捉主体。这是因为运动捕捉主体可以穿过桌子。那么哪个约束获胜?这取决于焊接约束相对于接触约束的软度。需要调整相应的solrefsolimp参数以实现所需的权衡。有关示例,请参见MuJoCo论坛上提供的模块化假肢手(MPL)模型;下面的图表是使用该模型生成的。

image18 image19

内存分配#

MuJoCo将运行时所需的所有内存预先分配到mjData中,并且在模型创建后不访问堆分配器。mjData中的内存由mj_makeData在两个连续的块中分配

  • mjData.buffer包含固定大小的数组。

  • mjData.arena包含动态大小的数组。

arena内存空间中有两种类型的动态数组分配。

  • contacts和与约束相关的数组从arena的开头布局。

  • stack数组从arena的末尾布局。

通过从arena空间的两侧分配动态数量,可变大小内存分配由一个单一数字控制:size MJCF元素的memory属性。与buffer中的固定大小数组不同,arena中的可变大小数组可以为NULL,例如在调用mj_resetData之后。当arena内存用尽时,将发生以下三种情况之一,具体取决于请求的内存类型

  • 如果在接触分配期间内存用尽,将发出警告,此步骤中不会添加后续接触,但模拟照常继续。

  • 如果在约束相关分配期间内存用尽,将发出警告,此步骤中将禁用约束求解器,但模拟照常继续。请注意,没有约束求解器的物理通常会非常不同,但允许模拟继续仍然有用,例如在场景初始化期间许多主体暂时重叠时。

  • 如果在栈数组分配期间内存用尽,将发生硬错误。

buffer的大小不同,arena的大小无法预先计算,因为接触数量和栈使用情况事先未知。那么应该如何选择它呢?目前使用以下简单的启发式方法,将来可能会改进:在最坏情况下,为100个接触和500个标量约束分配足够的内存。如果此启发式方法不足,我们建议以下步骤。使用memory属性显著增加arena内存,并检查运行时实际使用的内存。mjData.maxuse_arena跟踪自上次重置以来的最大arena内存利用率。simulate查看器在信息窗口(左下角)中将此数字显示为总arena空间的百分比。因此,可以从一个较大的数字开始,模拟一段时间,如果百分比较小,则回到XML并减小分配大小。但请记住,内存利用率在模拟过程中可能会发生巨大变化,具体取决于活动的约束数量以及使用的约束求解器。CG求解器内存效率最高,其次是牛顿求解器,而PGS求解器内存密集度最高。我们在设计模型时,通常目标是在探索模型时遇到的最坏情况下的内存利用率为50%。如果您只想使用CG求解器,则可以显著减少arena分配。

注意

MuJoCo 2.3.0中内存分配行为发生变化。在此版本之前,size MJCF元素的njmaxnconmaxnstack属性的语义分别为为接触、约束和栈分配的最大内存。如果您使用的是早期版本的MuJoCo,请切换到早期文档版本以了解之前的行为。

技巧与窍门#

这里提供了一些关于如何完成常见建模任务的指导。这里没有新内容,从这个意义上说,本节中的所有内容都可以从文档的其余部分推断出来。然而,推断过程并不总是显而易见的,因此将其明确写出来可能很有用。

性能调优#

下面列出了为最大限度提高模拟吞吐量可以采取的步骤。所有建议都涉及参数调整。建议在查看simulate实用程序内置的性能分析器时以交互方式进行这些操作。性能分析器还会报告详细且有时更有用的性能分析,可以通过testspeed实用程序获取。在开始下面更复杂的步骤时,请针对性能分析器报告的最昂贵的管线组件。请注意,其中一些对于MJX略有不同,请参见此处的专门章节。

  1. Timestep:尝试增加模拟时间步长。如数值积分一节末尾所述,时间步长是任何模型中最重要的参数。默认值是出于稳定性而非效率的考虑而选择的,通常可以增加。在某个时候,进一步增加会导致发散,因此最优时间步长是在发散从未发生或非常罕见的情况下最大的时间步长。实际值取决于模型。

  2. 积分器:根据数值积分一节末尾的建议选择您的积分器。默认推荐选择是implicitfast积分器。

  3. 约束雅可比矩阵:尝试在“dense”和“sparse”之间切换雅可比矩阵设置。这两种选项使用分别使用稠密或稀疏代数的独立代码路径,但在计算上是相同的,因此始终首选更快的一个。默认的“auto”启发式方法并非总是做出正确的选择。

  4. 约束求解器:如果性能分析器报告求解器花费了大量时间,请考虑以下几点

    • 求解器:默认的Newton通常是最快的求解器,因为它需要最少的迭代次数才能收敛。对于大型模型,CG求解器可能更快;对于自由度多于约束的模型,PGS求解器将最快,尽管这种情况并不常见。

    • 迭代次数容差:尝试减少迭代次数,或者等效地增加求解器的终止容差。特别是对于通常在2-3次(昂贵的)迭代中达到数值收敛的Newton求解器,最后一次迭代会将精度提高到没有明显影响的水平,可以跳过。

  5. 碰撞:如果性能分析器报告碰撞检测占用了大量计算时间,请考虑以下步骤

    • 使用contype / conaffinity机制减少检查的碰撞次数,如碰撞检测一节所述。

    • 修改碰撞几何体,用更廉价的原始体-原始体碰撞测试替换昂贵的碰撞测试(例如网格-网格)。根据经验,碰撞表中engine_collision_driver.c顶部具有自定义对函数的碰撞比使用通用凸体-凸体碰撞器mjc_Convex的碰撞要便宜得多。最昂贵的碰撞是涉及SDF几何体的碰撞。

    • 如果无法用原始体替换碰撞网格,请尽可能地简化网格。trimesh、Blender、MeshLab和CoACD等开源工具在这方面非常有用。

  6. 摩擦锥:椭圆锥更精确,在高impratio下更能防止滑动,但也更昂贵。如果精确摩擦不重要,请尝试切换到金字塔锥。

  7. 使用32位浮点精度(而不是默认的64位)编译MuJoCo。对于在多线程模式下运行的大型模型,内存访问比计算更昂贵,这可以带来(最高)2倍的性能提升。有关更多信息,请参见mjtNum

防止滑动#

下面列出了诊断和解决接触滑动的一些步骤,这在操作任务中尤其成问题。为了诊断滑动,建议使用simulate实用程序的内置可视化选项来检查接触和接触力。通常调整接触和力的大小(使用全局meansize或特定属性contactwidthcontactheightforcewidth)以及力缩放属性以更好地可视化和理解接触配置及resulting forces通常是有帮助的。

阻止滑动的接触力超出了摩擦锥

这意味着物理原理上无法阻止滑动。这发生在以下情况:

  1. 法向力太小。确保夹具能施加的最大力乘以滑动摩擦系数显著大于物体的重量。

  2. 滑动摩擦系数太低。增加滑动friction系数。

  3. 扭转摩擦不足以施加所需的扭矩。增加condim到4或6并选择适当的摩擦系数。condim 4启用扭转摩擦,阻止绕法向旋转。condim 6还启用滚动摩擦,阻止绕切向方向旋转。详见接触章节以及这些系数的具体语义。

几何体不支持所需的力或扭矩

这是一个常见的现实问题,通过改进夹具和手柄的设计来解决。

  1. 改善接触几何体的形状,增加更多接触点,可能采用非平面几何体(例如凸起),以便通过法向力而不是仅靠摩擦分量来防止滑动。

  2. 如果接触发生在平面之间,请尝试启用multiccd标志,该标志允许检测器找到比凸体-凸体碰撞器返回的单个接触更多的接触。

  3. 尝试通过设置nativeccd标志启用原生碰撞检测管线,该管线使用更准确高效的凸体碰撞检测算法。

高频振动

高频、低幅度振动也是许多工业环境中的现实问题,但与模拟不同,在现实世界中它们是可听见的。此类振动通常由增益非常高的控制器引起,有时也由接触或关节产生的黏滑反馈与机构的固有振型共振引起。诊断此类振动最简单的方法是在simulate中可视化接触力。解决方案通常是减小timestep和/或为相关关节添加一些armature。振动的另一个原因是来自显式阻尼的反馈。请使用隐式或implicitfast积分器,如数值积分一节所述。

慢速滑动

与导致快速滑动的上述问题不同,慢速、渐进式滑动是MuJoCo接触模型设计固有的特性,因为没有它,逆动力学就无法定义。这一点在软度与滑动澄清中详细讨论。这种类型的滑动可以通过两种方式解决。

  1. 增加impratio参数。这将减少(但不会完全阻止)慢速滑动。请注意,高impratio值仅适用于椭圆锥

  2. 通过将noslip_iterations增加到正整数来启用无滑动求解器。少量迭代(1、2或3)通常就足够了。无滑动后处理求解器将完全阻止滑动,代价是使逆动力学定义不清并增加额外的计算成本。

间隙#

许多机器人关节中都存在间隙。这通常是由齿轮箱中齿轮之间的小间隙引起的,但也可能由关节机构中的一些松动引起。其效果是电机可以转动一个小的角度,然后关节才开始转动,反之亦然(当关节上施加外力时)。间隙可以在MuJoCo中建模如下。与其在主体内设置一个单一的铰链关节,不如定义两个位置和方向相同的铰链关节

<body>
  <joint name="J1" type="hinge" pos="0 0 0" axis="0 0 1" armature="0.01"/>
  <joint name="J2" type="hinge" pos="0 0 0" axis="0 0 1" limited="true" range="-1 1"/>
</body>

因此,主体相对于其父元素的整体旋转是J1+J2。现在定义一个仅作用于J1的执行器。J2上的小关节范围使其保持在0附近,但允许它在作用于其上的力的方向上稍作移动,从而产生间隙效应。请注意J1中的armature属性。没有它,关节空间惯量矩阵将是奇异的,因为两个关节可以沿相反方向加速而不会遇到任何惯性。导致间隙的物理齿轮实际上具有旋转惯性(我们称之为armature),因此这是一种现实的建模方法。此示例中的数值应进行调整以获得所需的行为。关节限制约束的solrefsolimp参数也可以进行调整,以使间隙旋转结束在更软或更硬的限制处。

除了在J2中指定关节限制外,还可以指定一个软相等约束,使J2=0。然后应调整约束阻抗函数,使其在J2=0附近较弱,并在远离0时变强。如求解器参数中所示的新的阻抗函数参数化使得这成为可能。与关节限制相比,相等约束方法将在间隙范围和限制范围之间产生更平滑的过渡。它也会一直处于活动状态,这对于需要将约束违反或约束力作为输入的用户代码很方便。

恢复系数#

存在另一种指定solref的机制,如求解器参数中所述。当两个数字都非正时,它们被解释为(-刚度,-阻尼)并按约束阻抗进行缩放。为了实现接触和其他约束的完美恢复,将刚度设置为某个合理的较大值,阻尼设置为零。下面是一个球体在恢复系数为1的平面上弹跳的示例,接触前后的能量大致守恒。它不是精确守恒的,因为接触本身是软的,需要几个时间步长,并且这些时间步长内的(隐式)变形并不是精确守恒能量的。但总体效果是球长时间弹跳,其峰值高度没有明显变化,并且能量在初始值附近波动而不是漂移。

<worldbody>
  <geom type="plane" size="1 1 .1"/>

  <body pos="0 0 1">
    <freejoint/>
    <geom type="sphere" size="0.1" solref="-1000 0"/>
  </body>
</worldbody>