仿真#

初始化#

版本检查之后,下一步是分配并初始化仿真所需的主要数据结构,即 mjModel 和 mjData。与可视化和回调相关的其他初始化步骤将在稍后讨论。

mjModel 和 mjData 绝对不应由用户直接分配。相反,它们由相应的 API 函数分配和初始化。这些是非常精细的数据结构,包含其他结构(或其数组)、为所有中间结果预分配的数据数组,以及一个内部堆栈。我们的策略是在仿真开始时分配所有必要的堆内存,并在仿真结束后释放它,这样在仿真期间我们就不必调用 C 语言的内存分配和释放函数。这样做是为了提高速度、避免内存碎片化、未来 GPU 的可移植性以及在重置期间轻松管理整个模拟器的状态。然而,这也意味着由 size MJCF 元素中的 memory 属性给出的最大可变内存分配(它影响 mjData 的分配)必须设置得足够大。如果在仿真期间超出了这个最大大小,它不会动态增加,而是会生成一个错误。另请参见下面的诊断

首先,我们必须调用一个分配并初始化 mjModel 并返回其指针的函数。可用选项有:

// option 1: parse and compile XML from file
mjModel* m = mj_loadXML("mymodel.xml", NULL, errstr, errstr_sz);

// option 2: parse and compile XML from virtual file system
mjModel* m = mj_loadXML("mymodel.xml", vfs, errstr, errstr_sz);

// option 3: load precompiled model from MJB file
mjModel* m = mj_loadModel("mymodel.mjb", NULL);

// option 4: load precompiled model from virtual file system
mjModel* m = mj_loadModel("mymodel.mjb", vfs);

// option 5: deep copy from existing mjModel
mjModel* m = mj_copyModel(NULL, mexisting);

如果出现错误或警告,所有这些函数都返回 NULL 指针。在 XML 解析和模型编译的情况下,错误的描述会在作为参数提供的字符串中返回。对于其余的函数,会调用低级的 mju_errormju_warning 并附带错误/警告消息;请参见错误处理。一旦我们获得了由上述函数之一分配的 mjModel 的指针,我们就会将其作为参数传递给所有需要访问模型的 API 函数。请注意,大多数函数将此指针视为 const;更多相关内容请参见下面的模型更改

虚拟文件系统(VFS)允许磁盘资源加载到内存中或由用户以编程方式创建,然后 MuJoCo 的加载函数在访问磁盘之前会在 VFS 中搜索文件。请参见 API 参考章节中的虚拟文件系统

除了保存模型描述的 mjModel 外,我们还需要 mjData,这是执行所有计算的工作空间。请注意,mjData 是特定于某个 mjModel 的。API 函数通常假设用户知道他们在做什么,并进行最少的参数检查。如果传递给任何 API 函数的 mjModel 和 mjData 不兼容(或为 NULL),产生的行为将是不可预测的。mjData 的创建方式如下:

// option 1: create mjData corresponding to given mjModel
mjData* d = mj_makeData(m);

// option 2: deep copy from existing mjData
mjData* d = mj_copyData(NULL, m, dexisting);

一旦 mjModel 和 mjData 都被分配和初始化,我们就可以调用各种仿真函数。完成后,我们可以用以下函数删除它们:

// deallocate existing mjModel
mj_deleteModel(m);

// deallocate existing mjData
mj_deleteData(d);

代码示例展示了完整的初始化和终止序列。

MuJoCo 仿真是确定性的,只有一个例外:当启用传感器噪声功能时,会生成传感器噪声。这是通过内部调用 C 函数 rand() 来完成的。要生成相同的随机数序列,请在加载模型后和仿真开始前,使用所需的种子调用 srand()。模型编译器内部会调用 srand(123),以便为程序化纹理生成随机点。因此,如果程序化纹理的规范发生变化,并且用户在模型编译后没有调用 srand(),传感器数据中的噪声序列将会改变。

仿真循环#

在 MuJoCo 中有多种方式来运行仿真循环。最简单的方法是在一个循环中调用顶层仿真函数 mj_step,例如:

// simulate until t = 10 seconds
while (d->time < 10)
  mj_step(m, d);

这本身会模拟被动动力学,因为我们没有提供任何控制信号或施加力。控制系统的默认(也是推荐的)方法是实现一个控制回调,例如:

// simple controller applying damping to each DOF
void mycontroller(const mjModel* m, mjData* d) {
  if (m->nu == m->nv)
    mju_scl(d->ctrl, d->qvel, -0.1, m->nv);
}

这说明了两个概念。首先,我们正在检查控制量 mjModel.nu 是否等于自由度数量 mjModel.nv。通常,同一个回调可能用于多个模型,这取决于用户代码的结构,因此在回调中检查模型维度是个好主意。其次,MuJoCo 有一个类似 BLAS 的函数库,非常有用;实际上,代码库的很大一部分就是内部调用这些函数。上面的 mju_scl 函数将速度向量 mjData.qvel 乘以一个恒定的反馈增益,并将结果复制到控制向量 mjData.ctrl 中。要安装这个回调,我们只需将其分配给全局控制回调指针 mjcb_control

// install control callback
mjcb_control = mycontroller;

现在,如果我们调用 mj_step,我们的控制回调将在仿真流程需要控制信号时被执行,结果我们将最终模拟受控动力学(尽管阻尼并不能真正体现控制的概念,最好作为被动关节属性来实现,但这些都是更细微的点)。

除了依赖控制回调,我们也可以直接设置控制向量 mjData.ctrl。或者,我们可以像状态和控制中解释的那样设置施加的力。如果我们可以先于 mj_step 调用之前计算这些与控制相关的量,那么受控动力学(不使用控制回调)的仿真循环将变成:

while (d->time < 10) {
  // set d->ctrl or d->qfrc_applied or d->xfrc_applied
  mj_step(m, d);
}

为什么我们不能在调用 mj_step 之前计算控制量呢?毕竟,这不就是因果关系的含义吗?答案是微妙但重要的,与我们是在离散时间进行仿真有关。顶层仿真函数 mj_step 基本上做两件事:计算连续时间内的正向动力学,然后在一个由 mjModel.opt.timestep 指定的时间段内进行积分。正向动力学计算在时间 mjData.time 时的加速度 mjData.qacc,给定时间 mjData.time 时的状态和控制。然后,数值积分器将状态和时间推进到 mjData.time + mjModel.opt.timestep。现在,控制需要是时间 mjData.time 状态的函数。然而,一个通用的反馈控制器可能是一个非常复杂的函数,取决于状态的各种特征——特别是 MuJoCo 作为仿真中间结果计算的所有特征。这些可能包括接触、雅可比矩阵、被动力。在调用 mj_step 之前,这些量都是不可用的(或者说,它们可用,但是比当前时间步过时了一个时间步)。相反,当 mj_step 调用我们的控制回调时,它尽可能晚地进行——即在所有依赖于状态但不依赖于控制的中间结果都计算完毕之后。

不使用控制回调也可以达到同样的效果。这是通过将 mj_step 分成两部分来实现的:需要控制之前的部分和需要控制之后的部分。仿真循环现在变为:

while (d->time < 10) {
  mj_step1(m, d);
  // set d->ctrl or d->qfrc_applied or d->xfrc_applied
  mj_step2(m, d);
}

然而,有一个复杂之处:这只适用于欧拉积分。龙格-库塔积分器(以及我们计划实现的其他高级积分器)需要在每一步中多次评估整个动力学,包括反馈控制律,这只能通过控制回调来完成。但是对于欧拉积分,将 mj_step 分成 mj_step1mj_step2 足以为控制律提供计算的中间结果。

为了使上述讨论更清晰,我们提供了 mj_step、mj_step1 和 mj_step2 的内部实现,省略了一些计算计时诊断的代码。主要的仿真函数是:

