可视化#

MuJoCo 有一个原生的 3D 可视化器。其用法在 simulate.cc 代码示例和更简单的 basic.cc 代码示例中有所说明。虽然它不是一个功能齐全的渲染引擎,但它是一个方便、高效且外观相当不错的可视化器,有助于研究和开发。它不仅渲染仿真状态,还渲染装饰性元素,如接触点和力、等效惯性盒、凸包、运动学树、约束违反、空间坐标系和文本标签;这些可以帮助深入了解物理仿真并微调模型。

可视化器与仿真器紧密集成,支持屏幕上和屏幕外渲染,如 record.cc 代码示例所示。这使其适用于合成计算机视觉和机器学习应用,尤其是在云环境中。从 MuJoCo 1.40 版开始,还提供了 VR 集成,方便了利用 Oculus Rift 和 HTC Vive 等新型头戴式显示器的应用。

MuJoCo 中的可视化是一个两阶段过程

抽象可视化与交互

此阶段用几何对象、光源、相机以及生成 3D 渲染所需的所有其他内容的列表来填充 mjvScene 数据结构。它还为用户交互提供了抽象的键盘和鼠标挂钩。相关的数据结构和函数名称带有前缀 mjv

OpenGL 渲染

此阶段接收在抽象可视化阶段填充的 mjvScene 数据结构,并将其渲染出来。它还提供基本的 2D 绘图和帧缓冲区访问,因此大多数应用程序不需要直接调用 OpenGL。相关的数据结构和函数名称带有前缀 mjr

这种分离有几个原因。首先,这两个阶段在概念上是不同的,将它们分开是良好的软件设计。其次,它们有不同的依赖关系,无论是内部的还是对额外库的依赖;特别是,抽象可视化不需要任何图形库。第三,希望将其他渲染引擎与 MuJoCo 集成的用户可以绕过原生的 OpenGL 渲染器,但仍可利用抽象可视化器。

下面是 C 代码和注释中伪代码的混合,说明了同时进行仿真和渲染的 MuJoCo 应用程序的结构。这是 basic.cc 代码示例的简化版本。为具体起见,我们假设使用 GLFW,尽管它可以被替换为不同的窗口库,如 GLUT 或其衍生库。

// MuJoCo data structures
mjModel* m = NULL;                  // MuJoCo model
mjData* d = NULL;                   // MuJoCo data
mjvCamera cam;                      // abstract camera
mjvOption opt;                      // visualization options
mjvScene scn;                       // abstract scene
mjrContext con;                     // custom GPU context

// ... load model and data

// init GLFW, create window, make OpenGL context current, request v-sync
glfwInit();
GLFWwindow* window = glfwCreateWindow(1200, 900, "Demo", NULL, NULL);
glfwMakeContextCurrent(window);
glfwSwapInterval(1);

// initialize visualization data structures
mjv_defaultCamera(&cam);
mjv_defaultPerturb(&pert);
mjv_defaultOption(&opt);
mjr_defaultContext(&con);

// create scene and context
mjv_makeScene(m, &scn, 1000);
mjr_makeContext(m, &con, mjFONTSCALE_100);

// ... install GLFW keyboard and mouse callbacks

// run main loop, target real-time simulation and 60 fps rendering
while( !glfwWindowShouldClose(window) ) {
  // advance interactive simulation for 1/60 sec
  //  Assuming MuJoCo can simulate faster than real-time, which it usually can,
  //  this loop will finish on time for the next frame to be rendered at 60 fps.
  //  Otherwise add a cpu timer and exit this loop when it is time to render.
  mjtNum simstart = d->time;
  while( d->time - simstart < 1.0/60.0 )
      mj_step(m, d);

  // get framebuffer viewport
  mjrRect viewport = {0, 0, 0, 0};
  glfwGetFramebufferSize(window, &viewport.width, &viewport.height);

  // update scene and render
  mjv_updateScene(m, d, &opt, NULL, &cam, mjCAT_ALL, &scn);
  mjr_render(viewport, &scn, &con);

  // swap OpenGL buffers (blocking call due to v-sync)
  glfwSwapBuffers(window);

  // process pending GUI events, call GLFW callbacks
  glfwPollEvents();
}

