MuJoCo 踩坑日志

最近在搞 MuJoCo 仿真环境,决定在此记录下踩下的坑。

抽搐的关节

在搭建 MuJoCo 仿真环境时发现添加关节后,它一直在抽搐,开始以为是摩擦、阻尼之类的没设好,问 copilot 也是建议去设置一下相关的参数。

Copilot 是这么说的:
你的 robot_r1 关节一直在旋转,可能是因为缺少摩擦力或阻尼,导致关节在仿真中无法稳定下来。你可以尝试增加关节的摩擦力或调整阻尼参数来解决这个问题 …

然而设置并调整了也没什么用。然后在 MuJoCo 的图形界面一番摸索后发现一些端倪。

MuJoCo Simulate 界面

如上图所示,我打开了 Convex Hull 选项,看到外面的框架的凸包,于是我开始怀疑是碰撞的问题,于是将抽搐的关节移出整个框架外,果然就不抽搐了。那接下来就是修改碰撞检测的问题了。

翻看文档,有这么两个参数:

contype: int, “1”
This attribute and the next specify 32-bit integer bitmasks used for contact filtering of dynamically generated contact pairs. See Collision detection in the Computation chapter. Two geoms can collide if the contype of one geom is compatible with the conaffinity of the other geom or vice versa. Compatible means that the two bitmasks have a common bit set to 1.

conaffinity: int, “1”
Bitmask for contact filtering; see contype above.

那么就把这个外框架的两个参数都设为 2 好了,其它的默认为 1 保持不变。

在 v3.2.5 版本时,如果都设为 0 的话就会闪退,不知道为什么。但是升级到 v3.3.0 版本后就不会了,所以按道理就是把这两个参数都设为零,就是不会检测碰撞了!

需要注意的是,这个参数是 bitmasks 的形式,也就是说设为 3(0b0011) 的话,也是会和默认的 1(ob0001) 发生碰撞的。

凸包问题

其实跟上面提到的问题类似,其它的一些需要较高精度的物体,MuJoCo 默认只能将它们处理为凸包来实现碰撞检测,这就导致一些物体很难直接得到真实的仿真效果,而最显而易见的就是轴孔装配(Peg-in-hole)的问题了。

官方文档的介绍:链接

不妙的是,我正正是需要仿真一个类似轴孔装配的情况。如这篇讨论所述,要处理这个问题,目前只能去做一个凸包分解的工作,而好消息是,有现成的算法和工具去做这个事情。

正如帖子中提到的,有一个叫做 obj2mjcf 的工具可以自动将 obj 文件分解成多个凸包,并生成对应的 mjcf xml 文件。那么现在的问题就变成了,我要怎么从 solidworks 模型得到 obj 格式的文件了。 解决方法也很简单,就是整个 Blender 软件,导入 stl,导出 obj,结束。就是这么简单而又粗暴。

具体的使用就不赘述了,不过就是有个小坑。不知道为什么有时用 Blender 导出的 obj 文件,在 obj2mjcf 处理的时候会报错,如下:

