建模(Modeling)#
介绍(Introduction)#
MuJoCo 可以加载其原生 MJCF 格式以及流行但功能更有限的 URDF 格式的 XML 模型文件。本章是 MJCF 建模指南。参考手册可在 XML 参考 章节中找到。URDF 文档可以在别处找到;这里我们仅描述 MuJoCo 特定的 URDF 扩展。
MJCF 模型可以表示具有广泛功能和模型元素的复杂动力系统。访问所有这些功能需要一个丰富的建模格式,如果设计时没有考虑可用性,可能会变得繁琐。因此,我们努力将 MJCF 设计为一种可扩展的格式,允许用户从小处着手,以后构建更详细的模型。在这方面特别有用的是广泛的 默认设置 机制,其灵感来自 HTML 中内联的层叠样式表 (CSS) 的想法。它使用户能够快速创建新模型并进行实验。通过众多可用于重新配置仿真管道的 选项 以及支持快速重新加载(使模型编辑成为交互式过程)的快速重新加载功能,进一步辅助了实验。
可以将 MJCF 视为建模格式和编程语言之间的混合体。有一个内置的编译器,这通常是与编程语言相关的概念。虽然 MJCF 不具备通用编程语言的功能,但会根据模型的设计方式自动调用许多复杂的编译时计算。
加载模型(Loading models)#
如概述章节中的 模型实例 所述,MuJoCo 模型可以从 MJCF 或 URDF 格式的纯文本 XML 文件加载,然后编译成低级的 mjModel。或者,先前保存的 mjModel 可以直接从二进制 MJB 文件加载——其格式未记录,但本质上是 mjModel 内存缓冲区的副本。MJCF 和 URDF 文件使用 mj_loadXML() 加载,而 MJB 文件使用 mj_loadModel() 加载。
加载 XML 文件时,首先使用内部的 TinyXML 解析器将其解析为文档对象模型 (DOM)。然后根据模型格式处理此 DOM 并将其转换为高级的 :type:`mjSpec` 对象。转换取决于模型格式——模型格式是从 XML 文件中的顶级元素推断出来的,而不是从文件扩展名推断的。回想一下,一个有效的 XML 文件有一个唯一的顶级元素。对于 MJCF,此元素必须是 mujoco,对于 URDF,必须是 robot。
编译模型(Compiling models)#
一旦创建了高级的 :type:`mjSpec`——通过加载 MJCF 文件或 URDF 文件,或者 以编程方式——它就会被编译成 :type:`mjModel`。编译独立于加载,这意味着无论 :type:`mjSpec` 是如何创建的,编译器的工作方式都相同。解析器和编译器都执行广泛的错误检查,并在遇到第一个错误时中止。生成的错误消息包含 XML 文件中的行号和列号,并且是自解释的,因此我们不在此处记录它们。解析器使用自定义模式来确保文件结构、元素和属性有效。然后编译器应用许多额外的语义检查。最后,执行编译模型的一个仿真步骤,并拦截任何运行时错误。后者是通过(临时)将 mju_user_error 设置为指向抛出 C++ 异常的函数来完成的;如果需要,用户可以在运行时实现类似的错误拦截功能。
解析和编译的整个过程非常快——如果模型不包含大型网格或需要通过仿真计算的执行器长度范围,则不到一秒。这使得可以通过经常重新加载和可视化更改来交互式地设计模型。请注意,simulate.cc 代码示例有一个用于重新加载当前模型的键盘快捷键 (Ctrl+L)。
保存模型(Saving models)#
一个 MJCF 模型可以包含多个(包含的)XML 文件以及从 XML 引用的网格、高度场和纹理。编译后,所有这些文件的内容都被组装到 mjModel 中,可以使用 mj_saveModel() 保存到二进制 MJB 文件中。MJB 是一个独立的文件,不引用任何其他文件。它加载速度也更快。因此,我们建议将常用模型保存为 MJB,并在需要仿真时加载它们。
也可以使用 mj_saveLastXML() 将编译后的 :type:`mjSpec` 保存为 MJCF。如果相应 mjModel 中的任何实值字段在编译后被修改(这种情况不常见,但可能在系统识别应用等情况下发生),则在保存前会自动将修改复制回 :type:`mjSpec`。请注意,无法在编译后的模型中进行结构性更改。XML 写入器尝试生成最小的 MJCF 文件,保证编译成相同的模型,模由实值的纯文本表示引起的可忽略的数值差异。生成的文件可能不具有与原始文件相同的结构,因为 MJCF 具有许多用户便利功能,允许以不同方式指定相同的模型。XML 写入器使用 MJCF 的“规范”子集,其中所有坐标都是本地的,所有身体位置、方向和质量属性都是明确指定的。在计算章节中,我们展示了一个 示例 MJCF 文件和相应的 保存示例。
编辑模型(Editing models)#
从 MuJoCo 3.2 开始,可以使用 :type:`mjSpec` 结构体和相关 API 创建和修改模型。有关更多文档,请参阅 模型编辑 章节。
MJCF 机制(MJCF Mechanisms)#
MJCF 使用多种模型创建机制,这些机制跨越多个模型元素。为了避免重复,我们在本节中仅详细描述它们一次。这些机制不对应于计算章节中引入的新的仿真概念。它们的作用是简化 MJCF 模型的创建,并允许使用不同的数据格式而无需手动转换为规范格式。
运动树(Kinematic tree)#
MJCF 文件的主要部分是由嵌套的 :elem:`body` 元素创建的 XML 树。顶级 body 是特殊的,称为 worldbody。这种树形组织与 URDF 形成对比,在 URDF 中,用户创建一系列链接,然后用指定子链接和父链接的关节连接它们。在 MJCF 中,子 body 字面上是父 body 的子级,在 XML 的意义上。
当在 body 内定义 :elem:`joint` 时,其功能不是连接父级和子级,而是在它们之间创建运动自由度。如果在给定的 body 中没有定义关节,则该 body 将焊接到其父级。MJCF 中的一个 body 可以包含多个关节,因此不需要引入虚拟 body 来创建复合关节。相反,只需在同一个 body 内定义形成所需复合关节的所有基本关节。例如,可以使用两个滑块和一个铰链来模拟在平面中移动的 body。
其他 MJCF 元素可以在由嵌套 body 元素创建的树中定义,特别是 :elem:`joint`、:elem:`geom`、:elem:`site`、:elem:`camera`、:elem:`light`。当在 body 内定义元素时,它固定在该 body 的局部坐标系中并始终随之移动。引用多个 body 或根本不引用 body 的元素在运动树之外的不同部分中定义。
默认设置(Default settings)#
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 中可能嵌套的 :elem:`default` 元素创建。每个类都有一个唯一的名称——这是一个必需的属性,除了顶级类,如果未定义,其名称为“main”。每个类还具有一组完整的虚拟模型元素,其属性设置如下。当一个默认类在另一个默认类中定义时,子类自动从父类继承所有属性值。然后它可以通过定义相应的属性来覆盖其中一些或全部。顶级默认类没有父类,因此其属性初始化为内部默认值,这些默认值显示在 参考章节 中。
默认类中包含的虚拟元素不是模型的一部分;它们仅用于初始化实际模型元素的属性值。当首次创建实际元素时,其所有属性都从当前活动的默认类中的相应虚拟元素复制。总是有一个活动的默认类,可以通过三种方式之一确定。如果当前元素或其任何祖先 body 中未指定类,则使用顶级类(无论它是称为“main”还是其他名称)。如果当前元素未指定类,但其一个或多个祖先 body 指定了 childclass,则使用最近祖先 body 的 childclass。如果当前元素指定了一个类,则无论其祖先 body 中的任何 childclass 属性如何,都使用该类。
某些属性,例如 body 惯性,可以处于特殊的未定义状态。这指示编译器从其他信息推断相应的值,在这种情况下是附加到 body 的 geom 的惯性。无法在 XML 文件中输入未定义状态。因此,一旦在给定类中定义了属性,就不能在该类或其任何子类中取消定义。因此,如果目标是让给定模型元素中的某个属性保持未定义,则它必须在活动的默认类中未定义。
这里的最后一个转折是执行器。它们是不同的,因为一些与执行器相关的元素实际上是快捷方式,而快捷方式与默认设置机制的交互方式并不明显。这在下面的 执行器快捷方式 部分中解释。
坐标系(Coordinate frames)#
运动树中定义的所有元素的位置和方向都在局部坐标中表示,body 相对于父 body,而 geom、joint、site、camera 和 light 相对于包含它们的 body。
一个相关的属性是 compiler/angle。它指定 MJCF 文件中的角度是以度还是弧度表示(编译后,角度始终以弧度表示)。
位置使用以下属性指定:
- pos:
real(3), “0 0 0” 相对于父级的位置。
框架方向(Frame orientations)#
几个模型元素具有与之关联的右手空间框架。这些都是在运动树中定义的所有元素,除了关节。空间框架由其位置和方向定义。指定 3D 位置很简单,但指定 3D 方向可能具有挑战性。这就是为什么 MJCF 提供了几种替代机制。无论用户选择哪种机制,框架方向总是在内部转换为单位四元数。回想一下,绕单位向量 \((x, y, z)\) 给出的轴旋转角度 \(a\) 对应于四元数 \((\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)\)。最后一个数字是旋转角度,以度或弧度表示,由 :elem:`compiler` 的
angle属性指定。前三个数字确定一个 3D 向量,即旋转轴。该向量在编译期间被规范化为单位长度,因此用户可以指定任何非零长度的向量。请记住旋转是右手性的;如果向量 \((x, y, z)\) 的方向反转,将导致相反的旋转。改变 \(a\) 的符号也可用于指定相反的旋转。- euler:
real(3), optional 围绕三个坐标轴的旋转角度。应用这些旋转的轴序列由 :elem:`compiler` 的
eulerseq属性确定,并且对于整个模型是相同的。- 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 轴定向)很有用。
求解器参数(Solver parameters)#
计算章节的求解器 参数 部分解释了确定 MuJoCo 约束行为的量 \(d, b, k\) 的数学和算法含义。这里我们解释如何设置它们。设置是间接完成的,通过属性 solref 和 solimp,这些属性在所有涉及约束的 MJCF 元素中都可用。这些参数可以按约束调整,或按默认类调整,或保持未定义——在这种情况下,MuJoCo 使用下面显示的内部默认值。另请注意 :elem:`option` 中可用的覆盖机制;它可用于在运行时更改所有与接触相关的求解器参数,以便交互式试验参数设置或为数值优化实现连续方法。
这里我们关注单个标量约束。使用与计算章节稍有不同的符号,让 \(a_{1}\) 表示加速度,\(v\) 表示速度,\(r\) 表示位置或残差(在摩擦维度中定义为 0),\(k\) 和 \(b\) 是用于定义参考加速度 \(a_{ref} = -b v - k r\) 的虚拟弹簧的刚度和阻尼。让 \(d\) 是约束阻抗,\(a_{0}\) 是没有约束力时的加速度。我们之前的分析表明,约束空间中的动力学近似为
再次强调,用户控制的参数是 \(d, b, k\)。其余量是系统状态的函数,并在每个时间步自动计算。
阻抗(Impedance)#
我们首先解释约束阻抗 \(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)\)——阻抗 \(d\) 作为约束违反 \(r\) 的函数。
前 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}\) 之间进行插值的 S 形函数的形状,如下图所示。 图显示了两条反射的 S 形曲线,因为阻抗 \(d(r)\) 取决于 \(r\) 的绝对值。 \(\text{power}`(用于生成函数的多项式样条的幂)必须大于或等于 1。 :math:\)text{midpoint}`(指定拐点)必须在 0 和 1 之间,并以 \(\text{width}\) 的单位表示。请注意,当 \(\text{power}\) 为 1 时,无论 \(\text{midpoint}\) 如何,函数都是线性的。
这些图在垂直轴上显示阻抗 \(d(r)\),在水平轴上显示约束违反 \(r\)。
对于等式约束,\(r\) 是约束违反。对于限制、椭圆锥的法线方向和金字塔锥的所有方向,\(r\) 是(限制或接触)距离减去约束变为活动状态的边距;对于接触,此边距是
margin-gap。 限制和接触约束在 :math:`r < 0`(穿透)时处于活动状态。对于摩擦损耗或椭圆锥的摩擦维度,违反 \(r\) 恒为零,因此只有 \(d(0)\) 影响这些约束,所有其他
solimp值都被忽略。平滑性和可微性
为了完全平滑(可微)的动力学,限制和接触应具有 \(d_0=0`(``solimp[0]=0`\))。 特别是对于接触,应记住与 geom 关联的求解器参数的 混合规则。 另请参阅 计算章节 中关于导数的讨论以及
mjd_transitionFD()文档。
参考(Reference)#
接下来我们解释刚度 \(k\) 和阻尼 \(b\) 的设置,它们控制参考加速度 \(\ar\)。
参考加速度 的直观描述
参考加速度 \(\ar\) 决定了约束为了纠正违反而**试图实现的运动**。 想象一个物体掉落到平面上。撞击时,约束将产生一个法向力,试图使用特定的运动来纠正穿透;这个运动就是参考加速度。
理解参考加速度的另一种方式是思考计算章节中描述的未建模的变形变量。 想象两个物体压在一起,导致接触处变形。现在非常快地拉开物体;变形在恢复到未变形状态时的运动就是参考加速度。
这个加速度由两个数字定义,一个刚度 \(k\) 和一个阻尼 \(b\),可以直接设置或重新参数化为质量-弹簧-阻尼器系统(一个 :wikipedia:`简谐振子 <Harmonic_oscillator>`)的时间常数和阻尼比。参考加速度由 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{split}\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}\end{split}\]timeconst 参数应至少比仿真时间步长大两倍,否则系统可能相对于数值积分器变得太 stiff(特别是当使用欧拉积分时),并且仿真可能变得不稳定。这在内部是强制执行的,除非 :elem:`option` 的
flag/refsafe属性设置为 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{split}\begin{aligned} b &= \text{damping} / d_\text{width} \\ k &= \text{stiffness} \cdot d(r) / d_\text{width}^2 \\ \end{aligned}\end{split}\]类似于上面的推导,如果参考加速度使用负数格式给出且阻抗是常数,则静止时的穿透深度为
\[r = \frac{\au (1 - d)}{\text{stiffness}}\]
提示
在正值的默认格式中,\(\text{timeconst}\) 参数控制约束**柔软度**。 它以时间单位指定,意思是“约束试图解决违反的速度有多快”。较大的值对应于较软的约束。
负值的“直接”格式更灵活,例如允许完全弹性碰撞(\(\text{damping} = 0\))。它是系统识别的推荐格式。
正值格式中 \(\text{dampratio}\) 为 1 等价于直接格式中的 \(\text{damping} = 2 \sqrt{ \text{stiffness} }\)。
接触参数(Contact parameters)#
每个接触的参数在计算章节的 接触 部分中进行了描述。这里我们解释如何设置这些参数。如果几何体对是使用 XML 元素 :elem:`pair` 明确定义的,则它具有直接指定所有接触参数的属性。在这种情况下,将忽略各个 geom 的参数。另一方面,如果接触是由动态机制生成的,则需要从接触对中的两个 geom 推断其参数。如果两个 geom 具有相同的参数,则无需执行任何操作,但如果它们的参数不同怎么办?在这种情况下,我们使用 geom 属性 solmix 和 priority 来决定如何组合它们。每个接触参数的组合规则如下:
- condim
如果两个 geom 中有一个具有更高的优先级,则使用其 condim。如果两个 geom 具有相同的优先级,则使用两个 condim 的最大值。这样,一个无摩擦的 geom 和一个有摩擦的 geom 会形成一个有摩擦的接触,除非无摩擦的 geom 具有更高的优先级。后者在粒子系统等情况下是可取的,我们可能不希望粒子粘附到任何物体上。
- friction
回想一下,接触最多可以有 5 个摩擦系数:两个切向、一个扭转、两个滚动。mjData.contact 中的每个接触实际上都具有所有这 5 个系数,即使 condim 小于 6 并且并非所有系数都被使用。相比之下,geom 只有 3 个摩擦系数:切向(两个轴相同)、扭转、滚动(两个轴相同)。这 3 个摩擦系数的向量中的每一个都通过复制切向和滚动分量扩展为 5 个摩擦系数的向量。有关切向、扭转和滚动系数的直观描述,请参阅计算章节的 接触 部分。
然后根据以下规则计算接触摩擦系数:如果两个 geom 中有一个具有更高的优先级,则使用其摩擦系数。否则,使用两个 geom 上每个摩擦系数的**逐元素最大值**。
接触有 5 个系数而 geom 只有 3 个系数的原因如下。对于接触对,我们希望允许我们的求解器可以处理的最灵活的模型。如前所述,各向异性摩擦可用于模拟滑行等效果。然而,这需要知道接触切平面的两个轴是如何定向的。对于预定义的接触对,我们事先知道两种几何体类型,相应的碰撞函数总是生成以相同方式定向的接触框架——我们在这里不描述,但可以在可视化器中看到。然而,对于单个 geom,我们不知道它们可能与哪些其他 geom 碰撞以及它们的几何体类型可能是什么,因此在指定单个 geom 时无法知道接触切平面将如何定向。这就是为什么 MuJoCo 不允许在单个 geom 规范中使用各向异性摩擦,而只允许在显式接触对规范中使用。
- margin, gap
使用两个 geom 边距(或间隙)的最大值。geom 优先级在这里被忽略,因为边距和间隙是距离属性,单方面指定没有意义。
- solref, solimp
如果两个 geom 中有一个具有更高的
priority,则使用其 solref 和 solimp 参数。如果两个 geom 具有相同的优先级,则使用加权平均值。权重与 solmix 属性成比例,即 weight1 = solmix1 / (solmix1 + solmix2),类似地 weight2。这个加权平均规则有一个重要的例外。如果任一 geom 的 solref 非正,即它依赖于直接格式,则无论 solmix 如何,都使用逐元素最小值。这是因为平均不同格式的 solref 参数是没有意义的。
接触覆盖(Contact override)#
MuJoCo 使用计算章节中描述的精心设计且新颖的 约束模型。获得关于此模型如何工作的直觉需要一些实验。为了促进这个过程,我们提供了一种机制来覆盖一些求解器参数,而无需对实际模型进行更改。一旦覆盖被禁用,仿真将恢复为模型中指定的参数。此机制也可用于在数值优化(例如最优控制或状态估计)的上下文中实现连续方法。这是通过允许接触在优化的早期阶段从远处起作用来实现的——以帮助优化器找到梯度并接近一个好的解决方案——并在后期减少这种效果以使最终解决方案物理上真实。
这里相关的设置是 :elem:`option` 的 flag/override 属性,它启用和禁用此机制,以及 :elem:`option` 的 o_margin、o_solref、o_solimp 属性,它们指定新的求解器参数。请注意,覆盖仅适用于接触,而不适用于其他类型的约束。原则上,MuJoCo 模型中有许多实值参数可以从类似的覆盖机制中受益。然而,我们必须在某处划清界限,而接触是自然的选择,因为它们产生了最丰富但最难调整的行为。此外,接触动力学通常在数值优化方面提出挑战,经验表明,在接触参数上进行连续可以帮助避免局部最小值。
用户参数(User parameters)#
许多 MJCF 元素具有可选的 user 属性,它定义了一个特定于元素的自定义参数数组。这与 :size: 元素的相应 “nuser_XXX” 属性交互。例如,如果我们设置 nuser_geom 为 5,那么 mjModel 中的每个 geom 都将拥有一个包含 5 个实值参数的自定义数组。这些特定于 geom 的参数要么通过 :geom: 的 user 属性在 MJCF 文件中定义,如果省略此属性,则由编译器设置为 0。所有 “nuser_XXX” 属性的默认值为 -1,这会指示编译器自动将此值设置为模型中定义的最大关联 user 属性的长度。MuJoCo 不在任何内部计算中使用这些参数;它们可供自定义计算使用。解析器允许 XML 中任意长度的数组,编译器随后会将其调整大小为长度 nuser_XXX。
一些通常用于内部计算的元素特定参数也可以用于自定义计算。这是通过安装用户回调(user callbacks)来覆盖部分模拟流水线实现的。例如,:general: 执行器元素具有属性 dyntype 和 dynprm。如果 dyntype 设置为 “user”,那么 MuJoCo 将调用 mjcb_act_dyn 来计算执行器动力学,而不是调用其内部函数。由 mjcb_act_dyn 指向的用户函数可以按照其意愿解释 dynprm 中定义的参数。但是,此参数数组的长度无法更改(与之前描述的自定义数组不同,后者的长度在 MJCF 文件中定义)。其他回调也是如此。
除了上述元素特定的用户参数之外,还可以通过 :custom: 元素在模型中包含全局数据。对于在模拟过程中变化的数据,还有数组 mjData.userdata,其大小由 :size: 元素的 nuserdata 属性决定。
求解器设置(Solver settings)#
约束力和约束加速度的计算涉及数值求解一个优化问题。MuJoCo 有三种算法来解决这个优化问题:CG、Newton、PGS。每种算法都可以应用于金字塔形或椭圆形摩擦锥模型,并使用稠密或稀疏的约束雅可比矩阵。此外,用户可以指定最大迭代次数和控制提前终止的容差水平。还有一个第二 Noslip 求解器,它是一个后处理步骤,通过指定正数的 noslip 迭代次数来启用。所有这些算法设置都可以在 :option: 元素中指定。
默认设置适用于大多数模型,但在某些情况下需要调整算法。最好的方法是尝试相关的设置,并使用 simulate.cc 中的可视化分析器,该分析器显示不同计算的时间以及每次迭代的求解器统计信息。我们可以提供以下一般指南和观察结果:
约束雅可比矩阵对于小型模型应为稠密的,对于大型模型应为稀疏的。默认设置是 ‘auto’;当自由度数量最多为 60 时解析为稠密,超过 60 时解析为稀疏。但请注意,阈值最好根据活动约束的数量来定义,这取决于模型和行为。
在金字塔形和椭圆形摩擦锥之间的选择是建模选择而不是算法选择,即,它导致使用相同算法解决不同的优化问题。椭圆形锥更符合物理现实。然而,金字塔形锥可以提高算法性能——但不一定总是如此。虽然默认是金字塔形,但我们建议尝试椭圆形锥。当接触滑移是个问题时,抑制它的最佳方法是使用椭圆形锥、大的
impratio以及具有非常小容差的 Newton 算法。如果这还不够,启用 Noslip 求解器。Newton 算法是大多数模型的最佳选择。它在全局最小值附近具有二次收敛性,并且以惊人的少迭代次数到达那里——通常大约 5 次,很少超过 20 次。它应该与积极的容差值一起使用,例如 1e-10,因为它能够在最后阶段实现高精度而不会增加延迟(由于二次收敛)。唯一我们看到它变慢的情况是具有椭圆形锥和许多滑移接触的大型模型。在该状态下,Hessian 分解需要大量更新。在一些具有不幸模型元素排序导致高填充(fill-in)的大型模型中,它也可能变慢(计算最优消去顺序是 NP 难问题,因此我们依赖启发式方法)。请注意,分解后的 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 求解器,当两者都启用时,PGS 的设置成本将被支付,即使主求解器是 CG 或 Newton。主 PGS 和 Noslip PGS 的设置操作是相同的,因此当两者都启用时,设置成本只支付一次。
执行器(Actuators)#
本节描述了在 MuJoCo 中使用执行器的各个方面。关于计算模型,请参见 Actuation model。
组禁用(Group disable)#
- actuatorgroupdisable:
属性(可以通过在运行时设置 mjOption.disableactuator 整数位域来更改)允许用户根据执行器的 :group: 来禁用执行器集合。当希望为同一个运动树使用多种类型的执行器时,此功能非常方便。例如,考虑一个固件支持多种控制模式(例如,扭矩控制和位置控制)的机器人。在这种情况下,可以在同一个 MJCF 模型中定义两种类型的执行器,将一种类型的执行器分配给组 0,另一种分配给组 1。
- actuatorgroupdisable:
MJCF 属性选择默认禁用哪些组,并且可以在运行时设置 mjOption.disableactuator 来切换活动集。请注意,执行器总数
mjModel.nu保持不变,执行器索引也保持不变,因此需要用户知道被禁用的执行器相应的mjData.ctrl值将被忽略并且不产生任何力。此示例模型 有三个执行器组,可以在 simulate 交互式查看器中在运行时切换。参见 示例模型 和右侧的关联屏幕截图。
快捷方式(Shortcuts)#
如计算章节的 Actuation model 部分所述,MuJoCo 提供了一个灵活的执行器模型,具有传动、激活动力学和力生成组件,可以独立指定。完整的功能可以通过 XML 元素 :general: 访问,它允许用户创建各种自定义执行器。此外,MJCF 提供了用于配置常见执行器的快捷方式。这是通过 XML 元素 :motor:、:position:、:velocity:、:intvelocity:、:damper:、:cylinder:、:muscle: 和 :adhesion: 完成的。这些*不是*独立的模型元素。MuJoCo 内部仅支持一种执行器类型——这就是为什么当保存 MJCF 模型时,所有执行器都写为 general。快捷方式隐式地创建通用执行器,将其属性设置为合适的值,并公开一个具有可能不同名称的属性子集。例如,position 创建一个位置伺服,具有属性 kp``(伺服增益)。然而 ``general 没有 kp 属性。相反,解析器以协调的方式调整通用执行器的增益和偏置参数,以模拟位置伺服。通过直接使用 general 并将其属性设置为如下所述的某些值,也可以达到相同的效果。
执行器快捷方式也与默认值交互。回想一下,default setting 机制涉及类,每个类都有一个完整的虚拟元素集合(每种元素类型一个),用于初始化实际模型元素的属性。特别是,每个默认类只有一个通用执行器元素。如果我们在同一个默认类中指定了 position,后来又指定了 velocity,会发生什么?XML 元素按顺序处理,并且每次遇到与执行器相关的元素时,都会设置单个通用执行器的属性。因此 velocity 具有优先权。然而,如果我们在默认类中指定了 general,它将只设置明确给出的属性,而保持其余属性不变。在创建实际模型元素时也会出现类似的复杂情况。假设活动的默认类指定了 position,现在我们使用 general 创建一个执行器,并省略了它的某些属性。缺失的属性将被设置为用于建模位置伺服的值,即使此执行器可能并非 intended 作为位置伺服。
鉴于这些潜在的复杂性,我们推荐一个简单的方法:在默认类和实际模型元素的创建中都使用相同的执行器快捷方式。如果给定模型需要不同的执行器,要么创建多个默认类,要么避免对执行器使用默认值,而是显式指定它们的所有属性。
力限制(Force limits)#
执行器力通常限制在下限和上限之间。可以通过三种方式强制执行这些限制:
- 控制值钳位(Control clamping)与 ctrlrange:
如果设置了此执行器属性,输入的控制值将被钳位。对于简单的 motor, 钳位控制输入等同于钳位力输出。
- 在执行器输出端进行力钳位(Force clamping at actuator output)与 forcerange:
如果设置了此执行器属性,执行器的输出力将被钳位。此属性对于例如 position actuators 很有用, 以将力保持在界限内。请注意,位置执行器通常也需要控制范围钳位以避免达到关节限制。
- 在关节输入端进行力钳位(Force clamping at joint input)与 joint/actuatorfrcrange:
此关节属性会钳位所有作用于该关节的执行器传来的力(在通过 transmission 之后)。 如果传动是平凡的(执行器与关节之间存在一一对应关系),在关节处钳位执行器力等同于在执行器处钳位。 然而,在多个执行器作用于一个关节或一个执行器作用于多个关节的情况下——但实际的扭矩是由关节处的单个物理执行器施加的——则希望在关节本身处钳位力。 以下是三个希望在关节处而非执行器处钳位执行器力的示例:
在 此示例模型 中, 两个执行器,一个 motor 和一个 damper,作用于单个关节。
在 此示例模型 (类似于“Dubin’s Car”)中, 两个执行器通过 fixed tendon 传动作用于两个车轮,以施加对称(向前/后滚动)和反对称(向左/右转向)扭矩。
在 此示例模型 中, site transmission 实现了手臂末端执行器的笛卡尔控制器。 为了使计算的扭矩能够由单个扭矩受限的关节电机实现,需要在关节处对它们进行钳位。
请注意,在这种情况下,力/扭矩通过传动组合,应使用 jointactuatorfrc 传感器报告作用于关节上的总执行器力。 标准的 actuatorfrc 传感器将继续报告钳位前的执行器力。
- 在肌腱输入端进行力钳位(Force clamping at tendon input)与 tendon/actuatorfrcrange:
此肌腱属性会钳位所有作用于该肌腱的执行器传来的力。
上述钳位选项并非互斥,可以根据需要组合使用。
长度范围(Length range)#
字段 mjModel.actuator_lengthrange 包含可行执行器长度(更准确地说,是执行器传动长度)的范围。
这是模拟 muscle actuators 所必需的。这里我们重点讨论 actuator_lengthrange 的含义以及如何设置它。
与 mjModel 中所有其他是精确物理或几何量的字段不同,actuator_lengthrange 是一个近似值。 直观上,它对应于执行器传动在所有模型“可行”配置下所能达到的最小和最大长度。然而,MuJoCo 的约束是软的,因此原则上任何配置都是可行的。 但我们仍然需要为肌肉建模定义一个明确的范围。有三种方法可以设置此范围:(1) 使用所有执行器中可用的新属性 lengthrange 显式提供它; (2) 从执行器所连接的关节或肌腱的限制中复制它;(3) 自动计算,如本节其余部分所述。这里有许多选项,由新的 XML 元素 lengthrange 控制。
执行器长度范围的自动计算在编译时完成,结果存储在已编译模型的 mjModel.actuator_lengthrange 中。 如果模型随后被保存(无论是 XML 还是 MJB 格式),则在下一次加载时不需要重复计算。这一点很重要,因为计算会拖慢具有大型肌肉骨骼模型的模型编译器。 实际上,我们使编译器多线程化就是为了加速此操作(不同的执行器在不同的线程中并行处理)。
自动计算依赖于修改后的物理模拟。对于每个执行器,我们通过执行器的传动施加力(计算最小值时为负,计算最大值时为正), 在避免不稳定的阻尼状态下推进模拟,给予足够的时间使其稳定并记录结果。这与带动量的梯度下降法有关,实际上我们已经试验过显式的基于梯度的优化, 但问题在于不清楚我们应该优化什么目标(考虑到软约束的混合)。通过使用模拟,我们基本上是让物理告诉我们该优化什么。 但请记住,这仍然是一个优化过程,因此它具有可能需要调整的参数。我们提供了应适用于大多数模型的保守默认值,但如果不行, 请使用 lengthrange 的属性进行微调。
使用此功能时,务必牢记模型的几何结构。这里的隐含假设是可行执行器长度确实是有限的。此外,我们不将接触视为限制因素 (事实上,我们在此模拟中内部禁用了接触,以及被动力、重力、摩擦损耗和执行器力)。这是因为带有接触的模型可能会纠缠在一起并产生许多局部最小值。 因此,执行器应该受到模型中定义的关节或肌腱限制(在此模拟期间启用)或几何形状的限制。为了说明后者,考虑一个肌腱, 其一端附着于世界,另一端附着于一个通过铰链关节附着于世界的旋转物体。在这种情况下,肌腱的最小和最大长度是明确定义的, 并且取决于附着点在空间中追踪的圆的大小,即使用户没有为关节或肌腱定义任何限制。但是,如果执行器连接到关节,或连接到等于关节的固定肌腱,则它是无限制的。 编译器在这种情况下会返回错误,但它无法判断错误是由于缺乏收敛还是因为执行器长度无限制。所有这些听起来过于复杂, 在某种意义上,我们在这里考虑了所有可能的极端情况。在实践中,长度范围几乎总是用于连接到空间肌腱的肌肉执行器,并且模型中会定义关节限制,从而有效地限制肌肉执行器的长度。 如果您在此类模型中遇到收敛错误,最可能的解释是您忘记了包含关节限制。
有状态执行器(Stateful actuators)#
如计算章节的 Actuation model 部分所述,MuJoCo 支持具有内部动力学的执行器,其状态称为“激活(activations)”。
激活限制(Activation limits)#
有状态执行器的一个有用应用是“集成速度(integrated-velocity)”执行器,由 intvelocity 快捷方式实现。 与 pure velocity 执行器(直接对传动目标的velocity进行反馈)不同,*集成速度*执行器将一个*积分器*与一个*位置反馈*执行器耦合。 在这种情况下,激活状态的语义是“位置执行器的设定点”,而控制信号的语义是“位置执行器设定点的速度”。 请注意,在真实的机器人系统中,这种集成速度执行器是实现具有速度语义的执行器的最常见方式,而不是纯粹的速度反馈,后者通常非常不稳定(无论是在现实生活中还是在模拟中)。
对于集成速度执行器,通常希望*钳位*激活状态,否则位置目标会持续积分超出关节限制,导致可控性丧失。要查看激活钳位的效果,请加载以下示例模型:
请注意,actrange 属性始终以本地单位(弧度)指定,即使关节范围可以是度(默认)或弧度,具体取决于 compiler/angle 属性。
肌肉(Muscles)#
我们提供了一套用于建模生物肌肉的工具。希望以最少工作量添加肌肉的用户只需在执行器部分使用一行 XML 即可完成:
1<actuator>
2 <muscle name="mymuscle" tendon="mytendon">
3</actuator>
生物肌肉看起来彼此非常不同,但一旦应用了某种缩放,它们的行为却惊人地相似。我们的默认设置应用了这种缩放, 这就是为什么可以在不调整任何参数的情况下获得合理的肌肉模型。当然,构建更详细的模型需要调整参数,如本节所述。
请记住,即使肌肉模型相当精细,它仍然是 MuJoCo 执行器的一种类型,并遵守与所有其他执行器相同的约定。 可以使用 general 定义肌肉,但快捷方式 muscle 更方便。 与所有其他执行器一样,力产生机制和传动是独立定义的。然而,肌肉只有在连接到肌腱或关节传动时才有(生物)物理意义。 为具体起见,我们这里假设使用肌腱传动。
首先我们讨论长度和长度缩放。传动(即 MuJoCo 肌腱)的可行长度范围将扮演重要角色;请参见上面的 Length range 部分。 在生物力学中,肌肉和肌腱串联连接并形成肌肉-肌腱执行器。我们的约定有些不同:在 MuJoCo 中,具有空间属性(特别是长度和速度)的实体是肌腱, 而肌肉是一个抽象的力生成机制,拉动肌腱。因此,MuJoCo 中的肌腱长度对应于生物力学中的肌肉+肌腱长度。 我们假设生物肌腱是无弹性的,具有恒定长度 \(L_T\),而生物肌肉长度 \(L_M\) 随时间变化。MuJoCo 肌腱长度是生物肌肉和肌腱长度的总和:
另一个重要的常数是肌肉的最佳静息长度,记为 \(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)\)。 现在我们可以计算这两个常数,利用实际范围和缩放范围必须相互映射的事实:
在运行时,我们计算缩放的肌肉长度和速度如下:
缩放量的优点在于所有肌肉在该表示下的行为相似。该行为由许多实验论文中测量的力-长度-速度(\(\text{\small FLV}\))函数捕获。我们如下近似该函数:
该函数的形式为:
与 MuJoCo 执行器的一般形式比较,我们看到 \(F_L\cdot F_V\) 是执行器增益,\(F_P\) 是执行器偏置。 \(F_L\) 是作为长度函数的主动力,而 \(F_V\) 是作为速度函数的主动力。它们相乘得到总主动力(注意乘以 act,即执行器激活)。 \(F_P\) 是无源力,无论激活与否始终存在。\(\text{\small FLV}\) 函数的输出是缩放的肌肉力。 我们将缩放力乘以肌肉特定的常数 \(F_0\) 以获得实际的力:
负号是因为正的肌肉激活产生拉力。常数 \(F_0\) 是零速度时的峰值主动力。它与肌肉厚度(即生理横截面积或 PCSA)有关。 如果已知,可以使用 muscle 元素的 force 属性设置它。如果未知,我们将其设置为 :math:`-1`(这是默认值)。 在这种情况下,我们依赖于这样一个事实:较大的肌肉往往作用于移动更多重量的关节。属性 scale 定义此关系为:
量 \(\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}\) 函数的形状影响更大, 并且在许多情况下此参数是未知的。下面是一个图形说明:
这种图形格式在生物力学文献中很常见,显示了每个肌肉的操作范围叠加在归一化的 \(\text{FL}\) 曲线上(忽略垂直位移)。 我们的默认范围以黑色显示。蓝色曲线是两种手臂肌肉的实验数据。可以找到范围小的肌肉、范围大的肌肉、范围跨越 \(\text{FL}\) 曲线上升部分、 或下降部分、或部分两者都有的肌肉。现在假设您有一个包含 50 块肌肉的模型。您是否相信有人做了细致的实验并测量了您模型中每块肌肉的操作范围, 考虑了肌肉跨越的所有关节?如果没有,那么最好将肌肉骨骼模型视为具有与生物系统相同的一般行为,而在各种细节上有所不同——包括某些研究团体非常感兴趣的细节。 对于建模者认为是常数和已知的大多数肌肉属性,都有实验论文表明它们在某些条件下会变化。这不是要阻止人们构建精确的模型, 而是阻止人们过于相信他们的模型。
回到我们的肌肉模型,还有肌肉激活 act。这是一个一阶非线性滤波器的状态,其输入是控制信号。滤波器动力学为:
内部控制信号被钳位到 [0, 1],即使执行器没有指定控制范围。有两个时间常数由属性 timeconst 指定,即 \(\text{timeconst} = (\tau_\text{act}, \tau_\text{deact})\),默认值为 \((0.01, 0.04)\)。 遵循 Millard et al. (2013),有效时间常数 \(\tau\) 在运行时计算如下:
由于上述方程描述了不连续的切换,这在基于导数的优化中可能是不希望的,我们引入了可选的平滑参数 tausmooth。 当大于 0 时,切换由 mju_sigmoid 替换,它将在 \((\texttt{ctrl}-\texttt{act}) \pm \text{tausmooth}/2\) 范围内平滑地在两个值之间插值。
现在我们总结一下 muscle 元素的属性,用户可能希望根据他们对生物力学文献的熟悉程度 以及关于特定模型的详细测量数据的可用性进行调整:
- Defaults(默认值)
在所有地方使用内置默认值。您所需要做的就是将肌肉连接到肌腱,如本节开头所示。这将产生一个通用但合理的模型。
- 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 元素中进行。
- Custom model(自定义模型)
用户可以不去调整我们的肌肉模型参数,而是通过将 general 执行器的 gaintype、biastype 和 dyntype 设置为“user” 并在运行时提供回调来实现不同的模型。或者,将其中一些类型设置为“muscle”并使用我们的模型,同时替换其他组件。 请注意,肌腱几何计算仍由标准的 MuJoCo 流水线处理,向用户的肌肉模型提供 actuator_length、actuator_velocity 和 actuator_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 中的肌腱缠绕也更有限。我们允许球体和无限圆柱体作为缠绕对象,并且要求肌腱路径中的两个缠绕对象由一个固定点位(site)分隔。这是为了避免迭代计算肌腱路径的需要。我们还允许在球体或圆柱体内部放置“侧点位(side sites)”,这会导致反向缠绕:肌腱路径被约束穿过对象而不是绕过它。这可以替代 OpenSim 中用于将肌腱路径保持在给定区域内的环面(torus)缠绕对象。总的来说,肌腱缠绕是将 OpenSim 模型转换为 MuJoCo 模型最具挑战性的部分,需要一些手动工作。好的一面是,实际使用的高质量 OpenSim 模型数量很少,所以一旦它们被转换完成,我们就完成了。
下面我们说明了可用的四种肌腱缠绕类型。请注意,缠绕肌腱的弯曲部分被渲染为直线,但几何管道处理的是实际曲线,并解析地计算它们的长度和力矩:
传感器(Sensors)#
MuJoCo 可以模拟多种传感器,如下面 sensor 元素所述。
用户传感器类型也可以定义,并通过回调函数 mjcb_sensor 进行评估。传感器不影响仿真。相反,它们的输出被复制到数组 mjData.sensordata 中,可供用户处理。
这里我们描述所有传感器类型共有的 XML 属性,以避免后面重复。
name: string, optional |
传感器名称。 |
noise: real, “0” |
此传感器噪声模型的标准差。在 3.1.4 版本之前,这会导致向传感器添加噪声。在 3.1.4 版本中,此功能被移除,有关详细理由请参见 3.1.4 更新日志。在后续版本中,此属性作为保存标准差信息以供后续使用的便捷位置。 |
cutoff: real, “0” |
当此值为正时,它会限制传感器输出的绝对值。它还在 simulate.cc 的传感器数据图中用于规范化传感器输出。 |
user: real(nuser_sensor), “0 0 …” |
参见 用户参数。 |
相机(Cameras)#
除了默认的、用户可控的自由相机之外,“固定”相机可以附加到运动树上。
外参 (Extrinsics) |
默认情况下,相机帧附加到包含它们的 body 上。可选的 mode 和 target 属性可用于指定跟踪(随动)或瞄准(看向)某个 body 或子树的相机。相机看向相机帧的负 Z 轴方向,而正 X 和 Y 分别对应于图像平面中的*右*和*上*。 |
内参 (Intrinsics) |
相机内参使用 :ref:`ipd <XMLreference.html#body-camera-ipd>`(瞳距,立体渲染和 VR 所需)和 :ref:`fovy <XMLreference.html#body-camera-fovy>`(垂直视场角,以度为单位)指定。 上述规范意味着一个完美的点相机,没有像差。然而,在校准真实相机时,可以使用标准渲染管线表示两种类型的线性像差。第一种是垂直和水平方向上的不同焦距(轴对齐散光)。第二种是非中心主点。这些可以使用 focal 和 principal 属性来指定。当使用这些与校准相关的属性时,还必须指定物理 sensor size 和相机 resolution。在这种情况下,可以可视化渲染视锥体。 |
复合对象(Composite objects)#
复合对象不是新的模型元素。相反,它们是最初设计用于模拟粒子系统、绳索、布料和软体的现有元素的集合。随着时间的推移,这些类型中的大多数已被 replicate <XMLreference.html#replicate>`(用于重复对象)和 :ref:`flexcomp <XMLreference.html#body-flexcomp>`(用于软对象)取代。因此,现在唯一支持的复合类型是 ``cable`,它产生一个由球关节连接而成的不可伸展的物体链。
复合对象由常规的 MuJoCo 物体(body)组成,在此上下文中我们称之为“元素物体”。元素物体的集合由模型编译器自动生成。用户在高层面上配置自动生成器,使用新的 XML 元素 composite 及其属性和子元素,如 XML 参考章节所述。如果编译后的模型随后被保存,则 :el:`composite` 不再存在,并被自动生成的常规模型元素集合所取代。所以可以把它看作是一个由模型编译器扩展的宏。元素物体作为 :el:`composite` 出现的 body 的子级创建;因此,复合对象出现在 XML 中与定义常规子 body 相同的位置。每个自动生成的元素物体都有一个单独的 geom 附加到它上面。我们设计了复合对象生成器,尽可能具有直观的高层控制,但同时它也暴露了大量相互作用的选项,这些选项可以深刻地影响最终的物理效果。所以在某些时候,用户应该仔细阅读 参考文档。
除了设置物理属性,复合对象生成器还创建合适的渲染。对象可以作为 skins 渲染。皮肤是自动生成的,并且可以进行纹理化以及使用双三次插值进行细分。实际的物理,特别是碰撞检测,基于元素物体及其 geoms,而皮肤纯粹是一个可视化对象。然而在某些情况下,我们更喜欢查看皮肤表示,例如在 这个模型 中,其皮肤是一个连续的柔性表面,而不是一组不连续的薄盒子。然而,在微调模型并试图理解其背后的物理原理时,能够渲染 geoms 是很有用的。要切换渲染样式,请禁用皮肤的渲染并为 geoms 和肌腱启用第 3 组(group 3)。
电缆 (Cable).
作为一个快速入门,MuJoCo 提供了一个复合电缆的例子。在所有例子中,我们都有一个包含在模型中的静态场景,后面跟着一个单一的复合对象。下面的 XML 片段只是复合对象的定义;请参阅发行版中的 XML 模型文件以获取完整示例。
1<extension>
2 <plugin plugin="mujoco.elasticity.cable"/>
3</extension>
4
5<worldbody>
6 <composite prefix="actuated" type="cable" curve="cos(s) sin(s) s" count="41 1 1"
7 size="0.25 .1 4" offset="0.25 0 .05" initial="none">
8 <plugin plugin="mujoco.elasticity.cable">
9 <!--Units are in Pa (SI)-->
10 <config key="twist" value="5e8"/>
11 <config key="bend" value="15e8"/>
12 <config key="vmax" value="0"/>
13 </plugin>
14 <joint kind="main" damping="0.15" armature="0.01"/>
15 <geom type="capsule" size=".005" rgba=".8 .2 .1 1"/>
16 </composite>
17</worldbody>
电缆模拟了一个具有扭转和弯曲刚度的不可伸展的弹性一维物体。它使用一系列胶囊体或盒子进行离散化。其刚度和惯性特性直接根据给定的参数和横截面形状计算,这允许各向异性的行为,例如在皮带或计算机电缆中可以找到。它是一个单一的运动树,因此无需额外的约束即可精确不可伸展,从而能够使用大的时间步长。弹性模型在几何上是精确的,基于计算中心线(穿过横截面中心的线)的 Bishop 或无扭转帧。geoms 的方向相对于该帧表示,然后分解为扭转和弯曲分量,因此可以独立设置不同的刚度。此外,可以指定无应力配置是平坦的还是弯曲的,例如在螺旋弹簧的情况下。电缆需要使用第一方 引擎插件,未来可能会直接集成到引擎中。
粒子 (Particle).
粒子类型已弃用。建议改用更通用的 replicate,例如 这个模型。
网格 (Grid).
网格复合类型已被移除。建议使用二维柔性 可变形对象 来模拟薄弹性结构。
绳索 (Rope) 和环 (Loop).
绳索和环已弃用。建议使用电缆模拟不可伸展的弹性杆(弯曲和扭转),并使用一维柔性 可变形对象 模拟拉伸载荷场景下的可伸展字符串(例如拉伸的橡皮筋)。
布料 (Cloth).
布料已弃用。建议使用二维柔性 可变形对象 来模拟薄弹性结构。
盒子 (Box)、圆柱体 (Cylinder) 和椭球体 (Ellipsoid).
盒子类型以及圆柱体和椭球体类型现在已弃用,取而代之的是三维柔性 可变形对象 元素。
可变形对象(Deformable objects)#
前面描述的 复合对象 旨在有效地在刚体模拟器中模拟软体。这是可能的,因为 MuJoCo 的约束是软的,但尽管如此,它在功能和建模能力上是有限的。在 MuJoCo 3.0 中,我们引入了真正的可变形对象,涉及新的模型元素。前面描述的 skin 实际上就是这样一个元素,但它仅用于可视化。我们现在有一个相关的元素 flex,它根据需要生成接触力、约束力和被动力,以模拟各种可变形实体。皮肤和 flex 现在都在 XML 中一个名为 deformable 的新分组元素中定义。Flex 是一个低级元素,它指定了运行时所需的一切,但在建模时难以设计。为了帮助建模,我们进一步引入了元素 flexcomp,它自动化了低级 flex 的创建,类似于 composite 如何自动化创建(集合)模拟软体所需的 MuJoCo 对象。Flexes 可能最终会取代复合材料,但目前两者对于有些不同的目的都很有用。
Flex 是通过无质量的可拉伸元素连接起来的 MuJoCo 物体(body)的集合。这些元素可以是胶囊(1D flex)、三角形(2D flex)或四面体(3D flex)。在所有情况下,我们都允许一个半径,这使得元素变得光滑,并且在 1D 和 2D 中具有体积。基本元素如下图所示:
到目前为止,这些看起来像 geoms。但关键的区别在于它们会变形:随着物体(顶点)彼此独立地移动,元素的形状实时变化。碰撞和接触力现在被推广以处理这些可变的几何元素。请注意,当两个这样的元素发生碰撞时,接触不再只涉及两个物体,而是可能涉及多达 8 个物体(如果两个元素都是四面体)。接触力像以前一样计算,给定接触帧和在该帧中表达的相关量。但随后接触力被分配到所有相互作用的物体中。接触雅可比(Jacobian)的概念很复杂,因为接触点不能被认为固定在任何物体帧中。相反,我们使用加权方案将每个接触点“分配”给多个物体。也可以通过将所有顶点分配给同一个物体来创建刚性 flex。这是一种重新利用新的 flex 碰撞机制来实现刚性非凸网格碰撞的方法(与为碰撞目的而凸化的网格 geoms 不同)。
变形模型 (Deformation model).
为了保持 flex 的形状(在软意义上),我们需要产生被动力或约束力。在 MuJoCo 3.0 之前,这将涉及大量的肌腱加上对肌腱和关节的约束。这在这里仍然是可能的,但当 flex 很大时,在建模和仿真方面效率低下。相反,设计理念是使用一组参数并提供两种建模选择:一种新的(软)等式约束类型,适用于给定 flex 的所有边,允许大的时间步长;或者一种离散化的连续体表示,其中每个元素处于恒定应力状态,这等价于分段线性有限元,并实现了改进的真实感和准确性。基于边的模型可以看作是一种“集总”刚度模型,其中变形模式(例如剪切和体积)的正确耦合在单个量中取平均。连续体模型则允许使用材料的 泊松比 分别指定剪切和体积刚度。更多细节,请参见 Saint Venant-Kirchhoff 超弹性模型。
创建和可视化 (Creation and visualization).
1<option timestep=".001"/>
2
3<worldbody>
4 <flexcomp type="grid" count="24 4 4" spacing=".1 .1 .1" pos=".1 0 1.5"
5 radius=".0" rgba="0 .7 .7 1" name="softbody" dim="3" mass="7">
6 <contact condim="3" solref="0.01 1" solimp=".95 .99 .0001" selfcollide="none"/>
7 <edge damping="1"/>
8 <elasticity poisson="0.2" young="5e4">
9 </flexcomp>
10</worldbody>
使用 flexcomp 元素,我们可以从网格(包括四面体网格)创建 flexes,并自动生成所有的物体/顶点,并用合适的元素连接它们。我们还可以自动创建网格和其他拓扑结构。这种机制使得创建非常大的 flexes 变得容易,涉及数千甚至数万个物体、元素和边。显然,这样的仿真不会快。即使对于中等大小的 flexes,碰撞对的修剪也是必不可少的。这就是为什么我们开发了复杂的方法来修剪自碰撞;参见 XML 参考。
对于由四面体组成的三维 flexes,检查 flex 在内部是如何“三角化”的可能很有用。我们有一个特殊的可视化模式,可以剥离外层。下面是一个斯坦福兔子的例子。请注意它的外部有较小的四面体,内部有较大的四面体。这种网格设计是有意义的,因为我们希望碰撞表面是精确的,但在内部我们只需要软材料属性——这需要较低的空间分辨率。为了将表面网格转换为四面体网格,我们推荐使用开源工具,如 fTetWild 库。
包含文件(Including files)#
MJCF 文件可以使用 include 元素包含其他 XML 文件。机制上,解析器用包含文件中顶级元素的子 XML 元素列表替换主文件中对应于 include 元素的 DOM 节点。顶级元素本身被丢弃,因为它是用于 XML 目的的分组元素,如果包含它会违反 MJCF 格式。
此功能支持模块化的 MJCF 模型;请参见模型库中的 MPL 系列模型。模块化的一个例子是构建一个机器人模型(往往很复杂),然后将其包含在多个“场景”中,即定义机器人环境中对象的 MJCF 模型。另一个例子是创建一个包含常用资源(例如具有精心调整的 rgba 值的材料)的文件,并将其包含在引用这些资源的多个模型中。
包含的文件本身不需要是有效的 MJCF 文件,但它们通常是。确实,我们设计了这个机制以允许 MJCF 模型被包含在其他 MJCF 模型中。为了实现这一点,允许重复的 MJCF 部分,即使这在单个模型的上下文中在语义上没有意义。例如,我们允许运动树有多个根(即多个 :el:`worldbody` 元素),它们由解析器自动合并。否则,将机器人包含到场景中将是不可能的。
重复的 MCJF 部分的灵活性是有代价的:适用于整个模型的全局设置,例如 compiler 的 :at:`angle` 属性,可以被定义多次。MuJoCo 允许这样做,并在处理完所有 include 元素后,使用在复合模型中遇到的最后一个定义。因此,如果模型 A 以度定义,模型 B 以弧度定义,并且 A 在 B 的 :el:`compiler` 元素之后被包含在 B 中,则整个复合模型将被视为以度定义——在这种情况下会导致不良后果。用户必须确保彼此包含的模型在这方面是兼容的;局部坐标与全局坐标是另一个兼容性要求。
最后,如下所述,元素名称在同类型的所有元素中必须是唯一的。因此,例如,如果在两个模型中使用了相同的 geom 名称,并且一个模型被包含在另一个模型中,这将导致编译错误。多次包含同一个 XML 文件是解析错误。此限制的原因是我们希望避免重复的元素名称以及由包含引起的无限递归。
命名元素(Naming elements)#
MJCF 中的大多数模型元素都可以有名称。它们使用相应 XML 元素的 :at:`name` 属性定义。当给定了模型元素名称时,其名称在同类型的所有元素中必须是唯一的。名称区分大小写。它们在编译时用于引用相应的元素,并且也保存在 mjModel 中,以供用户在运行时方便使用。
名称通常是一个可选属性。我们建议保持未定义(以使模型文件更短),除非有特定理由定义它。可能有几个这样的原因:
一些模型元素在创建时需要引用其他元素。例如,一个空间肌腱需要引用点位(sites)以指定它经过的路径点。引用只能通过名称完成。请注意,资源(assets)存在的唯一目的就是被引用,因此它们必须有一个名称,但是可以省略并隐式地从相应的文件名设置。
可视化器提供了标记给定类型的所有模型元素的选项。当名称可用时,它会被打印在 3D 视图中的对象旁边;否则会打印一个通用标签,格式为 “body 7”。
函数 mj_name2id 返回具有给定类型和名称的模型元素的索引。相反,函数 mj_id2name 返回给定索引的名称。这对于涉及在 XML 中通过名称标识的模型元素(与依赖于在模型编辑时可能更改的固定索引相反)的自定义计算非常有用。
原则上,通过命名某些元素可以使模型文件更具可读性。但请记住,XML 本身有一种注释机制,该机制更适合实现可读性——尤其是因为大多数文本编辑器提供检测 XML 注释的语法高亮。
URDF 扩展(URDF extensions)#
统一机器人描述格式(Unified Robot Description Format,URDF)是一种流行的 XML 文件格式,许多现有机器人已使用此格式进行建模。这就是我们即使 URDF 只能表示 MuJoCo 中可用模型元素的一个子集,也实现了对它的支持的原因。除了标准的 URDF 文件,MuJoCo 还可以加载在顶层元素 :el:`robot` 下包含自定义(从 URDF 的角度看):el:mujoco 元素作为子元素的文件。此自定义元素可以包含子元素 compiler、option、size,其功能与 MJCF 中相同,只是默认的编译器设置被修改以适应 URDF 的建模约定。特别是 compiler 扩展已被证明非常有用,实际上,它的几个属性是因为许多现有的 URDF 模型具有非物理的动力学参数,如果保持未修改状态,MuJoCo 的内置编译器将会拒绝这些参数。此扩展也需要用于指定网格目录。另请注意,编译器属性 strippath、angle、fusestatic 和 discardvisual 对于 URDF 和 MJCF 具有不同的默认值。
请注意,虽然 MJCF 模型在解析时会根据自定义 XML 模式进行检查,但 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 bodies)#
mocap 物体是世界的静态子物体(即没有关节),并且它们的 :at:`mocap` 属性设置为“true”。它们可用于将运动捕捉设备的数据流输入到 MuJoCo 仿真中。假设您持有一个 VR 控制器,或一个装有运动捕捉标记(例如 Vicon)的物体,并且希望有一个模拟物体以相同方式移动,同时也与其他模拟物体交互。这里存在一个难题:虚拟物体无法推动您的物理手,因此您的手(以及由此您控制的物体)可能违反模拟的物理规则。但同时我们希望产生的模拟是合理的。我们如何做到这一点?
第一步是在 MJCF 模型中定义一个 mocap 物体,并实现在运行时读取数据流并将 mjModel.mocap_pos 和 mjModel.mocap_quat 设置为从运动捕捉系统接收到的位置和方向的代码。simulate.cc 代码示例使用鼠标作为运动捕捉设备,允许用户移动 mocap 物体:
关于 mocap 物体的关键点在于,模拟器将它们视为固定的。我们通过直接更新它们的位置和方向使它们从一个模拟时间步移动到下一个时间步,但就物理模型而言,它们的位置和方向是恒定的。那么,如果我们与一个常规的动态物体发生接触,就像 MuJoCo 发行版中提供的粒子示例(回想一下,在这些示例中,我们有一个胶囊探针,它是一个我们用鼠标移动的 mocap 物体),会发生什么?两个常规物体之间的接触将经历穿透以及相对速度,而与 mocap 物体的接触则缺少相对速度分量,因为模拟器不知道 mocap 物体本身在移动。因此产生的接触力较小,并且需要更长时间接触才能将动态物体推开。此外,在更复杂的模拟中,我们做了一些与物理不一致的事情可能导致不稳定性。
然而,有一个行为更好的替代方案。除了 mocap 物体,我们还包括第二个常规物体,并使用焊接平等约束将其连接到 mocap 物体。在下图中,粉色盒子是 mocap 物体,它连接到手的底座。在没有其他约束的情况下,手几乎完美地跟踪 mocap 物体(比弹簧阻尼器好得多),因为约束是隐式处理的,并且可以产生大的力而不会使模拟不稳定。但是,如果手被迫与桌子接触(右图),它不能同时遵守接触约束和跟踪 mocap 物体。这是因为 mocap 物体可以自由地穿过桌子。那么哪个约束会胜出?这取决于焊接约束相对于接触约束的柔软度。需要调整相应的 :at:`solref` 和 :at:`solimp` 参数以实现所需的权衡。请参阅 MuJoCo 论坛上提供的模块化假肢(MPL)手模型示例;下图是用该模型生成的。
内存分配(Memory allocation)#
MuJoCo 在运行时在 mjData 中预分配所有需要的内存,并且在模型创建后不访问堆分配器。mjData 中的内存由 mj_makeData 在两个连续的内存块中分配:
mjData.buffer包含固定大小的数组。mjData.arena包含动态大小的数组。
有两种类型的动态数组分配在 arena 内存空间中。
接触和约束相关的数组从
arena的开头开始布局。stack 数组从
arena的末尾开始布局。
通过从 arena 空间的两端分配动态数量,可变大小的内存分配由单个数字控制:MJCF 元素 size 的 :at:`memory` 属性。与 buffer 中的固定大小数组不同,arena 中的可变大小数组可以是 NULL,例如在调用 mj_resetData 之后。
当 arena 内存耗尽时,根据请求的内存类型,会发生以下三种情况之一:
如果在接触分配期间内存耗尽,将引发警告,并且在此步骤中不会添加后续接触,但模拟照常继续。
如果在约束相关分配期间内存耗尽,将引发警告,并且在此步骤中约束求解器将被禁用,但模拟照常继续。请注意,没有约束求解器的物理通常会有很大不同,但允许模拟继续仍然有用,例如,在许多物体暂时重叠的场景初始化期间。
如果在堆栈数组分配期间内存耗尽,将发生硬错误。
与 buffer 的大小不同,arena 的大小无法预先计算,因为接触数量和堆栈使用量事先未知。那么应该如何选择它?当前使用以下简单的启发式方法(未来可能会改进):在最坏情况下,为 100 个接触和 500 个标量约束分配足够的内存。如果此启发式方法不足,我们推荐以下过程。使用 :at:`memory` 属性显著增加 arena 内存,并在运行时检查实际使用的内存。
mjData.maxuse_arena 会跟踪自上次重置以来的最大 arena 内存使用量。simulate 查看器将此数字显示为总 arena 空间的一部分(在左下角的信息窗口中)。因此,可以从一个较大的数字开始,模拟一段时间,如果比例很小,可以返回 XML 并减少分配大小。但请记住,内存利用率在模拟过程中可能会发生巨大变化,这取决于有多少约束处于活动状态以及使用哪个约束求解器。CG 求解器是内存效率最高的,其次是 Newton 求解器,而 PGS 求解器是内存密集度最高的。当我们设计模型时,我们通常目标是在探索模型时遇到的最坏情况下利用率为 50%。如果您只打算使用 CG 求解器,您可以使用明显更小的 arena 分配。
注意
内存分配行为在 MuJoCo 2.3.0 中发生了变化。在此版本之前,MJCF 元素 size 的属性 :at:`njmax`、:at:`nconmax` 和 :at:`nstack` 的语义分别是为接触、约束和堆栈分配的最大内存。如果您使用的是早期版本的 MuJoCo,请切换到 较早 的文档版本以阅读之前的行为。
提示与技巧(Tips and tricks)#
这里我们提供关于如何完成一些常见建模任务的指导。这里没有新的内容,因为本节中的所有内容都可以从文档的其余部分推断出来。然而,推断过程并不总是显而易见的,因此将其明确说明可能很有用。
性能调优(Performance tuning)#
以下是为了最大化模拟吞吐量可以采取的一系列步骤。所有建议都涉及参数调整。建议在查看 simulate 实用程序的内置分析器时以交互方式进行这些操作。testspeed 实用程序也会报告详细且有时更有用的分析。当进行下面更复杂的步骤时,以分析器报告的最昂贵的流水线组件为目标。请注意,其中一些对于 MJX 有细微的不同,请参阅 其中的专门章节。
Timestep:尝试增加模拟时间步长。如 Numerical Integration 部分末尾所述,时间步长是任何模型中最重要的参数。默认值是为了稳定性而非效率而选择的,通常可以增加。在某个点上,进一步增加它会导致发散,因此最佳时间步长是最大不会发生发散或发散非常罕见的时间步长。实际值取决于模型。
Integrator:根据 Numerical Integration 部分末尾的建议选择您的积分器。默认推荐的选择是
implicitfast积分器。Constraint Jacobians:尝试在“dense”和“sparse”之间切换 Jacobian 设置。这两个选项使用分别使用密集或稀疏代数的独立代码路径,但在其他方面计算相同,因此总是首选更快的那个。默认的“auto”启发式方法并不总是做出正确的选择。
约束求解器(Constraint solver):如果分析器报告求解器花费了大量时间,请考虑以下事项:
solver:默认的 Newton 通常是最快的求解器,因为它需要最少的迭代次数来收敛。对于大型模型,CG 求解器可能更快;对于自由度多于约束的模型,PGS 求解器将是最快的,尽管这种情况并不常见。
iterations 和 tolerance:尝试减少迭代次数,或等效地,增加求解器的终止容差。特别是对于 Newton 求解器,它通常在两到三次(昂贵的)迭代中实现数值收敛,最后一次迭代将精度提高到没有明显影响的水平,可以跳过。
碰撞(Collisions):如果分析器报告碰撞检测占用了大量计算时间,请考虑以下步骤:
使用 contype / conaffinity 机制减少检查的碰撞次数,如 Collison detection 部分所述。
修改碰撞几何体,用更便宜的原语-原语碰撞替换昂贵的碰撞测试(例如网格-网格)。根据经验,在 engine_collision_driver.c 顶部的碰撞表中具有自定义配对函数的碰撞明显比使用通用凸-凸碰撞器
mjc_Convex的碰撞便宜。最昂贵的碰撞是涉及 SDF 几何体的碰撞。如果不能用原语替换碰撞网格,则尽可能简化网格。像 trimesh、Blender、MeshLab 和 CoACD 这样的开源工具在这方面非常有用。
Friction cones:椭圆锥更准确,并且在具有高 impratio 时更能防止滑动,但更昂贵。如果精确的摩擦不重要,尝试切换到金字塔锥。
使用 32 位浮点精度(而不是默认的 64 位)编译 MuJoCo。对于以多线程模式运行的大型模型,其中内存访问比计算更昂贵,这可以带来(高达)2 倍的性能提升。有关更多信息,请参阅 mjtNum。
防止滑动(Preventing slip)#
以下是为了诊断和解决接触滑动(在操作任务中尤其成问题)可以采取的一系列步骤。为了诊断滑动,建议使用 simulate 实用程序的内置可视化选项来检查接触和接触力。通常有助于调整接触和力的视觉大小(使用全局 meansize 或特定的 contactwidth、contactheight 和 forcewidth 属性)以及 force scaling 属性,以更好地可视化和理解接触配置及产生的力。
- 防止滑动的接触力在摩擦锥之外
这意味着物理上无法防止滑动,即使原则上也是如此。当以下情况时会发生: a. 法向力太小。 确保夹持器可以施加的最大力乘以滑动摩擦系数显著大于物体的重量。 b. 滑动摩擦系数太低。 增加滑动 friction 系数。 c. 扭转摩擦不足以施加所需的扭矩。 将 condim 增加到 4 或 6 并选择适当的摩擦系数。
condim 4 启用扭转摩擦,防止绕法线旋转。 condim 6 还启用滚动摩擦,防止绕切向方向旋转。 有关详细信息以及这些系数的具体语义,请参阅 Contact 部分。
- 几何形状不支持所需的力或扭矩
这是一个常见的现实世界问题,通过改进夹持器和手柄的设计来解决。 a. 改进接触几何体的形状以增加更多的接触点,可能使用非平坦几何形状(例如凸起),使得滑动由法向力而不仅仅是摩擦分量来防止。 b. 如果接触是在平坦表面之间,尝试启用 multiccd 标志,它允许检测器找到比凸-凸碰撞器返回的单个接触更多的接触。 c. 尝试通过设置 nativeccd 标志来启用原生碰撞检测流水线,它使用更准确、更高效的凸碰撞检测算法。
- 高频振动
高频、低振幅的振动在许多工业环境中也是一个现实世界的问题,但与模拟不同,在现实世界中它们是可听见的。这种振动通常由具有非常高增益的控制器引起,有时也由来自接触或关节的粘滑反馈引起,与机构的特征模式共振。诊断这种振动的最简单方法是在 simulate 中可视化接触力。解决方案通常是减少 timestep 和/或向相关关节添加一些 armature。振动的另一个原因是显式阻尼的反馈。使用隐式或 implicitfast 积分器,如 Numerical Integration 部分所述。
- 缓慢滑动
与上述导致快速滑动的问题不同,缓慢、渐进的滑动是 MuJoCo 接触模型的设计特性,因为没有它,逆动力学就无法定义。这在 softness and slip 澄清中详细讨论。这种类型的滑动可以通过两种方式解决: a. 增加 impratio 参数。这将减少(但不能完全防止)缓慢滑动。请注意,高的 impratio 值仅与 elliptic cones 配合良好。 b. 通过将 noslip_iterations 增加到正整数来启用 noslip 求解器。通常一个较小的数字(1、2 或 3)就足够了。noslip 后处理求解器将完全防止滑动,代价是使逆动力学定义不明确以及额外的计算成本。
齿隙(Backlash)#
齿隙存在于许多机器人关节中。它通常是由齿轮箱中齿轮之间的微小间隙引起的,但也可能由关节机构中的某些松动引起。效果是电机可以在关节转动之前转动一个小角度,反之亦然(当外部力施加在关节上时)。齿隙可以在 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 中的 :at:`armature` 属性。没有它,关节空间惯性矩阵将是奇异的,因为两个关节可以在相反方向上加速而不会遇到任何惯性。导致齿隙的物理齿轮实际上具有旋转惯性(我们称之为 armature),因此这是一种现实的建模方法。应调整此示例中的数字以获得所需的行为。关节限制约束的 :at:`solref` 和 :at:`solimp` 参数也可以调整,以使齿隙旋转在更软或更硬的限制处结束。
可以在 J2 中指定保持 J2=0 的软平等约束,而不是指定关节限制。然后应调整约束阻抗函数,使得约束在 J2=0 附近较弱,并在远离 0 时变得更强。Solver parameters 中显示的阻抗函数的新参数化实现了这一点。与关节限制相比,平等约束方法将在齿隙状态和限制状态之间产生更柔和的过渡。它也将一直处于活动状态,这在需要约束违反或约束力作为输入的用户代码中很方便。
恢复系数(Restitution)#
如 Solver parameters 中所述,存在另一种指定 :at:`solref` 的机制。当两个数字都为非正数时,它们被解释为 (-stiffness, -damping) 并按约束阻抗进行缩放。为了实现接触和其他约束的完全弹性,将刚度设置为某个合理的大值,阻尼设置为零。下面是一个球体在平面上弹跳且恢复系数为 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>