void mj_step(const mjModel* m, mjData* d) {
  // common to all integrators
  mj_checkPos(m, d);
  mj_checkVel(m, d);
  mj_forward(m, d);
  mj_checkAcc(m, d);

  // compare forward and inverse solutions if enabled
  if (mjENABLED(mjENBL_FWDINV))
    mj_compareFwdInv(m, d);

  // use selected integrator
  if (m->opt.integrator == mjINT_RK4)
    mj_RungeKutta(m, d, 4);
  else
    mj_Euler(m, d);
}

检查函数会在任何数值变得无效或过大时自动重置仿真。控制回调(如果有的话)在正向动力学函数内部被调用。

接下来我们展示两步法(two-part stepping)的实现,尽管只有在我们稍后解释了正向动力学后,具体细节才能完全理解。请注意,控制回调现在是直接调用的,因为我们实质上已经解构了正向动力学函数。还请注意,无论 mjModel.opt.integrator 的设置如何,我们在 mj_step2 中总是调用欧拉积分器。

void mj_step1(const mjModel* m, mjData* d) {
  mj_checkPos(m, d);
  mj_checkVel(m, d);
  mj_fwdPosition(m, d);
  mj_sensorPos(m, d);
  mj_energyPos(m, d);
  mj_fwdVelocity(m, d);
  mj_sensorVel(m, d);
  mj_energyVel(m, d);

  // if we had a callback we would be using mj_step, but call it anyway
  if (mjcb_control)
    mjcb_control(m, d);
}

void mj_step2(const mjModel* m, mjData* d) {
  mj_fwdActuation(m, d);
  mj_fwdAcceleration(m, d);
  mj_fwdConstraint(m, d);
  mj_sensorAcc(m, d);
  mj_checkAcc(m, d);

  // compare forward and inverse solutions if enabled
  if (mjENABLED(mjENBL_FWDINV))
    mj_compareFwdInv(m, d);

  // integrate with Euler; ignore integrator option
  mj_Euler(m, d);
}

状态和控制#

MuJoCo 有一个定义明确的状态,可以轻松地设置、重置和随时间推进。这与动力学系统的状态概念密切相关。动力学系统通常用以下一般形式描述:

dx/dt = f(t, x, u)

其中 t 是时间,x 是状态向量,u 是控制向量,f 是计算状态时间导数的函数。这是一个连续时间的公式,实际上 MuJoCo 模拟的物理模型也是在连续时间内定义的。尽管数值积分器在离散时间内运行,但计算的主要部分——即函数 mj_forward——对应于上述连续时间动力学函数 f(t,x,u)。这里我们解释这种对应关系。

MuJoCo 中的状态向量是:

x = (mjData.time, mjData.qpos, mjData.qvel, mjData.act)

对于一个二阶动力学系统,状态只包含位置和速度,但 MuJoCo 也可以模拟具有自身激活状态的致动器(如气缸和生物肌肉),这些状态被组装在向量 mjData.act 中。虽然物理模型是时不变的,但用户定义的控制律可以是时变的;特别是,从轨迹优化器获得的控制律通常会由 mjData.time 来索引。

上面使用“官方”这个词的原因是,用户回调可能会存储随时间变化并影响回调输出的额外状态变量;实际上,字段 mjData.userdata 的存在主要就是为了这个目的。其他类似状态的量,作为 mjData 的一部分并被正向动力学视为输入的是 mjData.mocap_posmjData.mocap_quat。这些量不寻常之处在于,它们本应在每个时间步都发生变化(通常由运动捕捉设备驱动),然而这种变化是由用户实现的,而模拟器将它们视为常量。从这个意义上说,它们与 mjModel 中的所有常量或用户设置的函数回调指针没有什么不同:这些常量会影响计算,但不是动力学系统状态向量的一部分。

约束求解器中的热启动机制实际上引入了另一个状态变量。该机制使用前一个时间步正向动力学的输出,即加速度向量 mjData.qacc,通过逆向动力学来估计当前的约束力。然后,这个估计值会初始化求解器中的优化算法。如果该算法运行到收敛,热启动将影响收敛速度,但不会影响最终解(因为底层的优化问题是凸的,没有局部最小值),但实际上该算法通常会提前终止,因此热启动对解有一定(通常非常小)的影响。

接下来我们来看控制和施加的力。MuJoCo 中的控制向量是:

u = (mjData.ctrl, mjData.qfrc_applied, mjData.xfrc_applied)

这些量指定了模型中定义的致动器的控制信号(mjData.ctrl),或者直接施加在关节空间(mjData.qfrc_applied)或笛卡尔空间(mjData.xfrc_applied)中指定的力和扭矩。

最后,调用对应于抽象动力学函数 f(t,x,u) 的 mj_forward,计算状态向量的时间导数。mjData 中对应的字段是:

dx/dt = f(t,x,u) = (1, mjData.qvel, mjData.qacc, mjData.act_dot)

当存在四元数时(即,当使用自由关节或球关节时),位置向量 mjData.qpos 的维度高于速度向量 mjData.qvel,因此这不仅仅是标量意义上的简单时间导数,而是考虑了四元数代数。

为了说明如何操作仿真状态,假设我们有两个对应相同 mjModel 的 mjData 指针 src 和 dst,我们想将整个仿真状态从一个复制到另一个(省略不影响仿真的内部诊断信息)。这可以这样做:

// copy simulation state
dst->time = src->time;
mju_copy(dst->qpos, src->qpos, m->nq);
mju_copy(dst->qvel, src->qvel, m->nv);
mju_copy(dst->act,  src->act,  m->na);

// copy mocap body pose and userdata
mju_copy(dst->mocap_pos,  src->mocap_pos,  3*m->nmocap);
mju_copy(dst->mocap_quat, src->mocap_quat, 4*m->nmocap);
mju_copy(dst->userdata,   src->userdata,   m->nuserdata);

// copy warm-start acceleration
mju_copy(dst->qacc_warmstart, src->qacc_warmstart, m->nv);

现在,假设控制也相同(见下文),并且任何已安装的回调不依赖于 src 和 dst 之间不同的用户定义状态变量,那么调用 mj_forward(m, src) 或 mj_step(m, src) 会得到与调用 mj_forward(m, dst) 或 mj_step(m, dst) 相同的结果。类似地,调用 mj_inverse(m, src) 会得到与调用 mj_inverse(m, dst) 相同的结果。关于逆向动力学的更多信息将在稍后介绍。

整个 mjData 也可以用函数 mj_copyData 复制。这涉及的代码更少,但速度慢得多。实际上,使用上述代码复制状态然后调用 mj_forward 重新计算所有内容,有时可能比复制 mjData 更快。这是因为 mjData 中预分配的缓冲区足够大,可以容纳所有可能约束都激活的最坏情况下的中间结果,但实际上,通常只有一小部分约束会同时激活。

为了说明如何操作控制向量,假设我们想在调用 mj_step 之前清除所有控制和施加的力,以确保我们正在模拟被动动力学(当然,假设没有控制回调)。这可以这样做:

// clear controls and applied forces
mju_zero(dst->ctrl, m->nu);
mju_zero(dst->qfrc_applied, m->nv);
mju_zero(dst->xfrc_applied, 6*m->nbody);

如果用户安装了一个不同于默认回调(即 NULL 指针)的控制回调 mjcb_control,那么用户回调应将上述某些字段设置为非零。请注意,MuJoCo 在时间步结束时不会清除这些控制/力。这是用户的责任。

在这种情况下,函数 mj_resetData 也相关。它将 mjData.qpos 设置为模型的参考配置 mjModel.qpos0,将 mjData.mocap_posmjData.mocap_quat 设置为 mjModel 中相应的固定物体位姿;并将所有其他状态和控制变量设置为 0。