Traceback (most recent call last):
  File "D:\Program Files\python3\lib\runpy.py", line 196, in _run_module_as_main
    return _run_code(code, main_globals, None,
  File "D:\Program Files\python3\lib\runpy.py", line 86, in _run_code
    exec(code, run_globals)
  File "D:\Program Files\python3\Scripts\obj2mjcf.exe\__main__.py", line 7, in <module>
  File "D:\Program Files\python3\lib\site-packages\obj2mjcf\cli.py", line 280, in main
    process_obj(obj_file, args)
  File "D:\Program Files\python3\lib\site-packages\obj2mjcf\cli.py", line 138, in process_obj
    for line in f.readlines():
UnicodeDecodeError: 'gbk' codec can't decode byte 0xb9 in position 64: illegal multibyte sequence

不过按下面的配置导出,且不保存 Blender 文件的话,就可以正常运行,可以稍微参考一下:

导出 obj 配置项

微小零件的穿模问题

继续添加一个自由的物体,发现它并没有按预期地被另一个固定的物体兜住,就像是直接穿模了一般掉到了地上。这真是太怪了。

最后发现是 timestep 设太高了,而且初始位置太高,导致加速度有点大,托不住。(后来发现并不是这个问题,而是需要设置 solimp 和 solref 的参数)

为了解决这个问题,需要去设置 MuJoCo 的 Solver Parameters 这些参数决定了 MuJoCo 仿真器的接触约束行为。

在 MuJoCo 中,约束空间的动力学可以近似为下面的形式:

$$a_1 + d (bv+kr) = (1-d) a_0$$

将上式移一下项,意义会更清晰:

$$a_1 = (1-d) \cdot a_0 + d \cdot (-bv-kr)= (1-d) \cdot a_0 + d \cdot a_{ref}$$

其中,$k$ 为刚度(stiffness), $b$ 为阻尼系数(damping), $d$ 为阻抗系数(Impedance)。 $a_1$ 为末状态加速度,$a_0$ 为原加速度,$a_{ref}$ 为参考加速度。$v$ 为速度,$r$ 为渗透深度。 上式也就是说约束状态下的加速度等于无约束状态下的加速度与参考加速度的加权平均。

而 Sover parameters 的设置由两部分组成——Impedance 和 Reference,分别对应着 $(k,b)$ 和 $d$ 的行为。

Impedance

Impdance 对应着 mjcf 文件中 geom 的 solimp 属性。格式为:

<geom solimp="0.9 0.05 0.001 0.5 2">

五个参数分别对应 $d_0, d_{\mathrm{width}}, \mathrm{width}, \mathrm{midpoint}, \mathrm{power}$

这五个参数共同定义了 d 关于 r 的函数:

$$d(0) = d_0, \quad d(\mathrm{width}) = d_{\mathrm{width}}$$

函数图像与各参数的关系示意如下:

不同参数下的d(r)函数图像

而关于 d 对接触行为的影响,官方的说法是对应着约束产生力的能力(ability to generate force)。简单来说,d 越大,约束能力越强。举两个极端的例子,若 $d=0$ 的话,则表现为没有约束,$a_1 \equiv a_0$; 而如果 $d=1$ 的话,$a_1 \equiv a_{ref}$,即接触行为只跟相对位置速度关系有关,加速度的变化在一瞬间完成。

然而上面仅仅是举例,事实上,MuJoCo 中 d 的取值范围是 $[0.0001, 0.9999]$

Reference

Reference 指的是 reference acceleration ($a_{ref}$),这部分控制参考加速度。 它决定了约束试图实现的动作(motion that constraint is trying to achieve)。

它的设置通过 solref 参数进行:

<geom solref="0.02 1">
<geom solref="-10 -1">

值得注意的是,这个参数的设置有两种形式,若设置的两个值为正数,则分别代表着时间常数(timeconst)和阻尼比(damp ratio); 若两个值为负数,则其绝对值代表刚度(stiffness)和阻尼(damping)。

若设置时间常数和阻尼比的话,会在一定的缩放操作后按照质量-弹簧-阻尼器模型来计算出 k 和 b 的值,如下:

$$b = 2 / (d_{\mathrm{width}} \cdot timeconst)$$ $$k = d(r) / (d_{\mathrm{width}}^2 \cdot timeconst^2 \cdot dampratio^2)$$

需要注意,时间常数的值需要至少为模拟器的 timestep 参数的两倍大,否则系统可能会变得过于僵硬。 而阻尼比的话一般设为 1,对应着临界阻尼。而小于 1 对应欠阻尼。大于 1 对应过阻尼。

什么是临界阻尼、欠阻尼和过阻尼可自行搜索或参考百科

最重要的一点来了,也是解决本节提出问题的关键。因为约束状态下的加速度等于原加速度(无约束状态下的加速度)与参考加速度的加权平均, 而这两个加速度一般是反向的,那么两个准静态接触的物体总会平衡在某个渗透深度下,而这个深度可以推导出来,其结果为:

$$r = a_0 \cdot (1 - d) \cdot timeconst^2 \cdot dampratio^2$$

而如果这个平衡渗透深度比物体的厚度还要大,那么就势必会穿模啦! 我的解决方法在下面总结处阐述,现在把这节收尾先。

正如上面提到的,除了设置时间常数和阻尼比外,还可以直接设置刚度和阻尼,但其实也会做一个缩放操作,如下:

$$b = damping / d_{width}$$

$$k = stiffness \cdot d(r) / d_{width}^2$$

而渗透深度如下:

$$r = \frac{a_0 (1-d)}{stiffness}$$

总结

那么知道原因后,解决方法也很明显了,通过改变各个参数,令 r 的值远小于物体的厚度即可。 我的做法是设置 solimp 的前两个参数为一样的,令 d 为常数。然后保持 dampratio 为 1, 将零件最小厚度的 1/10 代入 r 中,即可算出 timeconst 的值了。然后验证一下,是否大于 timestep 的两倍, 如果不是,则需要减小 timestep 的值了。

<geom friction="1 0.005 0.01" solimp="0.99 0.99 0.001 0.1 2" solref="0.0014 1" priority="1"/>

这里还有一点需要注意的是优先级的问题,即上面的 priority 属性。接触的两个物体优先级不一样,那么就会采用高者数据设置; 而如果优先级一样则会计算一次加权平均,权重由 solmix 参数决定。(见这里

步进电机

参考这个帖子:https://github.com/google-deepmind/mujoco/issues/175

一个 Collaborator 给出了解决方案:

You don’t need the callbacks. Just use a high gain position actuator on a joint with enough damping.

也就是说使用一个高 kp 和足够 kv 的一个位置定位 shortcut :

<position name="stepper" joint="slider" kp="100" kv="100" inheritrange="0.8" />

后续

这篇文章可能持续更新,敬请期待。

感觉 MuJoCo 的中文教程/资料好少啊,而且官方文档写得有点太详细了。其实有点想法写一个简明入门指南,不过,再说吧。


MuJoCo 踩坑日志
https://worranhin.github.io/2025/03/04/mujoco/
作者
Hin
发布于
2025年3月4日
许可协议