// close GLFW, free visualization storage
glfwTerminate();
mjv_freeScene(&scn);
mjr_freeContext(&con);

// ... free MuJoCo model and data

抽象可视化与交互#

此阶段用几何对象、光源、相机以及生成 3D 渲染所需的所有其他内容的列表来填充 mjvScene 数据结构。它还为用户交互提供了抽象的键盘和鼠标挂钩。

相机#

有两种类型的相机对象:一种是由独立数据结构 mjvCamera 表示的抽象相机,另一种是由嵌入在 mjvScene 中的数据结构 mjvGLCamera 表示的低级 OpenGL 相机。当存在抽象相机时,它在场景更新期间用于自动计算 OpenGL 相机参数,然后 OpenGL 渲染器会使用这些参数。或者,用户可以绕过抽象相机机制,直接设置 OpenGL 相机参数,如下文虚拟现实部分所述。

抽象相机可以表示由 mjvCamera.type 决定的三种不同相机类型。可能的设置由枚举 mjtCamera 定义

mjCAMERA_FREE

这是最常用的抽象相机。它可以用鼠标自由移动。它有一个观察点、到观察点的距离、方位角和仰角;不允许围绕视线进行扭转。函数 mjv_moveCamera 是一个鼠标挂钩,用于通过鼠标交互式地控制所有这些相机属性。当 simulate.cc 首次启动时,它使用自由相机。

mjCAMERA_TRACKING

这与自由相机类似,只是观察点不再是一个自由参数,而是与 mjvCamera.trackbodyid 指定的 MuJoCo 物体耦合。在每次更新时,观察点被设置为以指定物体为根的运动学子树的质心。还有一些滤波可以产生平滑的相机运动。距离、方位角和仰角由用户控制,不会自动修改。这对于在物体移动时跟踪它而无需转动相机很有用。要在 simulate.cc 中从自由相机切换到跟踪相机,请按住 Ctrl 并右键双击感兴趣的物体。按 Esc 返回自由相机。

mjCAMERA_FIXED

这是指在模型中明确定义的相机,与自由相机和跟踪相机不同,后者仅存在于可视化器中,并未在模型中定义。模型相机的 id 由 mjvCamera.fixedcamid 给出。此相机是固定的,因为可视化器无法更改其姿态或任何其他参数。但是,仿真器会在每个时间步计算相机姿态,如果相机附着到移动的物体上,或者处于跟踪或瞄准模式,它将会移动。

mjCAMERA_USER

这意味着在更新期间抽象相机被忽略,低级 OpenGL 相机不会被更改。这相当于根本不指定抽象相机,即在下面解释的更新函数中向 mjvCamera 传递一个 NULL 指针。

低级 mjvGLCamera 决定了实际的渲染。mjvScene 中嵌入了两个这样的相机,每只眼睛一个。每个相机都有位置、前向和向上方向。前向对应于相机坐标系的负 Z 轴,而向上对应于正 Y 轴。还有一个 OpenGL 意义上的视锥体,但我们存储的是左右视锥体边缘的平均值,然后在渲染时根据视口宽高比计算实际边缘,假设像素宽高比为 1:1。两个相机位置之间的距离对应于瞳孔间距 (ipd)。当低级相机参数由抽象相机自动计算时,ipd 以及垂直视场 (fovy) 取自 mjModel.vis.global.ipd/fovy(对于自由相机和跟踪相机),以及取自模型中定义的相机的特定 mjModel.cam_ipd/fovy。当未启用立体模式时(由 mjvScene.stereo 决定),两只眼睛的相机数据在渲染期间会进行内部平均。

选择#

在许多应用中,我们需要点击一个点并确定该点/像素所属的 3D 对象。这是通过函数 mjv_select 完成的,它使用射线碰撞。射线碰撞功能是引擎级别的,不依赖于可视化器(实际上它也用于模拟测距仪传感器,独立于可视化),但 select 函数是在可视化器中实现的,因为它需要有关相机和视口的信息。

