Unity 插件#
简介#
MuJoCo Unity 插件允许 Unity 编辑器和运行时使用 MuJoCo 物理引擎。用户可以导入 MJCF 文件并在编辑器中编辑模型。该插件在大多数方面依赖于 Unity——例如资源、游戏逻辑、模拟时间——但使用 MuJoCo 来决定物体的运动方式,从而让设计者能够访问 MuJoCo 的完整 API。
一个使用 MuJoCo Unity 插件的示例项目,以及一组入门教程,也作为一个独立的仓库提供。
安装说明#
插件目录包含一个 package.json 文件。Unity 的包管理器会识别此文件,并将插件的 C# 代码库导入到您的项目中。此外,Unity 还需要原生 MuJoCo 库,该库可以在相应的平台归档中找到。如果您只想使用插件而不进行开发,您应该使用仓库中特定版本的稳定提交,这些提交由 git 标签标识。使用 git 检出克隆仓库的相关版本(git checkout 3.X.Y,其中 X 和 Y 指定引擎版本)。直接使用仓库的 main 分支可能与最新发布的 MuJoCo 二进制文件不兼容。
在 Unity 2020.2 及更高版本中,包管理器会在导入包时查找原生库文件并将其复制到包目录。或者,您可以手动将原生库复制到包目录并重命名,请参阅下面的平台特定说明。该库也可以复制到项目 Assets 目录下的任何位置。
macOS#
在使用原生库之前,需要至少运行一次 MuJoCo 应用程序,以将该库注册为受信任的二进制文件。然后,从 /Applications/MuJoCo.app/Contents/Frameworks/mujoco.framework/Versions/Current/libmujoco.3.4.0.dylib 复制动态库文件(可以通过浏览 MuJoCo.app 的内容找到),并将其重命名为 mujoco.dylib。
Linux#
将 tar.gz 归档文件解压到 ~/.mujoco。然后从 ~/.mujoco/mujoco-3.4.0/lib/libmujoco.so.3.4.0 复制动态库,并将其重命名为 libmujoco.so。
Windows#
将 zip 归档文件解压到用户目录下一个名为 MuJoCo 的文件夹中,并复制文件 MuJoCo\bin\mujoco.dll。
使用插件#
导入器#
导入器从编辑器的“Asset”菜单调用:点击“Import MuJoCo Scene”并选择包含模型 MJCF 规范的 XML 文件。
鼠标弹簧#
当选定的游戏对象具有 MjBody 组件时,可以通过在场景视图中按住 Control 键并左键拖动,向该物体施加一个朝向鼠标光标的弹簧力。弹簧力原点的 3D 位置是通过将鼠标位置投影到由相机 X 方向和世界 Y 方向定义的平面上找到的。添加 Shift 键会将投影平面更改为与世界的 X 和 Z 轴平行。
给 Unity 用户的提示#
如果遇到任何编译或运行时错误,系统状态将是未定义的。因此,我们建议在控制台窗口中打开“Error Pause”。
在 PhysX 中,每个
Rigidbody都是一个“自由体”。相比之下,MuJoCo 需要为移动性明确指定关节。为方便起见,我们提供了一个上下文菜单,用于“解放”一个世界 geom(即一个没有任何MjBody祖先的MjGeom组件),方法是为其添加一个父MjBody和一个兄弟MjFreeJoint。该插件不支持没有物理存在的碰撞检测,因此没有内置的触发器碰撞体(trigger colliders)概念。可以通过添加一个触摸传感器并读取其
SensorReading值(该值将对应于法向力,请参阅触摸 传感器 文档 <sensor-touch>)来读取接触力的存在与否。
设计原则#
插件的设计提供了 MJCF 元素和 Unity 组件之间的一对一映射。为了使用 MuJoCo 模拟 Unity 场景(例如,当用户在编辑器中点击“播放”按钮时),插件会:
扫描场景中的 GameObject 层级结构,查找 MuJoCo 组件。
创建一个 MJCF 描述并将其传递给 MuJoCo 的编译器。
通过 MuJoCo 数据结构中相应的索引将每个组件绑定到 MuJoCo 运行时。该索引用于在模拟过程中更新 Unity 的变换。
这一设计原则有几个影响
Unity 组件的大多数字段直接对应于 MJCF 属性。因此,用户可以参考 MuJoCo 文档了解不同值的语义细节。
GameObject 层级结构中 MuJoCo 组件的布局决定了最终 MuJoCo 模型的布局。因此,我们采用一条设计规则:每个游戏对象最多只能有一个 MuJoCo 组件。
我们依赖 Unity 进行空间配置,这需要对向量分量进行坐标轴变换(swizzled),因为 Unity 使用 Y 轴作为垂直轴的左手坐标系,而 MuJoCo 使用 Z 轴作为垂直轴的右手坐标系。
Unity 的变换缩放会影响整个游戏对象子树的位置、方向和缩放。然而,MuJoCo 不支持倾斜的圆柱体和胶囊体的碰撞(倾斜的球体通过椭球体基元得到支持)。geom 和 site 的 Gizmo 会忽略这种倾斜(类似于 PhysX 碰撞体),并且总是会显示基元形状在物理引擎中的样子。
在运行时,更改组件字段的值不会触发场景重建,因此不会立即对物理产生影响。但是,新值将在下一次场景重建时加载。
在可能的情况下,我们都遵循 Unity 的方式:重力从 Unity 的物理设置中读取,模拟步长从 Unity 的时间管理器中的 Fixed Timestep 读取。所有外观方面(例如,网格、材质和纹理)都由 Unity 的资源管理器处理,RGBA 规范则使用材质资源来完成。
实现说明#
导入器工作流程#
当用户选择一个 MJCF 文件时,导入器首先在 MuJoCo 中加载该文件,将其保存到一个临时位置,然后处理生成的已保存文件。这有几个效果:
它验证了 MJCF——我们保证保存的 MJCF 与模式(schema)相匹配。
它验证资源(材质、网格、纹理)并将这些资源导入到 Unity 中,同时为 geom 的 RGBA 规范创建新的材质资源。
它允许导入器处理 <include> 元素,而无需复制 MuJoCo 的文件系统工作流程。
在 Unity 中,没有与 MJCF 的“级联”<default> 子句等效的功能。因此,Unity 中的组件反映了相应元素在应用了所有相关的默认类之后的状态,而原始 MJCF 中的类结构则被丢弃。
MuJoCo 场景#
当创建 MuJoCo 场景时,MjScene 组件首先扫描场景中所有 MjComponent 的实例。每个组件使用 Unity 场景的空间结构创建自己的 MJCF 元素,以描述模型的初始参考姿态(在 MuJoCo 中称为 qpos0)。MjScene 根据相应游戏对象的层级结构组合这些 XML 元素,并创建物理模型的单个 MJCF 描述。然后它创建运行时结构体 mjModel 和 mjData,并通过识别每个组件的唯一索引将其绑定到运行时。
在运行时,MjScene.FixedUpdate() 调用 mj_step,然后根据绑定时识别的索引 MjComponent.MujocoId 来同步每个游戏对象的状态。当应用程序启动时(例如,当用户点击“播放”),一个 MjScene 组件会被自动添加,当且仅当场景中包含任何 MuJoCo 组件时。如果您的应用程序的初始化阶段涉及在添加游戏对象和组件的同时进行物理演算,您可以在初始化阶段结束后调用 MjScene.CreateScene()。
场景重建通过以下方式保持物理和状态的连续性:
缓存关节的位置和速度。
MuJoCo 的状态被重置(到
qpos0),并同步 Unity 的变换。生成一个新的 XML,创建一个模型,该模型对于持久存在的关节具有与前一个模型相同的
qpos0。从缓存中设置 MuJoCo 状态(对于持久存在的关节),并同步 Unity 变换。
MuJoCo 具有动态场景编辑功能(通过 mjSpec),但是,Unity 插件目前尚不支持此功能。因此,添加和移除 MuJoCo 组件会导致完整的场景重建。这对于大型模型或者如果频繁发生,可能会非常耗时。我们打算在未来版本的插件中解除这个性能限制。
全局设置#
“一个元素对应一个组件”原则的一个例外是全局设置组件。该组件负责所有包含在 MJCF 的固定大小、单例、全局元素中的配置选项。目前它包含对应于 <option> 和 <size> 元素的信息,将来如果/当 <compiler> 元素中的字段与 Unity 插件相关时,它也将用于该元素。
在应用程序运行时调用导入器#
导入器由 MjImporterWithAssets 类实现,它是 MjcfImporter 的子类。这个父类接收一个 MJCF 字符串并生成组件的层级结构。它可以在播放时调用(不涉及编辑器功能),并且不调用任何 MuJoCo 库的函数。这在程序化生成 MuJoCo 模型(例如,通过某些进化过程)和/或当导入 MJCF 仅用于转换(例如,转换为 PhysX 或 URDF)时非常有用。由于它无法与 Unity 的 AssetManager(这是编辑器的一个功能)交互,该类的功能受到限制。具体来说:
它忽略所有资源(包括碰撞网格)。
它忽略视觉效果(包括 RGBA 规范)。
MuJoCo 传感器组件#
MuJoCo 定义了许多传感器,我们担心为每个传感器创建一个单独的 MjComponent 类会导致大量代码重复。因此,我们根据被测量的对象类型(执行器/物体/geom/关节/site)和测量数据的类型(标量/向量/四元数)创建了类。
这是一个将类型映射到传感器的表格:
MuJoCo 对象类型 |
数据类型 |
传感器名称 |
执行器 |
标量 |
|
物体 |
向量 |
|
物体 |
四元数 |
|
几何体 |
向量 |
|
几何体 |
四元数 |
|
关节 |
标量 |
|
Site |
标量 |
|
Site |
向量 |
|
Site |
四元数 |
|
这是反向的同一表格,将传感器映射到类:
传感器名称 |
插件类 |
|---|---|
|
SiteVector |
|
ActuatorScalar |
|
ActuatorScalar |
|
ActuatorScalar |
|
SiteVector |
|
*Vector(取决于帧类型) |
|
*Vector(取决于帧类型) |
|
*Vector(取决于帧类型) |
|
*Vector(取决于帧类型) |
|
*Vector(取决于帧类型) |
|
*Quaternion(取决于帧类型) |
|
*Vector(取决于帧类型) |
|
*Vector(取决于帧类型) |
|
*Vector(取决于帧类型) |
|
SiteVector |
|
JointScalar |
|
JointScalar |
|
JointScalar |
|
JointScalar |
|
JointScalar |
|
SiteVector |
|
BodyVector |
|
BodyVector |
|
BodyVector |
|
SiteVector |
|
SiteScalar |
|
SiteVector |
以下传感器尚未实现:
tendonpostendonvelballquatballangveltendonlimitpostendonlimitveltendonlimitfrcuser网格形状#
该插件允许使用任意 Unity 网格进行 MuJoCo 碰撞。在模型编译时,MuJoCo 调用 qhull 来创建网格的凸包,并将其用于碰撞。目前计算出的凸包在 Unity 中不可见,但我们打算在未来版本中将其暴露出来。
高度场#
MuJoCo 的 hfield 在 Unity 中通过地形(terrain)游戏对象表示。这允许使用 Unity 中可用的地形编辑工具来生成与 MuJoCo 碰撞的形状。在 Unity geom 组件中选择 hfield 类型时,右键上下文菜单提供了将相应的 Unity 地形添加到场景的实用工具。来自地形的数据会与模拟动态保持同步。
MuJoCo 插件#
当前版本的 Unity 包不支持加载使用MuJoCo 插件的 MJCF 场景,例如弹性插件。在即将发布的版本中,将添加实现此功能的基本能力。
与外部进程的交互#
Roboti 的用于 Unity 的 MuJoCo 插件在一个外部 Python 进程中进行模拟步进,并仅使用 Unity 进行渲染。相比之下,我们的插件依赖 Unity 来进行模拟步进。应该可以在外部进程“驱动”模拟的同时使用我们的插件,例如通过设置 qpos,调用 mj_kinematics,同步变换,然后使用 Unity 进行渲染或计算游戏逻辑。为了与外部进程建立通信,您可以使用 Unity 的 ML-Agents 包。