正向动力学#

正向动力学的目标是计算状态的时间导数,即加速度向量 mjData.qacc 和激活时间导数 mjData.act_dot。在此过程中,它会计算模拟动力学所需的所有其他内容,包括活动接触和其他约束、关节空间惯性及其 LTDL 分解、约束力、传感器数据等。所有这些中间结果都可在 mjData 中获得,并可用于自定义计算。如上面的仿真循环部分所示,主步进函数 mj_step 调用 mj_forward 来完成大部分工作,然后调用数值积分器将仿真状态推进到下一个离散时间点。

正向动力学函数 mj_forward 内部调用 mj_forwardSkip,并带有跳过参数 (mjSTAGE_NONE, 0),后者函数的实现如下:

void mj_forwardSkip(const mjModel* m, mjData* d, int skipstage, int skipsensor) {
  // position-dependent
  if (skipstage < mjSTAGE_POS) {
    mj_fwdPosition(m, d);
    if (!skipsensor)
      mj_sensorPos(m, d);
    if (mjENABLED(mjENBL_ENERGY))
      mj_energyPos(m, d);
  }

  // velocity-dependent
  if (skipstage < mjSTAGE_VEL) {
    mj_fwdVelocity(m, d);
    if (!skipsensor)
      mj_sensorVel(m, d);
    if (mjENABLED(mjENBL_ENERGY))
      mj_energyVel(m, d);
  }

  // acceleration-dependent
  if (mjcb_control)
    mjcb_control(m, d);
  mj_fwdActuation(m, d);
  mj_fwdAcceleration(m, d);
  mj_fwdConstraint(m, d);
  if (!skipsensor)
    mj_sensorAcc(m, d);
}

请注意,这与上面 mj_step1 和 mj_step2 中的调用序列相同,只是省略了对实数值的检查以及传感器和能量等特征的计算。被调用的函数是仿真流程的组件。它们又会调用子组件。

整数参数 skipstage 决定了将跳过哪些计算部分。可能的跳过级别有:

mjSTAGE_NONE

不跳过任何内容。运行所有计算。

mjSTAGE_POS

跳过依赖于位置但不依赖于速度、控制或施加的力的计算。这类计算的例子包括正向运动学、碰撞检测、惯性矩阵计算和分解。这些计算通常占用最多的 CPU 时间,应尽可能跳过(见下文)。

mjSTAGE_VEL

跳过依赖于位置和速度但不依赖于控制或施加的力的计算。例子包括计算科里奥利力和离心力、被动阻尼力、用于约束稳定的参考加速度。

mjData 的中间结果字段根据计算它们所需的状态部分进行组织。使用 mjSTAGE_POS 调用 mj_forwardSkip 假定第一部分(位置相关)的字段已经计算过,并且不会重新计算它们。类似地,mjSTAGE_VEL 假定第一和第二部分(位置和速度相关)的字段已经计算过。

我们什么时候可以使用上述机制并跳过一些计算呢?在常规仿真中,这是不可能的。然而,MuJoCo 不仅为仿真设计,也为更高级的应用设计,如基于模型的优化、机器学习等。在这种情况下,人们常常需要在一系列附近状态上对动力学进行采样,或者通过有限差分来近似导数——这是另一种形式的采样。如果样本排列在网格上,其中只有位置、只有速度或只有控制与中心点不同,那么上述机制可以将性能提高约 2 倍。

逆向动力学#

逆向动力学的计算是 MuJoCo 的一个独特功能,在任何其他能够模拟接触的现代引擎中都找不到。逆向动力学定义明确,并且由于我们在概述章节中描述的软约束模型,计算非常高效。事实上,一旦完成了与正向动力学共享的、依赖于位置和速度的计算,给定加速度来恢复约束力和施加的力就归结为一个解析公式。这非常快,以至于我们实际上使用逆向动力学(使用前一个时间步计算的加速度)来热启动正向动力学中的迭代约束求解器。

逆向动力学的输入与正向动力学中的状态向量相同,如状态和控制中所示,但没有 mjData.actmjData.time。假设没有依赖于用户定义状态变量的回调,逆向动力学的输入是 mjData 的以下字段:

(mjData.qpos, mjData.qvel, mjData.qacc, mjData.mocap_pos, mjData.mocap_quat)

主要输出是 mjData.qfrc_inverse。这是为了达到观测到的加速度 mjData.qacc 而必须作用于系统的力。如果正向动力学被精确计算,即通过将迭代求解器运行到完全收敛,我们将有:

mjData.qfrc_inverse = mjData.qfrc_applied + Jacobian'*mjData.xfrc_applied + mjData.qfrc_actuator

其中 mjData.qfrc_actuator 是由致动器产生的关节空间力,而雅可比矩阵是从关节空间到笛卡尔空间的映射。当 mjModel.opt.enableflags 中的“fwdinv”标志被设置时,上述恒等式用于监控正向动力学解的质量。具体来说,mjData.solver_fwdinv 的两个分量被设置为正向和逆向解之间差异的 L2 范数,分别以关节力和约束力表示。

与正向动力学类似,mj_inverse 内部调用 mj_inverseSkip,并带有跳过参数 (mjSTAGE_NONE, 0)。跳过机制与正向动力学中的相同,可用于加速结构化采样。结果 mjData.qfrc_inverse 是通过使用递归牛顿-欧拉算法计算作用于系统的净力,然后从中减去所有内力得到的。

当有实验数据可用时,逆向动力学可以作为一种分析工具。这在机器人学和生物力学中很常见。它也可以用来计算驱动系统沿给定参考轨迹运动所需的关节扭矩;这被称为计算扭矩控制。在状态估计、系统辨识和最优控制的背景下,它可以在优化循环中使用,以找到最小化物理违规以及其他成本的状态序列。物理违规可以通过逆向动力学计算出的任何无法解释的外部力的范数来量化。

多线程#

当 MuJoCo 用于仿真循环部分所述的仿真时,它在单线程中运行。我们已经尝试过对仿真流程中计算量大且适合并行处理的部分进行多线程化,并得出结论,速度提升不值得占用额外的处理器核心。这是因为 MuJoCo 已经很快了,与在同一时间步内启动和同步多个线程的开销相比,提升不大。如果用户开始处理涉及许多浮动体的大型仿真,我们最终可能会实现步内多线程,但目前这种用例并不常见。

我们倾向于使用多线程来加速在更高级应用中常见的采样操作,而不是加速单个仿真。仿真在时间上是内在串行的(一个 mj_step 的输出是下一个的输入),而在采样中,许多对正向或逆向动力学的调用可以并行执行,因为它们之间没有依赖关系,除了可能有一个共同的初始状态。

MuJoCo 从一开始就为多线程设计。与大多数现有模拟器不同,在这些模拟器中,动力学系统状态的概念很难映射到软件状态,并且通常分布在多个对象中,而在 MuJoCo 中,我们有统一的数据结构 mjData,它包含了所有随时间变化的东西。回想一下状态和控制的讨论。关键思想是为每个线程创建一个 mjData,然后将其用于所有线程内的计算。下面是通用模板,使用 OpenMP 来简化线程管理。

// prepare OpenMP
int nthread = omp_get_num_procs();      // get number of logical cores
omp_set_dynamic(0);                     // disable dynamic scheduling
omp_set_num_threads(nthread);           // number of threads = number of logical cores

// allocate per-thread mjData
mjData* d[64];
for (int n=0; n < nthread; n++)
  d[n] = mj_makeData(m);

// ... serial code, perhaps using its own mjData* dmain