函数 mjv_select 返回指定窗口坐标处的几何体索引,如果该坐标处没有几何体,则返回 -1。还会返回 3D 位置。有关如何使用此函数的示例,请参见代码示例 simulate.cc。在内部,mjv_select 调用引擎级函数 mj_ray,该函数又调用每个几何体的函数 mj_rayMeshmj_rayHfieldmju_rayGeom。用户可以通过直接调用这些函数来实现自定义选择机制。例如,在 VR 应用中,将手持控制器用作可以选择对象的“激光笔”是很有意义的。

扰动#

事实证明,交互式扰动在探索模型动力学以及探测闭环控制系统方面非常有用。用户可以通过将 mjData.qfrc_appliedmjData.xfrc_applied 设置为适当的力(分别在广义坐标和笛卡尔坐标中)来自由实现任何他们选择的扰动机制。

在 MuJoCo 1.40 版之前,用户代码必须维护一个对象集合才能实现扰动。所有这些对象现在都分组到数据结构 mjvPerturb 中。其用法在 simulate.cc 中进行了说明。其思想是选择一个感兴趣的 MuJoCo 物体,并为该物体提供一个参考姿态(即 3D 位置和四元数方向)。这些存储在 mjPerturb.refpos/quat 中。函数 mjv_movePerturb 是一个鼠标挂钩,用于通过鼠标控制参考姿态。函数 mjv_initPerturb 用于在扰动开始时将参考姿态设置为等于所选物体的姿态,以避免跳跃。

然后,这个扰动对象可用于直接移动所选物体(当仿真暂停或所选物体是 mocap 物体时),或向物体施加力和力矩。这是通过函数 mjv_applyPerturbPosemjv_applyPerturbForce 分别完成的。后一个函数将外部扰动力写入所选物体的 mjData.xfrc_applied。但是,它不会清除其余物体的 mjData.xfrc_applied,因此建议在用户代码中清除它,以防所选物体发生变化而留下先前时间步的扰动力。如果有多个设备可以施加扰动,或者用户代码需要从其他来源添加扰动,用户必须实现必要的逻辑,以便只有所需的扰动存在于 mjData.xfrc_applied 中,并且任何旧的扰动都被清除。

除了影响仿真,扰动对象还被抽象可视化器识别并可以被渲染。这是通过添加一个视觉字符串来表示位置差异,以及一个旋转的立方体来表示所选物体的参考方向来完成的。当 mjvOption 中相应的可视化标志启用时,扰动力本身也可以被渲染。

场景更新#

最后,我们将上述所有元素整合在一起,解释 mjvScene 在传递到 OpenGL 渲染阶段之前是如何更新的。这可以通过在每一帧调用一次函数 mjv_updateScene 来完成。mjvCamera 和 mjvPerturb 是此函数的参数,或者它们可以是 NULL 指针,在这种情况下,相应的功能将被禁用。在 VR 应用中,mjvScene.camera[n] (n=0,1) 的参数也必须在每一帧设置;这是由用户代码在 mjv_updateScene 之外完成的。函数 mjv_updateScene 检查 mjModel 和 mjData,构造所有需要渲染的几何体(根据指定的可视化选项),并用 mjvGeom 对象填充数组 mjvScene.geom。请注意,mjvGeom 是一个抽象几何体,与 mjModel 和 mjData 中的仿真几何体并非一一对应。特别是,mjvGeom 包含几何体姿态、缩放、形状(mjModel 中的基本体或网格索引)、材质属性、纹理(mjModel 中的索引)、标签以及指定渲染方式所需的所有其他内容。mjvScene 还包含最多八个从模型复制的 OpenGL 光源,以及一个在存在时位于光源位置 0 的头灯。

上述过程是最常见的方法,它在每一帧更新整个场景。此外,我们提供两个函数用于更精细的控制。mjv_updateCamera 仅更新相机(即将抽象的 mjvCamera 映射到低级的 mjvGLCamera),但不触及几何体或光源。当用户快速移动相机但仿真状态未改变时,这很有用——在这种情况下,重新创建几何体和光源列表是没有意义的。

