可视化#

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 相机不会改变。它等同于完全不指定抽象相机,即在下面解释的更新函数中将 NULL 指针传递给 mjvCamera。

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

选择#

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

函数 mjv_select 返回指定窗口坐标处的 geom 的索引,如果在这些坐标处没有 geom,则返回 -1。还会返回 3D 位置。有关如何使用此函数的示例,请参阅代码示例simulate.cc。在内部,mjv_select 调用引擎级函数mj_ray,该函数又调用每个 geom 的函数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,构建需要渲染的所有 geoms(根据指定的 visualization options),并用mjvGeom对象填充数组 mjvScene.geom。请注意,mjvGeom 是一个抽象 geom,它与 mjModel 和 mjData 中的仿真 geoms 不存在一一对应的关系。特别是,mjvGeom 包含 geom 位姿、缩放、形状(原始或 mjModel 中的网格索引)、材质属性、纹理(mjModel 中的索引)、标签以及指定如何进行渲染所需的其他一切。mjvScene 还包含最多八个从模型复制的 OpenGL 光源,以及存在时位于光源位置 0 的头灯。

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

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

mjCAT_STATIC

这选择属于世界主体(其主体 ID 为 0)的 MuJoCo geoms 和 sites。

mjCAT_DYNAMIC

这选择属于除世界主体之外的主体的 MuJoCo geoms 和 sites。

mjCAT_DECOR

这选择装饰元素,例如力箭头、自动生成的骨架、等效惯量框,以及抽象可视化器添加的任何其他元素,这些元素不对应于模型中定义的 MuJoCo geoms 和 sites。

mjCAT_ALL

这选择上述所有类别。

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

虚拟现实#

在桌面应用程序中,使用抽象 mjvCamera 以实现直观的鼠标控制,然后自动将其映射到用于渲染的 mjvGLCamera,这非常方便。在 VR 应用程序中情况则大不相同。在这种情况下,用户头部/眼睛以及投影表面都在被跟踪,因此在房间中具有物理存在。如果有什么可以由用户移动(通过鼠标或其他输入设备),那就是模型相对于房间的位置、方向和比例。这称为模型变换,并在 mjvScene 中表示。函数mjv_moveModel是用于控制此变换的鼠标钩子。在更新期间使用抽象 mjvCamera 时,模型变换会自动禁用,方法是将标志 mjvScene.enabletransform = 0 设置为 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 主体(在模型中定义)将控制器插入仿真中。这正是 MuJoCo 引入 mocap 主体的原因。从物理学角度看,这些主体被视为固定的,但用户需要在每个仿真步骤中以编程方式移动它们。它们可以通过接触与仿真交互,或者更好的是,通过与常规主体建立软等效约束,从而实现接触。后一种方法在论坛上提供的 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 相关选项、自动发现的默认窗口帧缓冲区功能以及当前活动的渲染缓冲区;参见下面的buffers。请注意,尽管 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 函数获取大小,请使用 glfwGetFramebufferSize 而不是 glfwGetWindowSize。另一方面,鼠标坐标由操作系统以窗口单位而不是帧缓冲区单位返回;因此,前面讨论的鼠标交互函数应该使用 glfwGetWindowSize 获取窗口高度,以归一化鼠标位移数据。

mjr_render 渲染 mjvScene.geom 列表中的所有 mjvGeom。抽象可视化选项 mjvOption 在这里不再相关;它们由 mjv_updateScene 用于确定要添加哪些 geoms,并且就 mjr_render 而言,这些选项已经“烘焙”在 mjvScene 中。但是,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 函数提供包装器。