// parallel section
#pragma omp parallel
{
  int n = omp_get_thread_num();       // thread-private variable with thread id (0 to nthread-1)

  // ... initialize d[n] from results in serial code

  // thread function
  worker(m, d[n]);                    // shared mjModel (read-only), per-thread mjData (read-write)
}

// delete per-thread mjData
for (int n=0; n < nthread; n++)
  mj_deleteData(d[n]);

由于所有顶层 API 函数都将 mjModel 视为 const,这种多线程方案是安全的。每个线程只写入自己的 mjData。因此,线程之间不需要进一步的同步。

上述模板反映了一种特定风格的并行处理。我们不是为每个工作项创建一个大量的线程,然后让 OpenMP 将它们分配到处理器上,而是依赖于手动调度。更确切地说,我们创建的线程数量与处理器数量相同,然后在 worker 函数中显式地将工作分配给各个线程。这种方法更有效,因为与处理器缓存相比,线程特定的 mjData 很大。

我们还使用一个共享的 mjModel 以提高缓存效率。在某些情况下,可能无法为所有线程使用同一个 mjModel。一个明显的原因是 mjModel 可能需要在线程函数内部被修改。另一个原因是 mjOption 结构(包含在 mjModel 中)可能需要调整(例如,为了控制求解器迭代次数),尽管这很可能对所有并行线程都是相同的,因此可以在并行部分之前在共享模型中进行调整。

线程特定的 mjData 如何初始化以及线程函数做什么当然是依赖于应用的。尽管如此,前面章节的一般效率准则在这里同样适用。将状态复制到线程特定的 mjData 中并运行 MuJoCo 来填充其余部分,可能比使用 mj_copyData 更快。此外,正向和逆向动力学中可用的跳过机制在并行采样应用中特别有用,因为样本通常具有结构,允许一些计算被重用。最后,请记住,正向求解器是迭代的,良好的热启动可以显著减少必要的迭代次数。当样本在状态和控制空间中彼此接近时,一个样本(理想情况下是中心的那个)的解可以用来热启动所有其他样本。在这种情况下,重要的是要确保附近样本之间的不同结果反映了样本之间的真实差异,而不是迭代求解器的不同热启动或终止条件。

mjModel 更改#

使用 mjSpec 进行程序化模型编辑

下面关于 mjModel 修改的讨论是在引入程序化模型编辑之前编写的。它仍然有效,但新的框架是修改模型的安全且推荐的方式。在运行时修改 mjModel 而不是修改 mjSpec 并重新编译的主要原因是速度。然而,进行某些更改可能不安全,可能导致段错误,或者物理行为会发生意外改变。

一般规则是,实数值参数可以安全更改,而结构性整数参数则不行,因为这可能导致不正确的大小或索引。这个规则并非普遍适用,下面我们描述例外情况。

整数类型不安全更改的一般规则的例外情况

字段

可修改性

注释

XXX_limited
XXX_group
XXX_matid
XXX_texid

安全

XXX_sameframe

不安全

此标志告诉引擎跳过父/子坐标系变换。从非零改为零是安全的,但反之则不然。

geom_contype
geom_conaffinity

不安全

如果父物体的 body_contypebody_conaffinity 被更新为所有子几何体的按位或运算结果,那么这样做是安全的。

geom_condim
geom_priority

安全

cam_resolution

安全

light_castshadow
light_active

安全

flex_contype
flex_conaffinity
flex_condim
flex_priority

安全

tex_data

安全

必须调用 mjr_uploadTexture 来更新 GPU 内存中的值。

在考虑实数值参数可以安全更改的规则的例外情况时,我们需要注意函数 mj_setConst,它构成了编译过程的最后一步。此函数将某些字段的更改传播到其他字段,从而允许进行否则会不安全的更改。

实数值类型可安全更改的一般规则的例外情况

字段

可修改性

注释

qpos0
qpos_spring

使用 mj_setConst 是安全的。

body_mass
body_inertia
body_ipos
body_iquat

使用 mj_setConst 是安全的。

请注意,质量和惯性通常一起缩放,因为惯性是 \(\sum m r^2\)。分开缩放它们是合法的,但意味着空间质量分布的改变。另请注意,对角惯性必须遵守三角不等式。

body_pos
body_quat

使用 mj_setConst 是安全的。

对于静态物体不安全,会使中阶段碰撞结构(BVH)失效。

body_gravcomp

安全。

如果具有重力补偿的物体数量从零变为非零,必须调用 mj_setConst

dof_armature

使用 mj_setConst 是安全的。

geom_pos
geom_quat
geom_size
geom_rbound
geom_aabb

不安全。

{site,cam,light}_
{pos,quat}

大部分安全。

对于带有跟踪或目标的相机和光源,需要调用 mj_setConst

tendon_stiffness
tendon_damping

大部分安全。

影响运动学树是否允许休眠。如果从/到零更改,需要调用 mj_setConst

actuator_gainprm
actuator_biasprm

大部分安全。

对于使用 dampratio 的类似位置的致动器,需要调用 mj_setConst

eq_data

使用 mj_setConst 是安全的。

对于连接和焊接约束,如果未提供偏移量,则会自动计算。

hfield_size

使用 mj_setConst 是安全的。

hfield_data

安全。

数据范围必须在 [0, 1] 内。
需要调用 mjr_uploadHField 来更新 GPU 内存中的值。

mesh_scale
mesh_pos
mesh_quat

并非不安全,但没有效果。

mesh_posmesh_quat 在运行时会影响 SDF 传感器。

mesh_vert
mesh_normal
mesh_face
mesh_polynormal

对于会发生碰撞的网格不安全。

对于可视化网格是安全的,但需要调用 mjr_uploadMesh 来更新 GPU 内存中的值。

bvh_aabb
oct_aabb
oct_coeff

不安全

最后,如果在运行时对 mjModel 进行了更改,可能希望将它们保存回 XML。函数 mj_saveLastXMLmj_copyBack 在有限的意义上可以做到这一点:它们将所有实数值参数从 mjModel 复制回 mjSpec(前者是全局内部规范,后者是用户的副本)。这并不能覆盖用户可能做的所有更改。保证所有更改都被保存的唯一方法是使用函数 mj_saveModel 将模型保存为二进制 MJB 文件,或者更好的方法是直接在 XML 或 mjSpec 中进行更改。总而言之,我们有合理但并不完美的机制来保存模型更改。这种不完美的原因是我们在处理一个已编译的模型,这就像更改一个二进制可执行文件并要求一个“反编译器”对 C 代码进行相应的更改——这通常是不可能的。

数据布局#

MuJoCo 中的所有矩阵都采用行主序格式。例如,线性内存数组 (a0, a1, … a5) 表示一个 2x3 的矩阵:

a0 a1 a2
a3 a4 a5

这个约定传统上与 C 语言相关联,而相反的列主序约定则与 Fortran 相关联。选择哪一种并没有特别的原因,但无论选择哪一种,都必须时刻牢记。所有操作矩阵的 MuJoCo 工具函数,如 mju_mulMatMatmju_mulMatVec 等都假定这种矩阵布局。对于向量,行主序和列主序格式当然没有区别。

在可能的情况下,MuJoCo 会利用稀疏性。这可以使计算复杂度从 O(N^3) 变为 O(N)。惯性矩阵 mjData.qM 及其 LTDL 分解 mjData.qLD 总是以稀疏形式表示。qM 使用一种为对应树形拓扑的矩阵设计的自定义索引格式,而 qLD 使用标准的 CSR 格式。qM 将在即将到来的变更中迁移到 CSR。函数 mj_factorMmj_solveMmj_solveM2mj_mulM 用于稀疏分解、替换和矩阵向量乘法。用户也可以使用函数 mj_fullM 将这些矩阵转换为稠密格式,尽管 MuJoCo 内部从不这样做。