通过操作抽象几何体列表可以实现更高级的渲染效果。例如,用户可以在列表末尾添加自定义几何体。有时,希望渲染一系列仿真状态(即轨迹),而不仅仅是当前状态。为此,我们提供了函数 mjv_addGeoms,它将与当前仿真状态相对应的几何体添加到 mjvScene 中已有的列表中。它不会改变光源列表,因为光照是累加的,有太多光源会使场景过亮。重要的是,用户可以通过枚举类型 mjtCatBit 的位掩码选择将添加哪些几何体类别

mjCAT_STATIC

这会选择属于世界物体(物体 id 为 0)的 MuJoCo 几何体和站点。

mjCAT_DYNAMIC

这会选择属于世界物体以外的其他物体的 MuJoCo 几何体和站点。

mjCAT_DECOR

这会选择装饰性元素,如力箭头、自动生成的骨架、等效惯性盒以及由抽象可视化器添加且不对应于模型中定义的 MuJoCo 几何体和站点的任何其他元素。

mjCAT_ALL

这会选择以上所有类别。

主更新函数 mjv_updateScene 通常会使用 mjCAT_ALL 调用。它会清除几何体列表,并调用 mjv_addGeom 仅添加当前模型状态的几何体。如果我们要渲染一个轨迹,我们必须小心避免视觉混乱。因此,用 mjCAT_ALL 渲染其中一帧(通常是第一帧或最后一帧,取决于用例),而所有其他帧用 mjCAT_DYNAMIC 渲染是有意义的。由于静态/世界对象不移动,在每一帧中渲染它们只会减慢 GPU 并产生视觉混叠。至于装饰元素,可能存在我们想要渲染所有这些元素的情况——例如,为了可视化接触力随时间的演变。总之,mjvScene 的构造方式有很大的灵活性。我们为主要用例提供了自动化,但用户也可以根据需要进行编程更改。

虚拟现实#

在桌面应用中,使用抽象的 mjvCamera 允许直观的鼠标控制,然后自动将其映射到用于渲染的 mjvGLCamera 是很方便的。在 VR 应用中,情况则大不相同。在这种情况下,用户的头部/眼睛以及投影表面正在被跟踪,因此在房间中具有物理存在。如果用户可以移动任何东西(通过鼠标或其他输入设备),那就是模型相对于房间的位置、方向和缩放。这称为模型变换,并在 mjvScene 中表示。函数 mjv_moveModel 是一个鼠标挂钩,用于控制此变换。在更新期间使用抽象的 mjvCamera 时,模型变换会自动禁用,方法是设置标志 mjvScene.enabletransform = 0,而不是清除实际参数。这样,用户可以在 VR 和桌面相机模式之间切换,而不会丢失模型变换参数。

既然我们引入了两个空间,即模型空间和房间空间,我们需要在它们之间进行映射,并澄清哪些空间量是相对于哪个空间坐标系定义的。仿真器可访问的所有内容都存在于模型空间中。房间空间只能由可视化器访问。在房间空间中定义的唯一量是 mjvGLCamera 参数。函数 mjv_room2modelmjv_model2roommjv_cameraInModelmjv_cameraInRoom 执行必要的变换,并且是 VR 应用所必需的。

我们现在概述一下在 VR 应用中将头部跟踪连接到 MuJoCo 可视化器的过程。一个说明这一点的代码示例将很快发布。我们假设一个跟踪设备实时提供两只眼睛的位置(通常通过跟踪头部的位置和方向并假设一个用户特定的瞳孔间距生成),以及相机的前向和向上方向。我们直接将这些数据复制到两个 mjvGLCamera 中,它们位于 mjvScene.camera[n],其中 n=0 是左眼,n=1 是右眼。请注意,前向方向垂直于投影表面,不一定与注视方向对齐;实际上,注视方向是未知的(除非我们还有一个眼动跟踪设备),并且不影响渲染。

我们还必须设置 mjvGLCamera 视锥体。如何做到这一点取决于 VR 系统的性质。对于头戴式显示器,如 Oculus Rift 和 HTC Vive,投影表面随头部移动,因此视锥体是固定的,并由 SDK 提供。在这种情况下,我们只需将其复制到 mjvGLCamera 中,平均左右边缘以计算 frustum_center 参数。或者,投影表面可以是房间中固定的显示器(zSpace 系统就是这种情况)。对于这样的系统,我们必须在每一帧计算视锥体,通过考虑显示器和眼睛/相机之间的空间关系。这假设显示器也被跟踪。这里的自然方法是将显示器定义为房间坐标系的中心,并相对于它跟踪头部。在 zSpace 系统中,这是通过将运动捕捉相机嵌入显示器本身来完成的。

