仿真#

初始化#

在进行version检查后,下一步是分配和初始化仿真所需的主要数据结构,即 mjModel 和 mjData。与可视化和回调相关的额外初始化步骤将在稍后讨论。

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

首先,我们必须调用其中一个分配和初始化 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-like 函数库;事实上,代码库的很大一部分是由内部调用此类函数组成。上面的 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);
}

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

接下来我们展示两步法实现的步骤,尽管具体细节只有在我们稍后解释正向动力学后才能理解。请注意,由于我们实际上已经解包了正向动力学函数,现在直接调用控制回调函数。另请注意,无论 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 在内部调用带有跳过参数 (mjSTAGE_NONE, 0) 的 mj_forwardSkip,后者的实现如下

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

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

多线程#

仿真循环一节所述,当 MuJoCo 用于仿真时,它在单线程中运行。我们曾尝试对仿真管道中计算开销大且易于并行处理的部分进行多线程处理,并得出结论,所带来的速度提升不值得占用额外的处理器核心。这是因为与在同一时间步内启动和同步多个线程的开销相比,MuJoCo 本身已经很快。如果用户开始处理包含许多浮体的大规模仿真,我们最终可能会实现步内多线程,但目前这种使用场景并不常见。

与其加速单个仿真,我们更倾向于使用多线程来加速更高级应用中常见的采样操作。仿真在时间上是固有的串行(一个 mj_step 的输出是下一个 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 可能需要在线程函数内部进行修改。另一个原因是 mjModel 中包含的 mjOption 结构可能需要调整(例如,控制求解器迭代次数),尽管这对于所有并行线程可能相同,因此可以在并行部分之前在共享模型中进行调整。

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

模型更改#

模型编辑框架

下面关于运行时修改 mjModel 的讨论是在 模型编辑 框架 3.2.0 版本引入之前编写的。它仍然有效,但新框架是修改模型的安全且推荐的方法。

mjModel 中包含的 MuJoCo 模型应代表系统的恒定物理属性,理论上在编译后不应更改。当然,实践中事情并非如此简单。经常需要更改 mjModel.opt 中的物理选项,以便试验物理的不同方面或创建自定义计算。事实上,这些选项的设计使得用户可以在时间步之间对其进行任意更改。

一般规则是,实值参数可以安全更改,而结构整数参数则不能,因为那可能导致不正确的大小或索引。尽管如此,这个规则并非普遍适用。一些实值参数(如惯量)需要遵循某些属性。另一方面,一些结构参数(如对象类型)可能可以更改,但这取决于是否有任何大小或索引依赖于它们。mjtByte 类型的数组可以安全更改,因为它们是启用和禁用某些功能的二进制指示符。唯一的例外是 mjModel.tex_data,它是以 mjtByte 表示的纹理数据。

更改与上传到 GPU 的资源相对应的 mjModel 字段时,用户还必须调用相应的上传函数:mjr_uploadTexturemjr_uploadMeshmjr_uploadHField。否则,用于仿真和渲染的数据将不再一致。

一个相关的考虑是更改已被编译器用于计算其他实值字段的 mjModel 实值字段:如果我们进行更改,我们希望它能够传播。这就是函数 mj_setConst 的作用:它更新 mjModel 的所有派生字段。这些字段的名称以“0”结尾,对应于模型处于参考配置 mjModel.qpos0 时的预计算量。

最后,如果在运行时对 mjModel 进行了更改,可能希望将其保存回 XML。函数 mj_saveLastXML 在有限的意义上实现了这一点:它将 mjModel 中的所有实值参数复制回内部的 mjSpec,然后将其保存为 XML。这并未涵盖用户可能进行的所有更改。确保所有更改都已保存的唯一方法是使用函数 mj_saveModel 将模型保存为二进制 MJB 文件,或者更好的是,直接在 XML 中进行更改。不幸的是,在某些情况下(例如系统辨识),需要以编程方式进行更改,而这只能通过编译后的模型来实现。因此,总而言之,我们有合理的但并非完美的机制来保存模型更改。这种不完美的原因在于我们正在使用编译后的模型,这就像更改二进制可执行文件并要求“反编译器”对 C 代码进行相应的更改一样——这通常是不可能的。

数据布局#

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

a0 a1 a2
a3 a4 a5

传统上,这种约定与 C 相关联,而相反的列主序约定与 Fortran 相关联。选择哪种方式并没有特别的理由,但无论选择哪种,务必时刻牢记。所有操作矩阵的 MuJoCo 实用函数,例如 mju_mulMatMatmju_mulMatVec 等,都假定采用这种矩阵布局。对于向量而言,行主序和列主序格式当然没有区别。

在可能的情况下,MuJoCo 会利用稀疏性。这可以在 O(N) 和 O(N^3) 复杂度之间产生巨大差异。惯量矩阵 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 在内部使用稀疏矩阵

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

MuJoCo 还在内部使用六维空间向量。这些是 mjData 中以“c”为前缀的量,即 cvel、cacc、cdot 等。它们是结合了三维旋转分量和三维平移分量的空间运动和力向量。我们不提供处理它们的实用函数,并且在此处文档化它们超出了我们的范围。请参阅 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_iter,它显示求解器在上次调用 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 中。这可以用作另一种诊断。一般来说,仿真不稳定与能量增加相关。在某些特殊情况下(禁用所有单边约束、执行器和耗散力时),底层的物理系统是能量守恒的。在这种情况下,总能量的任何时间波动都表明数值积分存在误差。对于此类系统,龙格-库塔积分器的性能远优于默认的半隐式欧拉积分器。

雅可比#

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

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

除了这些自动计算的雅可比外,我们还提供支持函数,允许用户按需计算额外的雅可比。实现此目的的主要函数是mj_jac。该函数需要一个三维点和一个 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可用于将给定接触产生的力转换为更直观的格式:一个三维力后跟一个三维扭矩。当condim为 1 或 3 时,扭矩分量将为零,否则非零。这个力和扭矩在由 mjContact.frame 给定的接触坐标系中表示。与 mjData 中的所有其他矩阵不同,此矩阵以转置形式存储。通常,一个对应于坐标系的 3x3 矩阵会将坐标轴沿列方向排列。这里轴沿行方向排列。因此,鉴于 MuJoCo 使用行优先格式,接触法线轴(根据我们的约定是接触坐标系的 X 轴)在位置 mjContact.frame[0-2],Y 轴在 [3-5],Z 轴在 [6-8]。这种排列的原因是因为我们可以有无摩擦接触,其中只使用法线轴,所以将其坐标放在mjContact.frame的前 3 个位置是有道理的。

坐标系和变换#

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

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

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

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

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