当启用稀疏雅可比选项时,约束雅可比矩阵 mjData.efc_J 会以稀疏形式表示。函数 mj_isSparse 可以用来确定当前是否使用稀疏格式。在这种情况下,转置雅可比矩阵 mjData.efc_JT 也会被计算,并且逆约束惯性 mjData.efc_AR 也会变为稀疏。稀疏矩阵以压缩稀疏行(CSR)格式存储。对于一个维度为 m x n 的通用矩阵 A,该格式为:

变量

大小

含义

A

m * n

实数值数据

A_rownnz

m

每行的非零元素数

A_rowadr

m

行数据在 A 和 A_colind 中的起始索引

A_colind

m * n

列索引

因此 A[A_rowadr[r]+k] 是底层稠密矩阵在第 r 行、第 A_colind[A_rowadr[r]+k] 列的元素,其中 k < A_rownnz[r]。通常不需要 m*n 的存储空间(假设矩阵确实是稀疏的),但我们为最坏情况分配了空间。此外,在可以改变稀疏模式的操作中,将数据分散开来更有效,这样在插入新数据时就不必进行大量的内存移动。我们称这种稀疏布局为“未压缩”。它仍然是一种有效的布局,但不是标准约定中的 A_rowadr[r] = A_rowadr[r-1] + A_rownnz[r],我们设置 A_rowadr[r] = r*n。MuJoCo 内部使用稀疏矩阵。

为了表示 3D 方向和旋转,MuJoCo 使用单位四元数——即排列为 q = (w, x, y, z) 的 4D 单位向量。这里 (x, y, z) 是旋转轴单位向量乘以 sin(a/2),其中 a 是以弧度为单位的旋转角度,而 w = cos(a/2)。因此,对应于零旋转的四元数是 (1, 0, 0, 0)。这是 MJCF 中所有四元数的默认设置。

MuJoCo 内部也使用 6D 空间向量。这些是 mjData 中以 'c' 为前缀的量,即 cvel、cacc、cdot 等。它们是空间运动和力向量,结合了一个 3D 旋转分量和一个 3D 平移分量。我们不提供用于处理它们的工具函数,并且在此处记录它们超出了我们的范围。请参见 Roy Featherstone 关于空间代数的网页。这种不寻常的顺序(旋转先于平移)是基于这份资料,并且显然是过去的标准惯例。

数据结构 mjModel 和 mjData 包含许多指向预分配缓冲区的指针。这些数据结构的构造函数(mj_makeModel 和 mj_makeData)分配一个大缓冲区,即 mjModel.buffermjData.buffer,然后将其分区并设置所有其他指针。mjData 在这个主缓冲区之外还包含一个堆栈,如下所述。即使两个指针看起来是连续的,例如 mjData.qposmjData.qvel,也不要假设数据数组是连续的,并且它们之间没有间隙。构造函数为每个数据数组实现字节对齐,并在必要时跳过字节。所以,如果你想复制 mjData.qposmjData.qvel,正确的方法是笨办法:

// do this
mju_copy(myqpos, d->qpos, m->nq);
mju_copy(myqvel, d->qvel, m->nv);

// DO NOT do this, there may be padding at the end of d->qpos
mju_copy(myqposqvel, d->qpos, m->nq + m->nv);

可选头文件 mjxmacro.h 中定义的 X 宏 可用于自动化分配与 mjModel 和 mjData 匹配的数据结构,例如在为脚本语言编写 MuJoCo 包装器时。

内部堆栈#

MuJoCo 在 mjData.arena 的一个“竞技场”空间中分配和管理动态内存。竞技场内存空间包含两种类型的动态分配内存:

  • 与约束相关的内存,因为在一步开始时接触点的数量是未知的。

  • 用于临时变量的内存,由内部堆栈机制管理。

有关竞技场和内部堆栈布局的详细信息,请参见内存分配

大多数顶层的 MuJoCo 函数在 mjData 堆栈上分配空间,用于内部计算,然后释放它。它们不能使用常规的 C 堆栈,因为分配大小是在运行时动态确定的。调用堆内存管理函数效率低下且会导致碎片化——因此使用自定义堆栈。当任何 MuJoCo 函数被调用时,返回时 mjData.pstack 的值是相同的。唯一的例外是函数 mj_resetData 及其变体:它们设置 mjData.pstack = 0。请注意,当在 mj_stepmj_step1mj_step2 中检测到不稳定性时,此函数会在内部被调用。因此,如果用户函数利用了自定义堆栈,这需要在可能重置仿真的 MuJoCo 调用之间进行。

以下是在用户代码中使用自定义堆栈的通用模板。

// mark an mjData stack frame
mj_markStack(d);

// allocate space
mjtNum* myqpos = mj_stackAllocNum(d, m->nq);
mjtNum* myqvel = mj_stackAllocNum(d, m->nv);

// restore the mjData stack frame
mj_freeStack(d);

函数 mj_stackAllocNum 检查是否有足够的空间,如果有,则推进堆栈指针,否则触发一个错误。它还跟踪最大堆栈分配;请参见下面的诊断。请注意,mj_stackAllocNum 仅用于分配最常见的数组类型 mjtNum 数组。mj_stackAllocInt 用于整数数组分配,而 mj_stackAllocByte 用于分配任意字节数和对齐。

错误和警告#

当发生致命错误时,MuJoCo 会在内部调用函数 mju_error。mju_error 的作用如下:

  1. 将错误消息附加到程序目录下的 MUJOCO_LOG.TXT 文件末尾(如果文件不存在则创建)。同时写入日期和时间以及错误消息。

  2. 如果安装了用户错误回调 mju_user_error,则调用该函数并以错误消息作为参数。否则,将错误消息和“按 Enter 键退出...”打印到标准输出。然后等待任何键盘输入,然后以失败状态终止模拟器。

如果安装了用户错误回调,它必须**不**返回,否则模拟器的行为是未定义的。这里的想法是,如果调用了 mju_error,仿真就不能继续,并且期望用户进行一些更改以避免错误条件。错误消息是自解释的。

一种即使在出错后仍希望继续的情况是,一个交互式模拟器加载模型文件失败。这可能是因为用户提供了错误的文件名,或者模型编译失败。这种情况通过一种特殊机制处理,避免了调用 mju_error。模型加载函数 mj_loadXMLmj_loadModel 在操作失败时返回 NULL,并且无需退出程序。对于 mj_loadXML,有一个输出参数包含导致失败的解析器或编译器错误,而 mj_loadModel 则会生成相应的警告(见下文)。

mj_loadXML 内部实际上使用了 mju_error 机制,通过临时安装一个“用户”处理程序来触发一个 C++ 异常,然后该异常被拦截。这是可能的,因为解析器、编译器和运行时是编译和链接在一起的,并且使用同一份 C/C++ 内存管理器和标准库。如果用户实现一个触发 C++ 异常的错误回调,这将发生在他们的工作空间中,不一定与 MuJoCo 库工作空间相同,所以会发生什么并不清楚;结果可能取决于编译器和平台。最好避免这种方法,在调用 mju_error 时直接退出(这是在没有用户处理程序时的默认行为)。

MuJoCo 也可以生成警告。它们指示可能导致数值不准确的情况,但也可以指示加载模型时遇到的问题以及其他有问题但模拟器仍能继续正常运行的情况。警告机制有两个层次。高层是通过函数 mj_warning 实现的。它在 mjData 中注册一个警告,具体细节在下面的诊断部分有更详细的解释,并且还会调用低层函数 mju_warning。或者,低层函数也可以直接被调用(例如从 mj_loadModel 内部)而不在 mjData 中注册警告。这在 mjData 不可用的地方进行。