除了跟踪头部和使用正确的透视投影外,VR 应用通常还涉及手持空间控制器,这些控制器必须映射到模拟对象的运动或以其他方式与仿真交互。这些控制器的姿态由运动捕捉系统在房间空间中记录。我们提供的变换函数(特别是 mjv_room2model)可用于映射到模型空间。一旦我们在模型空间中获得了控制器的姿态,我们就可以使用 MuJoCo mocap 物体(在模型中定义)将控制器插入到仿真中。这正是 mocap 物体被引入 MuJoCo 的原因。从物理学的角度来看,这些物体被视为固定的,但期望用户在每个仿真步骤中以编程方式移动它们。它们可以通过接触与仿真交互,或者更好的是,通过软等式约束与常规物体交互,而常规物体又会产生接触。后一种方法在论坛上提供的 MPL 模型中有所说明。它提供了有效的动态滤波,并避免了涉及行为像无限重物体的接触(固定物体就是这样)。请注意,mocap 物体随时间变化的位置和方向存储在 mjData.mocap_pos/quat 中,而不是存储在 mjModel 中。这是因为 mjModel 应该保持不变。存储在 mjModel 中的固定 mocap 物体姿态仅在初始化和重置时使用,此时用户代码还没有机会更新 mjData.mocap_pos/quat。

OpenGL 渲染#

此阶段接收在抽象可视化阶段填充的 mjvScene 数据结构,并将其渲染出来。它还提供基本的 2D 绘图和帧缓冲区访问,因此大多数应用程序不需要直接调用 OpenGL。

上下文和 GPU 资源#

渲染过程的第一步是创建模型特定的 GPU 上下文 mjrContext。这是通过首先使用函数 mjr_defaultContext 清除数据结构,然后调用函数 mjr_makeContext 来完成的。这在前面已经说明过;相关代码是

mjModel* m;
mjrContext con;

// clear mjrContext only once before first use
mjr_defaultContext(&con);

// create window with OpenGL context, make it current
GLFWwindow* window = glfwCreateWindow(1200, 900, "Demo", NULL, NULL);
glfwMakeContextCurrent(window);

// ... load MuJoCo model

// make model-specific mjrContext
mjr_makeContext(m, &con, mjFONTSCALE_100);

// ... load another MuJoCo model

// make mjrContext for new model (old context freed automatically)
mjr_makeContext(m, &con, mjFONTSCALE_100);

// free context when done
mjr_freeContext(&con);

mjrContext 与 OpenGL 上下文有什么关系?OpenGL 上下文是使应用程序能够与视频驱动程序通信并发送渲染命令的东西。在调用 mjr_makeContext 之前,它必须存在并且在调用线程中是当前的。GLFW 和相关库提供了如上所示的必要函数。

mjrContext 特定于 MuJoCo。创建后,它包含由 mjr_makeContext 上传到 GPU 的所有资源的引用(在 OpenGL 中称为“名称”)。这些包括模型特定的资源,如网格和纹理,以及通用资源,如指定字体大小的字体位图、用于阴影映射和离屏渲染的帧缓冲对象以及相关的渲染缓冲。它还包含从 mjModel.vis 复制的 OpenGL 相关选项、自动发现的默认窗口帧缓冲的能力,以及当前活动的渲染缓冲区;请参见下面的缓冲区。请注意,尽管 MuJoCo 使用固定功能 OpenGL,但它避免了立即模式渲染,而是预先将所有资源上传到 GPU。这使其效率与现代着色器相当,甚至可能更高,因为固定功能 OpenGL 现在是通过由视频驱动程序开发人员编写并经过大量优化的内部着色器来实现的。

mjrContext 的大多数字段在调用 mjr_makeContext 后保持不变。唯一的例外是 mjrContext.currentBuffer,它在活动缓冲区更改时会更改。某些 GPU 资源也可能更改,因为用户可以使用函数 mjr_uploadTexturemjr_uploadMeshmjr_uploadHField 上传修改后的资源。这可用于实现动态效果,例如将视频馈送插入渲染中,或调制地形图。此类修改会影响驻留在 GPU 上的资源,但它们的 OpenGL 名称被重用,因此更改在 mjrContext 中实际上不可见。

用户**绝不**应该直接对 mjrContext 进行更改。MuJoCo 的渲染器假定只有它才能管理 mjrContext。事实上,这种对象通常是不透明的,其内部结构不会向用户公开。我们之所以公开它,是因为 MuJoCo 采用开放式设计,也因为用户可能希望将自己的 OpenGL 代码与 MuJoCo 的渲染器交错使用,在这种情况下,他们可能需要对 mjrContext 的某些字段进行只读访问。例如,在 VR 应用中,用户需要从 MuJoCo 的离屏缓冲区 blit 到 VR SDK 提供的纹理。

当加载不同的 MuJoCo 模型时,必须再次调用 mjr_makeContext。还有一个函数 mjr_freeContext,它释放 GPU 资源,同时保留初始化和能力标志。当应用程序即将退出时,应调用此函数。它在 mjr_makeContext 内部自动调用,因此在加载不同模型时无需直接调用它,尽管这样做也不是错误。在渲染开始前必须调用一次函数 mjr_defaultContext,以清除为数据结构 mjrContext 分配的内存。如果在调用 mjr_makeContext 之后调用它,它将擦除任何记录表明 GPU 资源已分配但未释放这些资源,所以不要这样做。

渲染缓冲区#

除了默认的窗口帧缓冲区,OpenGL 还可以支持无限的帧缓冲区对象 (FBO) 用于自定义渲染。在 MuJoCo 中,我们为两个帧缓冲区提供系统支持:默认的窗口帧缓冲区和一个离屏帧缓冲区。它们由枚举类型 mjtFramebuffer 中的常量引用,即 mjFB_WINDOW 和 mjFB_OFFSCREEN。在任何时候,这两个缓冲区中的一个对于 MuJoCo 渲染是活动的,这意味着所有后续命令都指向它。mjrContext 中还引用了另外两个帧缓冲区对象,用于阴影映射和解析多样本缓冲区,但这些是内部使用的,用户不应尝试直接访问它们。

活动缓冲区通过函数 mjr_setBuffer 设置。这将设置 mjrContext.activeBuffer 的值并相应地配置 OpenGL 状态。当调用 mjr_makeContext 时,它内部调用 mjr_setBuffer 并以 mjFB_WINDOW 为参数,以便默认情况下在窗口缓冲区中开始渲染。如果指定的缓冲区不存在,mjr_setBuffer 会自动默认为另一个缓冲区(请注意,在 Linux 上使用无头渲染时,可能没有窗口帧缓冲区)。

从 OpenGL 的角度来看,窗口帧缓冲区和离屏帧缓冲区之间存在重要差异,这些差异会影响 MuJoCo 用户与渲染器的交互方式。窗口帧缓冲区由操作系统创建和管理,而不是由 OpenGL。因此,分辨率、双缓冲、四缓冲立体、多样本、垂直同步等属性是在 OpenGL 之外设置的;在我们的代码示例中,这是通过 GLFW 调用完成的。OpenGL 能做的只是检测这些属性;我们在 mjr_makeContext 中这样做,并将结果记录在 mjrContext 的各种窗口能力字段中。这就是为什么这些属性不属于 MuJoCo 模型的原因;它们是特定于会话/软件的,而不是特定于模型的。相反,离屏帧缓冲区完全由 OpenGL 管理,因此我们可以使用我们想要的任何属性创建该缓冲区,即使用 mjModel.vis 中指定的分辨率和多样本属性。

用户可以直接访问两个缓冲区中的像素。这是通过函数 mjr_readPixelsmjr_drawPixelsmjr_blitBuffer 完成的。读/写将像素从/到活动缓冲区传输到/从 CPU。Blit 在 GPU 上的两个缓冲区之间传输像素,因此速度快得多。方向是从活动缓冲区到非活动缓冲区。请注意,mjr_blitBuffer 具有可以具有不同大小的源和目标视口,从而允许在此过程中缩放图像。