mju_warning 的作用如下:如果安装了用户回调 mju_user_warning,它会调用该回调。否则,它会将警告消息附加到 MUJOCO_LOG.TXT,并进行 printf,类似于 mju_error,但不退出。当为 MATLAB 等环境开发 MuJoCo 包装器时,安装一个在命令窗口中打印警告的用户回调(使用 mexPrintf)是有意义的。

当 MuJoCo 在堆上分配和释放内存时,它总是使用函数 mju_mallocmju_free。这些函数在安装了用户回调 mju_user_mallocmju_user_free 时会调用它们,否则它们会调用标准的 C 函数 malloc 和 free。这种间接性的原因是因为用户可能希望 MuJoCo 使用他们控制下的堆。例如,在 MATLAB 中,用于内存分配的用户回调会使用 mxmalloc 和 mexMakeArrayPersistent。

诊断#

MuJoCo 有几个内置的诊断机制,可以用来微调模型。它们的输出被分组在 mjData 开头的诊断部分。

当模拟器遇到一个非致命错误但仍可疑并可能导致数值结果不准确的情况时,它会触发一个警告。有几种可能的警告类型,由枚举类型 mjtWarning 索引。数组 mjData.warning 为每种警告类型包含一个 mjWarningStat 数据结构,指示自上次重置以来每种警告类型被触发了多少次,以及关于警告的任何信息(通常是有问题的模型元素的索引)。计数器在重置时被清除。当给定类型的警告首次被触发时,警告文本也会由 mju_warning 打印,如上文错误和内存中所述。所有这些都由函数 mj_warning 完成,模拟器在遇到警告时会在内部调用它。用户也可以直接调用此函数来模拟一个警告。

当需要为高速仿真优化模型时,了解 CPU 时间花在流水线的哪个部分是很重要的。这反过来可以建议简化模型的哪些部分或如何设计用户应用程序。MuJoCo 提供了一个广泛的性能分析机制。它涉及多个计时器,由枚举类型 mjtTimer 索引。每个计时器对应一个顶层 API 函数或该函数的组件。与警告类似,计时器信息会累积,并且只有在重置时才会被清除。数组 mjData.timer 为每个计时器包含一个 mjTimerStat 数据结构。给定计时器(在下面的示例中对应于 mj_step)的平均每次调用时长可以计算为:

mjtNum avtm = d->timer[mjTIMER_STEP].duration / mjMAX(1, d->timer[mjTIMER_STEP].number);

这个机制是 MuJoCo 内置的,但只有在用户安装了计时器回调 mjcb_time 时才有效。否则,所有计时器时长都为 0。这种设计的原因是,在 C 语言中没有平台无关的方式来实现高分辨率计时器而不引入额外的依赖项。此外,大多数时候用户不需要计时,在这种情况下没有理由调用计时函数。

仿真流程中需要密切监控的一个部分是迭代约束求解器。这里最简单的诊断是 mjData.solver_niter,它显示了求解器在上一次调用 mj_step 或 mj_forward 时进行了多少次迭代。请注意,求解器有用于提前终止的容差参数,所以这个数字通常小于允许的最大迭代次数。数组 mjData.solver 为约束求解器的每次迭代包含一个 mjSolverStat 数据结构,其中包含有关约束状态和线搜索的信息。

mjModel.opt.enableflags 中的 fwdinv 选项被启用时,字段 mjData.fwdinv 也会被填充。它包含正向和逆向动力学之间的差异,以广义力和约束力表示。回想一下,逆向动力学使用解析公式并且总是精确的,因此任何差异都是由于正向动力学中迭代求解器的收敛性不佳造成的。mjData.solver 中接近终止时的数值与 mjData.fwdinv 中的数值具有相似的量级,但它们是两种不同的诊断。

由于 MuJoCo 的运行时使用编译后的模型,因此在编译或加载模型时会预先分配内存。回想一下 MJCF 中 size 元素的 memory 属性。它决定了为动态数组预分配的空间。用户应该如何知道适当的值是什么?如果有一个可靠的方法,我们就会在编译器中实现它,但并没有。理论上的最坏情况,即所有几何体都与其他所有几何体接触,需要巨大的分配,而这在实践中几乎从不需要。我们的方法是在 MJCF 中提供对大多数模型都足够的默认设置,并允许用户使用上述属性手动调整它们。如果模拟器在运行时耗尽动态内存,它将触发一个错误。当触发此类错误时,用户应增加 memory。字段 mjData.maxuse_arena 就是为了帮助进行这种调整而设计的。它记录了自上次重置以来竞技场的最大使用量。因此,一种策略是进行非常大的分配,然后在典型仿真期间监控 mjData.maxuse_memory 统计数据,并用它来减少分配。

mjModel.opt.enableflags 中相应的标志被设置时,动能和势能会被计算并存储在 mjData.energy 中。这可以作为另一个诊断工具。通常,仿真不稳定性与能量增加有关。在某些特殊情况下(当所有单边约束、致动器和耗散力都被禁用时),底层的物理系统是能量守恒的。在这种情况下,总能量的任何时间波动都表明数值积分存在不准确性。对于这类系统,龙格-库塔积分器的性能比默认的半隐式欧拉积分器好得多。

雅可比矩阵#

任何向量函数对其向量参数的导数称为雅可比矩阵。当这个术语用于多关节运动学和动力学时,它指的是某个空间量作为系统构型函数的导数。在这种情况下,雅可比矩阵也是一个线性映射,作用于构型流形(co)切空间中的向量——如速度、动量、加速度、力。这里有一个需要注意的地方,即 mjData.qpos 中编码的系统构型维度为 mjModel.nq,而切空间维度为 mjModel.nv,当存在四元数关节时,后者更小。所以雅可比矩阵的大小是 N x mjModel.nv,其中 N 是被微分的空间量的维度。

MuJoCo 可以解析地微分许多空间量。这些包括肌腱长度、致动器传动长度、末端执行器位姿、接触和其他约束违规。对于肌腱和致动器传动,相应的量是 mjData.ten_momentmjData.actuator_moment;我们称它们为力臂,但数学上它们是雅可比矩阵。所有标量约束违规的雅可比矩阵存储在 mjData.efc_J 中。请注意,我们谈论的是约束违规而不是约束本身。这是因为约束违规具有长度单位,即它们是我们可以微分的空间量。约束是更抽象的实体,微分它们的含义并不清楚。

除了这些自动计算的雅可比矩阵,我们还提供了支持函数,允许用户按需计算额外的雅可比矩阵。完成这项工作的主要函数是 mj_jac。它给定一个 3D 点和一个 MuJoCo 物体,该点被认为附着于该物体。mj_jac 随后计算平移和旋转雅可比矩阵,它们告诉我们,如果我们对运动学构型做一个微小的改变,一个锚定在给定点的空间坐标系将如何平移和旋转。更确切地说,雅可比矩阵将关节速度映射到末端执行器速度,而雅可比矩阵的转置将末端执行器力映射到关节力。还有其他几个 mj_jacXXX 函数;这些是便利函数,它们使用不同的兴趣点(如物体质心、几何体中心等)调用主 mj_jac 函数。

能够精确高效地计算末端执行器雅可比矩阵是在关节坐标下工作的一个关键优势。这些雅可比矩阵是许多控制方案的基础,这些方案将末端执行器误差映射到适合抑制这些误差的致动器命令。在 MuJoCo 中通过 mj_jac 函数计算末端执行器雅可比矩阵在 CPU 成本方面基本上是免费的;所以不要犹豫使用这个函数。

接触#

碰撞检测和求解接触力在计算章节中有详细解释。这里我们从编程的角度进一步阐明接触处理。

碰撞检测阶段会找到几何体之间的接触,并将它们记录在 mjContact 数据结构的数组 mjData.contact 中。它们经过排序,使得同一对刚体之间的多个接触是连续的(请注意,一个刚体可以附着多个几何体),并且刚体对本身也经过排序,使得第一个刚体作为主索引,第二个刚体作为次索引。并非所有检测到的接触都包含在接触力计算中。当一个接触被包含时,其 mjContact.exclude 字段为 0,其 mjContact.efc_address 是活动标量约束列表中的地址。排除的原因可以是 geomgap 属性,以及某些使用虚拟接触进行中间计算的内部处理。

列表 mjData.contact 是由正向和逆向动力学的位置阶段生成的。这是自动完成的。但是,用户可以重写内部碰撞检测函数,例如实现非凸网格碰撞,或者用 MuJoCo 提供的几何体特定基元之外的函数替换我们使用的一些凸碰撞函数。全局二维数组 mjCOLLISIONFUNC 包含每对几何体类型的碰撞函数指针(在左上三角部分)。要替换它们,只需将这些指针设置为您的函数。碰撞函数的类型是 mjfCollision。当用户碰撞函数检测到接触时,它们应该为每个接触构造一个 mjvContact 结构,然后调用函数 mj_addContact 将该接触添加到 mjData.contact 中。mj_addContact 的参考文档解释了自定义碰撞函数必须填充 mjContact 的哪些字段。请注意,我们在这里讨论的函数对应于近相碰撞,并且仅在内部宽相碰撞机制构建了候选几何体对列表之后才被调用。

在计算完约束力之后,接触 i 的力向量从以下位置开始:

mjtNum* contactforce = d->efc_force + d->contact[i].efc_address;

所有其他 efc_XXX 向量也类似。请记住,接触摩擦锥可以是金字塔形或椭圆形,具体取决于在 mjModel.opt 中选择的求解器。函数 mj_isPyramidal 可用于确定使用的是哪种摩擦锥类型。对于金字塔形锥体,接触力(其地址我们已在上面计算)的解释并非易事,因为其分量是沿着与金字塔边缘对应的冗余非正交轴的力。函数 mj_contactForce 可用于将给定接触产生的力转换为更直观的格式:一个 3D 力后跟一个 3D 力矩。当 condim 为 1 或 3 时,力矩分量将为零,否则不为零。此力和力矩在 mjContact.frame 给出的接触坐标系中表示。与 mjData 中的所有其他矩阵不同,此矩阵以转置形式存储。通常,对应于坐标系的 3x3 矩阵的轴应沿着列。在这里,轴是沿着矩阵的行。因此,鉴于 MuJoCo 使用行主序格式,接触法线轴(根据我们的约定,它是接触坐标系的 X 轴)位于 mjContact.frame[0-2] 的位置,Y 轴在 [3-5],Z 轴在 [6-8]。这种安排的原因是,我们可能有无摩擦接触,其中只使用法线轴,因此将其坐标放在 mjContact.frame 的前 3 个位置是合理的。

休眠岛#

计算章节中概括地描述了休眠岛。这里我们关注实现细节。

的高级休眠状态由 mjData.tree_asleep 描述(但请参见下面的注意事项)。负值表示树是活动的,非负值表示休眠。最大活动状态的树被赋值为 -(1 + mjMINAWAKE),在每个时间步中,如果它们的速度低于休眠容差,这个整数就会增加,直到 -1,表示“准备休眠”。如果一个岛中的所有树都准备好休眠,它们将在状态推进期间进入休眠状态,并且它们在 tree_asleep 中的关联值将被设置为一个(非负的)索引周期:即“休眠岛”。如果岛中的任何一棵树被唤醒,那么所有的树都会被唤醒。

休眠策略#

运动树的休眠能力由模型编译时确定的策略控制。编译器会自动确定策略为“允许”或“从不”,不过这些可以通过使用 body/sleep 属性来覆盖(详见其文档)。还有一个特殊的“init”休眠策略,请见下一节。

休眠#

休眠可以通过以下两种方式之一发生

自动

上述速度阈值是相对于与岛关联的所有速度的无穷范数(最大绝对值)。在取这个范数之前,速度会按元素与 mjModel.dof_length 相乘,因为旋转速度和平移速度的单位不同。平移自由度的长度为 1;旋转自由度的长度对应于其关联几何体的平均长度。因此,sleep_tolerance 的单位是 [长度/时间]。

当一个岛进入休眠状态时,其相关的速度被设置为 0。因此,在任何有岛进入休眠状态的时间步,所有与速度相关的量都必须在休眠状态通过调用 mj_forwardSkip 传播之前重新计算。

如果岛中的任何树具有“从不”休眠策略,则整个岛都不能休眠。

初始化为休眠

通过将树根的 body/sleep 属性设置为“init”,它被标记为“初始化为休眠”,并在 mjData 初始化期间进入休眠状态。这对于大型模型非常有用,因为等待许多树进入休眠状态可能会非常耗时。

由于共享接触或以其他方式位于同一岛中的树必须一起休眠,如果一个岛中的某些树被初始化为休眠,那么所有这些树都必须被标记为休眠。此模型包含一个 XML 示例,由于不满足此条件,将产生编译错误。最后请注意,初始化为休眠功能仅适用于默认配置(而不适用于关键帧,请参阅下面的讨论)。

唤醒#

唤醒发生在时间步的开始,可以在 mj_kinematics 期间或之后不久的仿真管线位置阶段发生。休眠的岛根据以下标准被唤醒

  • 其相关的配置 qpos 被用户更改,例如在仿真暂停时以交互方式重新定位配置。

  • 其相关的速度 qvel 或施加的力 qfrc_appliedxfrc_applied 被用户设置为非零值,例如在仿真期间以交互方式扰动模型。请注意,检查是通过与 0 的逐字节比较执行的,因此将相关元素设置为浮点值 -0.0 将唤醒该岛,但没有其他副作用。

  • 它与一个活动的树发生接触。由于接触而唤醒会导致碰撞检测运行*两次*,但仅在发生的时间步。这是必需的,以便检测岛内部以及岛与世界之间的接触,这些接触在第一次运行时因其被视为休眠而被跳过。

  • 它通过活动的等式约束或有限肌腱连接到一个活动的树。

  • 它通过等式约束连接到另一个岛中的休眠树。要发生这种情况,该等式必须在两棵树都进入休眠状态时被禁用。

上面列出的自动唤醒标准旨在使休眠岛的行为就像它们是活动的一样,但这并非总是如此。例如,如果地板上的自由体进入休眠状态,然后重力反转,它们将保持在原地休眠,直到因其他原因被唤醒。最极端的非物理性例子是初始化为休眠的岛。它们可以被放置在半空中或深度碰撞中,但在被唤醒之前不会移动。

注意#

新功能

休眠是一项新功能(2025年11月),可能会发生变化,并且可能存在潜在的错误。

休眠的执行器

body/sleep 文档中所述,默认情况下,带有执行器的树不允许休眠,但这可以由用户覆盖。默认不允许休眠的原因是,一旦执行器被标记为休眠,唤醒它所需的计算就不再执行。即使执行了(即,如果无论其休眠状态如何,都为所有执行器计算驱动力),这个计算也发生在加速度/力阶段,此时唤醒树已经为时已晚,因为唤醒必须在位置阶段发生。因此,如果允许带有执行器的树休眠,则必须通过触摸相关的速度或力来手动唤醒,如上所述。

休眠的传感器

对于大多数传感器,当其关联的对象处于休眠状态时,我们可以跳过其值的计算,报告这些对象上次活动时计算的值。有些传感器始终处于活动状态,但禁用休眠不会影响它们的计算值

  • rangefinder 传感器始终处于活动状态;它们所附着的 site 的休眠状态与报告的值无关。

  • clock 传感器始终处于活动状态(没有关联的对象)。

  • userplugin 传感器始终处于活动状态。