绘制像素#

主要的渲染函数是 mjr_render。它的参数是用于渲染的矩形视口、由抽象可视化器填充的 mjvScene,以及由 mjr_makeContext 创建的 mjrContext。视口可以是整个活动缓冲区,也可以是其中的一部分用于自定义效果。对应于整个缓冲区的视口可以通过函数 mjr_maxViewport 获得。请注意,虽然离屏缓冲区大小不变,但窗口缓冲区大小在用户调整或最大化窗口时会改变。因此,用户代码不应假设固定的视口大小。在代码示例 simulate.cc 中,我们使用一个在窗口大小改变时触发的回调,而在 basic.cc 中,我们只是在每次渲染时检查窗口大小。在某些缩放显示器上(似乎只在 OSX 上),窗口大小和帧缓冲区大小可能不同。因此,如果您使用 GLFW 函数获取大小,请使用 glfwGetFramebuferSize 而不是 glfwGetWindowSize。另一方面,鼠标坐标由操作系统以窗口单位而不是帧缓冲区单位返回;因此,前面讨论的鼠标交互函数应使用 glfwGetWindowSize 来获取标准化鼠标位移数据所需的窗口高度。

mjr_render 渲染来自列表 mjvScene.geom 的所有 mjvGeom。抽象可视化选项 mjvOption 在这里不再相关;它们由 mjv_updateScene 用于确定要添加哪些几何体,而就 mjr_render 而言,这些选项已经“烘焙”进去了。然而,还有另一组嵌入在 mjvScene 中的渲染选项,这些选项会影响 OpenGL 渲染过程。数组 mjvScene.flags 包含由枚举类型 mjtRndFlag 索引的标志,包括启用和禁用线框模式、阴影、反射、天空盒和雾的选项。阴影和反射涉及额外的渲染通道。MuJoCo 的渲染器非常高效,但根据模型复杂度和可用的 GPU,在某些情况下可能需要禁用这些效果中的一个或两个。

参数 mjvScene.stereo 决定了立体模式。可能的值由枚举类型 mjtStereo 给出,如下所示

mjSTEREO_NONE

禁用立体渲染。使用 mjvScene 中两个 OpenGL 相机的平均值。请注意,渲染器始终期望两个相机都已正确定义,即使不使用立体模式。

mjSTEREO_QUADBUFFERED

此模式仅在活动缓冲区是窗口,且窗口支持四缓冲 OpenGL 时才有效。这需要专业的显卡。代码示例 simulate.cc 尝试打开这样一个窗口。在此模式下,当窗口是双缓冲时,MuJoCo 的渲染器使用 GL_BACK_LEFT 和 GL_BACK_RIGHT 缓冲区来渲染两个视图(由 mjvScene 中的两个 OpenGL 相机决定),否则使用 GL_FRONT_LEFT 和 GL_FRONT_RIGHT。如果窗口不支持四缓冲 OpenGL 或活动缓冲区是离屏缓冲区,渲染器会恢复到下面描述的并排模式。

mjSTEREO_SIDEBYSIDE

这种立体模式不需要特殊硬件,并且始终可用。提供给 mjr_render 的视口被分成两个并排的相等矩形。左视图在左侧渲染,右视图在右侧渲染。原则上,用户可以在普通显示器上交叉眼睛看立体图像,但这里的目标是在立体设备中显示它。大多数头戴式显示器都支持这种立体模式。

除了主要的 mjr_render 函数外,我们还提供了几个用于“装饰”图像的函数。这些是 2D 渲染函数,包括 mjr_overlaymjr_textmjr_rectanglemjr_figure。用户可以使用自己的 OpenGL 代码绘制额外的装饰。这应该在 mjr_render 之后完成,因为 mjr_render 会清除视口。

我们还提供了函数 mjr_finishmjr_getError 用于与 GPU 的显式同步和 OpenGL 错误检查。它们只是在内部调用 glFinish 和 glGetError。这与上面提到的基本 2D 绘图函数一起,旨在提供足够的功能,以便大多数用户不需要编写 OpenGL 代码。当然,我们无法在所有情况下都实现这一点,除非为所有 OpenGL 提供包装器。