有些传感器始终处于活动状态,但禁用休眠可能会影响其计算值。这些是明确依赖于接触存在的传感器,但它们上次活动时存在的接触不足以确定它们的当前值

  • 没有对象说明符(匹配所有接触)的 contact 传感器。

  • 其唯一对象说明符是静态的 contact 传感器。

  • 使用 site 属性的 contact 传感器。

  • 附着在静态刚体上的 forcetorque 传感器(例如,地板上的重量传感器)。

临时选择

一些实现选择是临时的,可能会发生变化。

一个具体的例子是决定硬编码 mjMINAWAKE 的值,而不是作为运行时选项暴露给用户。这样做有两个原因。首先,在我们的实验中,我们发现更改此值等同于更改 sleep_tolerance,后者是更有用的调节旋钮。其次,有人可能会主张使用以时间为单位而不是整数个时间步长的休眠时间语义。在有明确证据表明这两个原因中的一个或两个都无效之前,我们选择了简单的数值常数。

静态刚体

除了允许运动树休眠的主要优化之外,休眠功能还包括另一个相关的优化:跳过与静态刚体相关的计算。如果世界刚体或其静态子节点包含大量几何体,其姿态将只计算一次,那么这将非常有价值。

这导致了一个微妙(尽管不太可能)的“陷阱”。虽然允许在仿真期间启用休眠,但休眠必须在初始化时或至少在一次 mj_step 之后启用。即

// this is OK:
mjData* d = mj_makeData(m);            // sleeping is enabled at init time
mj_step(m, d);
...

// this is also OK:
mjData* d = mj_makeData(m);            // sleeping is disabled at init time
mj_step(m, d);
...
m->opt.enableflags |= mjENABLE_SLEEP;  // enable sleeping after at least one step
mj_step(m, d);

// this is an error:
mjData* d = mj_makeData(m);            // sleeping is disabled at init time
m->opt.enableflags |= mjENABLE_SLEEP;  // enable sleeping
mj_step(m, d);                         // undefined behavior, static elements not computed
被违背的假设

休眠打破了 MuJoCo 核心中固有的几个假设(如果禁用休眠,这些假设仍然成立)。

管线阶段:通常保证在位置阶段结束前不会读取任何与速度相关的量,在速度阶段结束前不会读取任何与力相关的量。这个假设是 mj_step1/mj_step2 分割的核心,但被 mj_kinematics 中对 qvelqfrc_appliedxfrc_applied 的读取所违背。

紧凑状态:虽然休眠状态名义上由 mjData.tree_asleep 给出,但这是一种假象。一旦一个岛处于休眠状态,mjData 中与之关联的所有位置和速度相关量的子集就变成了一个预先计算的潜在状态,它“等待岛被唤醒”。因此,完全保存和恢复带有休眠元素的仿真状态的唯一方法是 复制 整个 mjData 结构。这也是为什么休眠初始化仅适用于默认配置而不适用于关键帧的原因。请注意,使用标准工具保存和加载状态仍然是有效的操作,只是休眠的岛会被隐式唤醒。

RK4 积分器

由于在子步骤内唤醒的微妙之处,目前不支持 RK4 积分器。

潜在错误

休眠是一项新功能(2025年11月),可能存在潜在错误。这些错误通常可能分为两类

  • 本可以跳过的量被重新计算。这种错误的唯一可观察效果是仿真比它可能的速度要慢。这类错误只能通过详细的性能分析来诊断。

  • 实际错误。希望这些错误会导致信息丰富的运行时错误,请向开发团队报告任何错误。

坐标系与变换#

MuJoCo 中使用了多个坐标系。最高层的区别是关节坐标和笛卡尔坐标。从关节坐标向量到所有刚体的笛卡尔位置和方向的映射称为正向运动学,是物理管线的第一步。相反的映射称为逆运动学,但它不是唯一确定的,在 MuJoCo 中没有实现。回想一下,切空间之间的映射(即,关节速度和力到笛卡尔速度和力)由刚体雅可比矩阵给出。

在这里,我们进一步解释坐标系的细微之处和划分,并总结可用的变换函数。在关节坐标中,唯一的复杂之处在于,由于四元数关节,位置向量 mjData.qpos 的维度与速度和加速度向量 mjData.qvelmjData.qacc 不同。函数 mj_differentiatePos “减去”两个关节位置向量并返回一个速度向量。相反,函数 mj_integratePos 接受一个位置向量和一个速度向量,并返回一个被给定速度位移后的新位置向量。

笛卡尔坐标更复杂,因为我们使用三种不同的坐标系:局部坐标系、全局坐标系和基于质心的坐标系。局部坐标用于在 mjModel 中表示父刚体和子刚体之间的静态偏移,以及刚体与其上附着的任何几何体、site、相机和灯光之间的静态偏移。这些静态偏移是在任何关节变换之外应用的。所以 mjModel.body_posmjModel.body_quat 和 mjModel 中所有其他空间量都是在局部坐标中表示的。正向运动学的工作是沿着运动树累积关节变换和静态偏移,并计算所有在全局坐标中的位置和方向。mjData 中以“x”开头的量是在全局坐标中表示的。它们是 mjData.xposmjData.geom_xpos 等。坐标系方向通常存储为 3x3 矩阵 (xmat),但刚体的方向也存储为单位四元数 mjData.xquat。给定这个刚体四元数,附着在刚体上的所有其他对象的四元数可以通过四元数乘法重建。函数 mj_local2Global 从局部刚体坐标转换到全局笛卡尔坐标。

位姿是 3D 位置和单位四元数方向的组合。没有单独的数据结构;这种组合是逻辑上的。它表示空间中的一个位置和方向,换句话说,一个空间坐标系。请注意,OpenGL 使用 4x4 矩阵来表示相同的信息,只是在这里我们使用四元数来表示方向。函数 mju_mulPose 将两个位姿相乘,这意味着它用第二个位姿变换第一个位姿(顺序很重要)。mju_negPose 构造相反的位姿,而 mju_trnVecPose 用一个位姿变换一个 3D 向量,如果我们将位姿看作一个坐标系,它将向量从局部坐标映射到全局坐标。如果我们只想操作方向部分,我们可以用类似的四元数工具函数 mju_mulQuatmju_negQuatmju_rotVecQuat 来做到这一点。

最后,是基于质心的坐标系。这用于表示 6D 空间向量,包含一个 3D 角速度、角加速度或力矩,后跟一个 3D 线速度、线加速度或力。请注意顺序是反的:旋转后是平移。mjData.cdofmjData.cacc 是此类向量的例子;名称以“c”开头。这些向量在多关节动力学计算中起着关键作用。在此解释超出了我们的范围;请参阅 Featherstone 关于该主题的优秀幻灯片。总的来说,用户应避免直接处理这些量。而是使用函数 mj_objectVelocitymj_objectAcceleration 和低级函数 mju_transformSpatial 来获取给定刚体的线速度和角速度、加速度和力。不过,对于感兴趣的读者,我们总结一下“c”量最不寻常的方面。假设我们想表示一个在原地旋转的刚体。人们可能期望一个空间速度具有非零的角速度和零的线速度。然而事实并非如此。旋转被解释为围绕穿过坐标系中心的轴进行,该轴在刚体外部(我们使用运动树的质心)。这样的旋转不仅会旋转刚体,还会平移它。因此,空间向量必须具有非零的线速度来补偿围绕刚体外轴旋转的副作用。如果您调用 mj_objectVelocity,得到的 6D 量将在一个以刚体为中心并与世界坐标系对齐的坐标系中表示。因此,线性分量将如预期般为零。该函数还会将平移放在旋转之前,这是我们对局部和全局坐标的约定。