Python#

MuJoCo 提供原生 Python 绑定,这些绑定是使用 pybind11 用 C++ 开发的。Python API 与底层的 C API 保持一致。这导致了一些非 Pythonic 的代码结构(例如函数参数的顺序),但其好处是 API 文档 同时适用于这两种语言。

Python 绑定以 mujoco 包的形式在 PyPI 上发布。这些是低级绑定,旨在尽可能直接访问 MuJoCo 库。然而,为了提供开发者在典型 Python 库中期望的 API 和语义,这些绑定在许多地方特意偏离了原始 MuJoCo API,这些地方在本页中都有说明。

Google DeepMind 的 dm_control 强化学习库依赖于 mujoco 包,并继续由 Google DeepMind 提供支持。对于依赖于 1.0.0 之前版本的 dm_control 的代码,请查阅迁移指南

对于 mujoco-py 用户,我们下面提供了迁移说明

教程 notebook#

使用 Python 绑定的 MuJoCo 教程可在此处获取:mjcolab

安装#

安装此包的推荐方法是通过 PyPI

pip install mujoco

软件包中提供了一份 MuJoCo 库的副本,因此**无需**单独下载或安装。

交互式查看器#

Python 包的 mujoco.viewer 模块中提供了一个交互式 GUI 查看器。它基于与 MuJoCo 二进制发布版附带的 simulate 应用程序相同的代码库。支持三种不同的用例

独立应用程序#

  • python -m mujoco.viewer 启动一个空的可视化会话,可以通过拖放加载模型。

  • python -m mujoco.viewer --mjcf=/path/to/some/mjcf.xml 为指定的模型文件启动可视化会话。

托管查看器#

从 Python 程序/脚本调用,通过函数 viewer.launch。此函数会*阻塞用户代码*以支持精确的物理循环计时。当用户代码实现为 引擎插件物理回调 并在 MuJoCo 执行 mj_step 期间被调用时,应使用此模式。

  • viewer.launch() 启动一个空的可视化会话,可以通过拖放加载模型。

  • viewer.launch(model) 为给定的 mjModel 启动可视化会话,其中可视化器内部创建自己的 mjData 实例。

  • viewer.launch(model, data) 与上述相同,只是可视化器直接在给定的 mjData 实例上操作 – 退出时 data 对象将被修改。

被动查看器#

通过调用 viewer.launch_passive(model, data)。此函数*不阻塞*,允许用户代码继续执行。在此模式下,用户的脚本负责计时和推进物理状态,并且除非用户明确同步传入事件,否则鼠标拖动扰动将不起作用。

警告

在 MacOS 上,launch_passive 要求用户脚本通过特殊的 mjpython 启动器执行。mjpython 命令作为 mujoco 包的一部分安装,可以作为通常的 python 命令的直接替代品,并支持一组完全相同的命令行标志和参数。例如,可以通过 mjpython my_script.py 执行脚本,并通过 mjpython -m IPython 启动 IPython shell。

launch_passive 函数返回一个句柄,可用于与查看器交互。它具有以下属性

  • camoptpert 属性:分别对应于 mjvCameramjvOptionmjvPerturb 结构体。

  • lock():作为上下文管理器为查看器提供互斥锁。由于查看器在其自己的线程中运行,用户代码必须确保在修改任何物理或可视化状态之前持有查看器锁。这些状态包括传递给 launch_passivemjModelmjData 实例,以及查看器句柄的 camoptpert 属性。

  • sync():自上次调用 sync 以来,同步 mjModelmjData 和 GUI 用户输入之间的状态。为了允许用户脚本对 mjModelmjData 进行任意修改而无需持有查看器锁,被动查看器仅在 sync 调用期间访问或修改这些结构体。

    用户脚本必须调用 sync,以便查看器反映物理状态变化。sync 函数还将 GUI 中的用户输入传输回 mjOption(在 mjModel 中)和 mjData,包括启用/禁用标志、控制输入和鼠标扰动。

  • update_hfield(hfieldid):更新指定 hfieldid 处的高度场数据,以便后续渲染。

  • update_mesh(meshid):更新指定 meshid 处的网格数据,以便后续渲染。

  • update_texture(texid):更新指定 texid 处的纹理数据,以便后续渲染。

  • close():以编程方式关闭查看器窗口。此方法无需锁定即可安全调用。

  • is_running():如果查看器窗口正在运行,则返回 True;如果已关闭,则返回 False。此方法无需锁定即可安全调用。

  • user_scn:一个 mjvScene 对象,允许用户添加或更改渲染标志,并向渲染场景添加自定义可视化几何体。这与查看器内部用于渲染最终场景的 mjvScene 是分开的,并且完全由用户控制。用户脚本可以调用例如 mjv_initGeommjv_connectoruser_scn 添加可视化几何体,并且在下次调用 sync() 时,查看器会将这些几何体整合到未来的渲染图像中。类似地,用户脚本可以更改 user_scn.flags,这些更改将在下次调用 sync() 时生效。sync() 调用还会将通过 GUI 进行的渲染标志更改复制回 user_scn 以保持一致性。例如

    with mujoco.viewer.launch_passive(m, d, key_callback=key_callback) as viewer:
    
      # Enable wireframe rendering of the entire scene.
      viewer.user_scn.flags[mujoco.mjtRndFlag.mjRND_WIREFRAME] = 1
      viewer.sync()
    
      while viewer.is_running():
        ...
        # Step the physics.
        mujoco.mj_step(m, d)
    
        # Add a 3x3x3 grid of variously colored spheres to the middle of the scene.
        viewer.user_scn.ngeom = 0
        i = 0
        for x, y, z in itertools.product(*((range(-1, 2),) * 3)):
          mujoco.mjv_initGeom(
              viewer.user_scn.geoms[i],
              type=mujoco.mjtGeom.mjGEOM_SPHERE,
              size=[0.02, 0, 0],
              pos=0.1*np.array([x, y, z]),
              mat=np.eye(3).flatten(),
              rgba=0.5*np.array([x + 1, y + 1, z + 1, 2])
          )
          i += 1
        viewer.user_scn.ngeom = i
        viewer.sync()
        ...
    

查看器句柄也可以用作上下文管理器,它在退出时自动调用 close()。一个使用 launch_passive 的用户脚本的最小示例可能如下所示。(请注意,此示例是一个简单的说明性示例,**不**一定以正确的挂钟速率保持物理模拟运行。)

import time

import mujoco
import mujoco.viewer

m = mujoco.MjModel.from_xml_path('/path/to/mjcf.xml')
d = mujoco.MjData(m)

with mujoco.viewer.launch_passive(m, d) as viewer:
  # Close the viewer automatically after 30 wall-seconds.
  start = time.time()
  while viewer.is_running() and time.time() - start < 30:
    step_start = time.time()

    # mj_step can be replaced with code that also evaluates
    # a policy and applies a control signal before stepping the physics.
    mujoco.mj_step(m, d)

    # Example modification of a viewer option: toggle contact points every two seconds.
    with viewer.lock():
      viewer.opt.flags[mujoco.mjtVisFlag.mjVIS_CONTACTPOINT] = int(d.time % 2)

    # Pick up changes to the physics state, apply perturbations, update options from GUI.
    viewer.sync()

    # Rudimentary time keeping, will drift relative to wall clock.
    time_until_next_step = m.opt.timestep - (time.time() - step_start)
    if time_until_next_step > 0:
      time.sleep(time_until_next_step)

可选地,viewer.launch_passive 接受以下关键字参数。

  • key_callback:一个可调用对象,每当查看器窗口中发生键盘事件时就会被调用。这允许用户脚本对各种按键作出反应,例如,按下空格键时暂停或恢复运行循环。

    paused = False
    
    def key_callback(keycode):
      if chr(keycode) == ' ':
        nonlocal paused
        paused = not paused
    
    ...
    
    with mujoco.viewer.launch_passive(m, d, key_callback=key_callback) as viewer:
      while viewer.is_running():
        ...
        if not paused:
          mujoco.mj_step(m, d)
          viewer.sync()
        ...
    
  • show_left_uishow_right_ui:布尔参数,指示启动查看器时 UI 面板是否可见或隐藏。请注意,无论指定的值如何,用户仍可以在启动后通过按下 Tab 或 Shift+Tab 切换这些面板的可见性。

基本用法#

安装后,可以通过 import mujoco 导入软件包。结构体、函数、常量和枚举可以直接从顶层 mujoco 模块访问。

结构体#

绑定包括暴露 MuJoCo 数据结构的 Python 类。为了实现最大性能,这些类提供对 MuJoCo 使用的原始内存的访问,而无需复制或缓冲。这意味着某些 MuJoCo 函数(例如 mj_step)会*就地*更改字段的内容。因此,建议用户在需要时创建副本。例如,当记录物体的位置时,可以写 positions.append(data.body('my_body').xpos.copy())。如果没有 .copy(),列表将包含相同的元素,所有元素都指向最新的值。这同样适用于 NumPy 切片。例如,如果创建了局部变量 qpos_slice = data.qpos[3:8],然后调用 mj_stepqpos_slice 中的值将被更改。

为了符合 PEP 8 命名规范,结构体名称以大写字母开头,例如 mjData 在 Python 中变为 mujoco.MjData

除了 mjModel 之外的所有结构体都有 Python 构造函数。对于具有 mj_defaultFoo 样式初始化函数的结构体,Python 构造函数会自动调用默认初始化器,因此例如 mujoco.MjOption() 会创建一个新的 mjOption 实例,该实例已通过 mj_defaultOption 预先初始化。否则,Python 构造函数会对底层 C 结构体进行零初始化。

具有 mj_makeFoo 样式初始化函数的结构体在 Python 中具有相应的构造函数重载,例如 Python 中的 mujoco.MjvScene(model, maxgeom=10) 创建一个新的 mjvScene 实例,该实例使用 C 中的 mjv_makeScene(model, [新的 mjvScene 实例], 10) 初始化。当使用这种形式的初始化时,当 Python 对象被删除时,相应的释放函数 mj_freeFoo/mj_deleteFoo 会自动调用。用户无需手动释放资源。

mujoco.MjModel 类没有 Python 构造函数。相反,我们提供了三个静态工厂函数来创建新的 mjModel 实例:mujoco.MjModel.from_xml_stringmujoco.MjModel.from_xml_pathmujoco.MjModel.from_binary_path。第一个函数接受 XML 模型作为字符串,而后两个函数接受 XML 或 MJB 模型文件的路径。所有这三个函数都可选地接受一个 Python 字典,该字典在模型编译期间转换为 MuJoCo 虚拟文件系统

函数#

MuJoCo 函数作为同名的 Python 函数公开。与结构体不同,我们不尝试使函数名符合 PEP 8 规范,因为 MuJoCo 使用下划线和驼峰式命名。在大多数情况下,函数参数与 C 中完全相同,并且支持与 mujoco.h 中声明的名称相同的关键字参数。接受数组输入参数的 C 函数的 Python 绑定期望 NumPy 数组或可转换为 NumPy 数组的可迭代对象(例如列表)。输出参数(即 MuJoCo 期望将值写回调用者的数组参数)必须始终是可写的 NumPy 数组。

在 C API 中,接受动态大小数组作为输入的函数期望一个指向数组的指针参数以及一个指定数组大小的整数参数。在 Python 中,大小参数被省略,因为我们可以自动(事实上更安全地)从 NumPy 数组推断出来。调用这些函数时,按照它们在 mujoco.h 中出现的顺序传递除数组大小之外的所有参数,或者使用关键字参数。例如,mj_jac 在 Python 中应调用为 mujoco.mj_jac(m, d, jacp, jacr, point, body)

绑定在调用底层 MuJoCo 函数之前**释放 Python 全局解释器锁 (GIL)**。这允许一定程度的基于线程的并行性,但是用户应注意 GIL 仅在 MuJoCo C 函数本身执行期间释放,而在执行任何其他 Python 代码期间不释放。

注意

绑定提供附加功能的一个地方是顶层 mj_step 函数。由于它经常在循环中调用,我们添加了一个额外的 nstep 参数,指示底层 mj_step 应调用多少次。如果未指定,nstep 采用默认值 1。以下两个代码片段执行相同的计算,但第一个在后续物理步骤之间不获取 GIL

mj_step(model, data, nstep=20)
for _ in range(20):
  mj_step(model, data)

枚举和常量#

MuJoCo 枚举可作为 mujoco.mjtEnumType.ENUM_VALUE 使用,例如 mujoco.mjtObj.mjOBJ_SITE。MuJoCo 常量以相同的名称直接在 mujoco 模块下可用,例如 mujoco.mjVISSTRING

最小示例#

import mujoco

XML=r"""
<mujoco>
  <asset>
    <mesh file="gizmo.stl"/>
  </asset>
  <worldbody>
    <body>
      <freejoint/>
      <geom type="mesh" name="gizmo" mesh="gizmo"/>
    </body>
  </worldbody>
</mujoco>
"""

ASSETS=dict()
with open('/path/to/gizmo.stl', 'rb') as f:
  ASSETS['gizmo.stl'] = f.read()

model = mujoco.MjModel.from_xml_string(XML, ASSETS)
data = mujoco.MjData(model)
while data.time < 1:
  mujoco.mj_step(model, data)
  print(data.geom_xpos)

命名访问#

大多数精心设计的 MuJoCo 模型会为感兴趣的对象(关节、几何体、物体等)分配名称。当模型被编译为 mjModel 实例时,这些名称与用于索引各种数组成员的数字 ID 相关联。为了方便和代码可读性,Python 绑定在 MjModelMjData 上提供了“命名访问”API。结构体 mjModel 中的每个 name_fooadr 字段定义了一个名称类别 foo

对于每个名称类别 foomujoco.MjModelmujoco.MjData 对象提供一个方法 foo,该方法接受一个字符串参数,并返回给定名称的实体 foo 对应的所有数组的访问器对象。访问器对象包含与 mujoco.MjModelmujoco.MjData 的字段相对应的属性名称,但去掉了下划线之前的部分。此外,访问器对象还提供 idname 属性,它们可以分别用作 mj_name2idmj_id2name 的替代品。例如

  • m.geom('gizmo') 返回与名称为“gizmo”的几何体相关联的 MjModel 对象 m 中数组的访问器。

  • m.geom('gizmo').rgba 是长度为 4 的 NumPy 数组视图,指定了几何体的 RGBA 颜色。具体来说,它对应于 m.geom_rgba[4*i:4*i+4] 的一部分,其中 i = mujoco.mj_name2id(m, mujoco.mjtObj.mjOBJ_GEOM, 'gizmo')

  • m.geom('gizmo').idmujoco.mj_name2id(m, mujoco.mjtObj.mjOBJ_GEOM, 'gizmo') 返回的数字相同。

  • m.geom(i).name'gizmo',其中 i = mujoco.mj_name2id(m, mujoco.mjtObj.mjOBJ_GEOM, 'gizmo')

此外,Python API 为一些名称类别定义了一些别名,这些别名对应于定义该类别实体的 MJCF 模式中的 XML 元素名称。例如,m.joint('foo')m.jnt('foo') 相同。这些别名的完整列表如下所示。

关节的访问器与其他类别略有不同。一些 mjModelmjData 字段(大小为 nqnv)与自由度 (DoFs) 相关联,而不是与关节相关联。这是因为不同类型的关节具有不同数量的自由度。尽管如此,我们将这些字段与其相应的关节相关联,例如通过 d.joint('foo').qposd.joint('foo').qvel,但是这些数组的大小会因关节类型而异。

命名访问保证在模型的实体数量上是 O(1)。换句话说,按名称访问实体所需的时间不会随着模型中名称或实体数量的增加而增加。

为了完整起见,我们在此提供了 MuJoCo 中所有名称类别的完整列表,以及 Python API 中定义的相应别名。

  • body (物体)

  • jntjoint (关节)

  • geom (几何体)

  • site (位点)

  • camcamera (相机)

  • light (灯光)

  • mesh (网格)

  • skin (皮肤)

  • hfield (高度场)

  • textexture (纹理)

  • matmaterial (材质)

  • pair (对)

  • exclude (排除)

  • eqequality (相等性)

  • tendonten (肌腱)

  • actuator (致动器)

  • sensor (传感器)

  • numeric (数值)

  • text (文本)

  • tuple (元组)

  • keykeyframe (关键帧)

渲染#

MuJoCo 本身要求用户在调用任何 mjr_ 渲染例程之前设置一个可工作的 OpenGL 上下文。Python 绑定提供了一个基本类 mujoco.GLContext,可帮助用户为离屏渲染设置此类上下文。要创建上下文,请调用 ctx = mujoco.GLContext(max_width, max_height)。创建上下文后,必须在使用 MuJoCo 渲染函数之前将其设为当前上下文,您可以通过 ctx.make_current() 来实现。请注意,上下文在任何给定时间只能在一个线程上成为当前上下文,并且所有后续渲染调用都必须在同一线程上进行。

ctx 对象被删除时,上下文会自动释放,但在某些多线程场景中,可能需要显式释放底层的 OpenGL 上下文。为此,请调用 ctx.free(),此后用户有责任确保不再对该上下文进行任何渲染调用。

创建上下文后,用户可以按照 MuJoCo 的标准渲染流程进行,例如在可视化部分中记录的那样。

错误处理#

MuJoCo 通过 mju_error 机制报告不可恢复的错误,该机制会立即终止整个进程。用户可以通过 mju_user_error 回调安装自定义错误处理程序,但它也应终止进程,否则回调返回后 MuJoCo 的行为是未定义的。实际上,只需确保错误回调不返回*到 MuJoCo*,但允许使用 longjmp 跳过 MuJoCo 的调用栈返回到外部调用点。

Python 绑定利用 longjmp 将不可恢复的 MuJoCo 错误转换为 Python 异常 mujoco.FatalError,这些异常可以按照通常的 Python 方式捕获和处理。此外,它使用当前私有的 API 以线程本地的方式安装其错误回调,从而允许从多个线程并发调用 MuJoCo。

回调#

MuJoCo 允许用户安装自定义回调函数来修改其计算管线的某些部分。例如,mjcb_sensor 可用于实现自定义传感器,而 mjcb_control 可用于实现自定义执行器。回调通过 mujoco.h 中前缀为 mjcb_ 的函数指针公开。

对于每个回调 mjcb_foo,用户可以通过 mujoco.set_mjcb_foo(some_callable) 将其设置为 Python 可调用对象。要重置它,请调用 mujoco.set_mjcb_foo(None)。要检索当前安装的回调,请调用 mujoco.get_mjcb_foo()。(如果回调未通过 Python 绑定安装,**不应**使用 getter。)每次进入回调时,绑定会自动获取 GIL,并在重新进入 MuJoCo 之前释放它。这可能会导致严重的性能影响,因为回调在 MuJoCo 的计算管线中触发多次,可能不适合“生产”用例。但是,预期此功能对于原型设计复杂的模型将很有用。

或者,如果回调是在本地动态库中实现的,用户可以使用 ctypes 获取指向 C 函数指针的 Python 句柄,并将其传递给 mujoco.set_mjcb_foo。然后,绑定将检索底层函数指针,并将其直接分配给原始回调指针,并且每次进入回调时将**不**获取 GIL。

模型编辑#

模型编辑的 C API 在编程章节中有所记录。此功能在 Python API 中有所体现,并增加了几个便利方法。以下是最小的使用示例,更多示例可在模型编辑 colab notebook 中找到。

import mujoco
spec = mujoco.MjSpec()
spec.modelname = "my model"
body = spec.worldbody.add_body(
    pos=[1, 2, 3],
    quat=[0, 1, 0, 0],
)
geom = body.add_geom(
    name='my_geom',
    type=mujoco.mjtGeom.mjGEOM_SPHERE,
    size=[1, 0, 0],
    rgba=[1, 0, 0, 1],
)
...
model = spec.compile()

构造#

MjSpec 对象包装了 mjSpec 结构体,可以通过三种方式构造

  1. 创建一个空 spec:spec = mujoco.MjSpec()

  2. 从 XML 字符串加载 spec:spec = mujoco.MjSpec.from_string(xml_string)

  3. 从 XML 文件加载 spec:spec = mujoco.MjSpec.from_file(file_path)

注意 from_string()from_file() 方法只能在构造时调用。

资产#

所有这三种方法都接受一个可选参数 assets,用于解析 XML 中的资产引用。此参数是一个字典,将资产名称(字符串)映射到资产数据(字节),如下所示

assets = {'image.png': b'image_data'}
spec = mujoco.MjSpec.from_string(xml_referencing_image_png, assets=assets)
model = spec.compile()

保存到 XML#

编译后的 MjSpec 对象可以使用 to_xml() 方法保存到 XML 字符串

print(spec.to_xml())
<mujoco model="my model">
  <compiler angle="radian"/>

  <worldbody>
    <body pos="1 2 3" quat="0 1 0 0">
      <geom name="my_geom" size="1" rgba="1 0 0 1"/>
    </body>
  </worldbody>
</mujoco>

附加#

可以通过使用附件来组合多个 specs。以下选项是可能的

  • 将子 spec 中的 body 附加到父 spec 中的 frame:body.attach_body(body, prefix, suffix),返回附加 body 的引用,该引用应与用作输入的 body 相同。

  • 将子 spec 中的 frame 附加到父 spec 中的 body:body.attach_frame(frame, prefix, suffix),返回附加 frame 的引用,该引用应与用作输入的 frame 相同。

  • 将子 spec 附加到父 spec 中的 site:parent_spec.attach(child_spec, site=site_name_or_obj),返回一个 frame 的引用,该 frame 是转换为 frame 的附加 worldbody。该 site 必须属于子 spec。前缀和后缀也可以指定为关键字参数。

  • 将子 spec 附加到父 spec 中的 frame:parent_spec.attach(child_spec, frame=frame_name_or_obj),返回一个 frame 的引用,该 frame 是转换为 frame 的附加 worldbody。该 frame 必须属于子 spec。前缀和后缀也可以指定为关键字参数。

附加的默认行为是不复制,因此所有子引用(worldbody 除外)在父 spec 中仍然有效,因此修改子 spec 将修改父 spec。这对于 MJCF 中的 attachreplicate 元元素则不然,它们在附加时创建深拷贝。但是,可以通过将 spec.copy_during_attach 设置为 True 来覆盖默认行为。在这种情况下,子 spec 被复制,并且对子的引用将不指向父 spec。

import mujoco

# Create the parent spec.
parent = mujoco.MjSpec()
body = parent.worldbody.add_body()
frame = parent.worldbody.add_frame()
site = parent.worldbody.add_site()

# Create the child spec.
child = mujoco.MjSpec()
child_body = child.worldbody.add_body()
child_frame = child.worldbody.add_frame()

# Attach the child to the parent in different ways.
body_in_frame = frame.attach_body(child_body, 'child-', '')
frame_in_body = body.attach_frame(child_frame, 'child-', '')
worldframe_in_site = parent.attach(child, site=site, prefix='child-')
worldframe_in_frame = parent.attach(child, frame=frame, prefix='child-')

便利方法#

Python 绑定提供了许多 C API 中不直接可用的便利方法和属性,以使模型编辑更加容易

命名访问#

MjSpec 对象具有诸如 .body().joint().site() 等方法,用于按名称访问元素。spec.geom('my_geom') 将返回名为“my_geom”的 mjsGeom,如果不存在则返回 None

元素列表#

可以使用命名属性访问 spec 中的所有元素列表,使用复数形式。例如,spec.meshes 返回 spec 中所有网格的列表。以下属性已实现:sitesgeomsjointslightscamerasbodiesframesmaterialsmeshespairsequalitiestendonsactuatorsskinstexturestextstuplesflexeshfieldskeysnumericsexcludessensorsplugins

元素移除#

对于可以有子元素的元素(bodies 和 defaults),方法 spec.detach_body(body)spec.detach_default(def) 分别从 spec 中移除 bodydef 及其所有子元素。分离 body 子树时,所有引用子树中元素的元素也将被移除。对于所有其他元素,方法 delete() 移除 spec 中相应的元素,例如 spec.geom('my_geom').delete() 将移除名为“my_geom”的几何体以及所有引用它的元素。

树遍历#

以下方法返回与树相关的元素列表,有助于运动树的遍历

直接子元素

与上面描述的 spec 级元素列表类似,bodies 具有返回所有直接子元素列表的属性。例如,body.geoms 返回作为该 body 直接子元素的所有 geoms 的列表。这适用于所有树内元素,即 bodiesjointsgeomssitescameraslightsframes

递归搜索

body.find_all() 返回位于给定 body 子树中的给定类型的所有元素的列表。元素类型可以使用 mjtObj 枚举或相应的字符串指定。例如,body.find_all(mujoco.mjtObj.mjOBJ_SITE)body.find_all('site') 都将返回该 body 下所有 sites 的列表。

父级

给定元素的父 body(包括 bodies 和 frames)可以通过 parent 属性访问。例如,site 的父级可以通过 site.parent 访问。

序列化#

MjSpec 对象可以使用函数 spec.to_zip(file) 连同其所有资产一起序列化,其中 file 可以是文件路径或文件对象。要从 zip 文件加载 spec,请使用 spec = MjSpec.from_zip(file),其中 file 是 zip 文件路径或 zip 文件对象。

PyMJCFbind 的关系#

dm_controlPyMJCF 模块提供了与此处描述的原生模型编辑 API 类似的功能,但由于其依赖于 Python 对字符串的操作,速度大约慢了两个数量级。

对于熟悉 PyMJCF 的用户,MjSpec 对象在概念上类似于 dm_controlmjcf_model。未来可能会在此处添加更详细的迁移指南;同时,请注意模型编辑 colab notebook 包含 dm_control 教程 notebookPyMJCF 示例的重新实现。

PyMJCF 提供“绑定”的概念,通过辅助类访问 mjModelmjData 值。在原生 API 中,不需要辅助类,因此可以直接将 mjs 对象绑定到 mjModelmjData。例如,假设我们有多个 geom 的名称中包含字符串“torso”。我们想从 mjData 中获取它们在 XY 平面上的笛卡尔坐标位置。可以按如下方式完成

torsos = [data.bind(geom) for geom in spec.geoms if 'torso' in geom.name]
pos_x = [torso.xpos[0] for torso in torsos]
pos_y = [torso.xpos[1] for torso in torsos]

使用 bind 方法需要从 :cite:`ref:`mjSpec` 编译 mjModelmjData。如果自上次编译以来从 mjSpec 中添加或删除了对象,则会引发错误。

注意#

  • mj_recompile 的工作方式与 C API 不同。在 C API 中,它就地修改模型和数据,而在 Python API 中,它返回新的 mjModelmjData 对象。这是为了避免悬空引用。

从源代码构建#

注意

只有在修改 Python 绑定(或试图在非常旧的 Linux 系统上运行)时才需要从源代码构建。如果不是这种情况,我们建议从 PyPI 安装预构建的二进制文件。

  1. 确保已安装 CMake 和 C++17 编译器。

  2. 从 GitHub 下载最新二进制版本。在 macOS 上,下载的是 DMG 文件,您可以双击或运行 hdiutil attach <dmg_file> 来挂载。

  3. 从 GitHub 克隆整个 mujoco 仓库并 cd 到 python 目录

    git clone https://github.com/google-deepmind/mujoco.git
    cd mujoco/python
    
  4. 创建一个虚拟环境

    python3 -m venv /tmp/mujoco
    source /tmp/mujoco/bin/activate
    
  5. 使用 make_sdist.sh 脚本生成一个源代码分发 tarball。

    bash make_sdist.sh
    

    make_sdist.sh 脚本生成构建绑定所需的额外 C++ 头文件,并从仓库中 python 目录之外的其他位置拉取所需文件到 sdist 中。完成后,脚本将创建一个 dist 目录,其中包含一个 mujoco-x.y.z.tar.gz 文件(其中 x.y.z 是版本号)。

  6. 使用生成的源代码分发来构建和安装绑定。您需要将之前下载的 MuJoCo 库路径指定到 MUJOCO_PATH 环境变量中,并将 MuJoCo 插件目录路径指定到 MUJOCO_PLUGIN_PATH 环境变量中。

    注意

    对于 macOS,需要从 DMG 中提取文件。一旦您像步骤 2 中那样挂载了它,可以在 /Volumes/MuJoCo 中找到 mujoco.framework 目录,并在 /Volumes/MuJoCo/MuJoCo.app/Contents/MacOS/mujoco_plugin 中找到 plugins 目录。这两个目录可以复制到方便的位置,或者您可以使用 MUJOCO_PATH=/Volumes/MuJoCo MUJOCO_PLUGIN_PATH=/Volumes/MuJoCo/MuJoCo.app/Contents/MacOS/mujoco_plugin

    cd dist
    MUJOCO_PATH=/PATH/TO/MUJOCO \
    MUJOCO_PLUGIN_PATH=/PATH/TO/MUJOCO_PLUGIN \
    pip install mujoco-x.y.z.tar.gz
    

Python 绑定现在应该已安装!要检查它们是否已成功安装,cdmujoco 目录之外,并运行 python -c "import mujoco"

提示

作为参考,可以在 MuJoCo 的 GitHub 持续集成设置中找到工作构建配置。

模块#

mujoco 包包含两个子模块:mujoco.rolloutmujoco.minimize

rollout (展开)#

mujoco.rolloutmujoco.rollout.Rollout 展示了如何添加额外的 C/C++ 功能,通过 pybind11 暴露为 Python 模块。它实现在 rollout.cc 中,并封装在 rollout.py 中。该模块解决了一个常见的用例,即在 Python 之外实现的紧密循环有益:给定初始状态和控制序列,展开轨迹(即在循环中调用 mj_step),并返回后续状态和传感器值。如果将多个 MjData 实例(每个线程一个)作为参数传递,展开将在内部管理的线程池中并行运行。此 notebook 展示了如何使用 rollout rollout_colab,以及一些基准测试,例如下图。

_images/rollout.png

基本用法形式是

state, sensordata = rollout.rollout(model, data, initial_state, control)
  • model 是 MjModel 的单个实例,或长度为 nbatch 的同构 MjModel 序列。同构模型具有相同的整数大小,但浮点值可以不同。

  • data 是 MjData 的单个实例,或长度为 nthread 的兼容 MjDatas 序列。

  • initial_state 是一个 nbatch x nstate 数组,包含 nbatch 个大小为 nstate 的初始状态,其中 nstate = mj_stateSize(model, mjtState.mjSTATE_FULLPHYSICS)完整物理状态 的大小。

  • control 是一个 nbatch x nstep x ncontrol 的控制数组。控制默认为 mjModel.nu 标准执行器,但可以通过传递可选的 control_spec 位标志来指定任何组合的 用户输入 数组。

如果展开发散,则使用当前状态和传感器值来填充轨迹的剩余部分。因此,可以使用非递增的时间值来检测发散的展开。

rollout 函数设计为计算无状态的,因此设置了步进管线的所有输入,并且给定 MjData 实例中已存在的任何值都不会对输出产生影响。

默认情况下,如果 len(data) > 1rollout.rollout 每次调用都会创建一个新的线程池。要在多次调用中重用线程池,请使用 persistent_pool 参数。当使用持久池时,rollout.rollout 不是线程安全的。基本用法形式是

state, sensordata = rollout.rollout(model, data, initial_state, persistent_pool=True)

池在解释器关闭时或调用 rollout.shutdown_persistent_pool 时关闭。

要从多个线程使用多个线程池,请使用 Rollout 对象。基本用法形式是

# Pool shutdown upon exiting block.
with rollout.Rollout(nthread=nthread) as rollout_:
 rollout_.rollout(model, data, initial_state)

# Pool shutdown on object deletion or call to rollout_.close().
# To ensure clean shutdown of threads, call close() before interpreter exit.
rollout_ = rollout.Rollout(nthread=nthread)
rollout_.rollout(model, data, initial_state)
rollout_.close()

由于释放了全局解释器锁,此函数也可以使用 Python 线程进行线程化。然而,这不如使用本地线程高效。有关线程操作的示例(以及更一般的用法示例),请参阅 rollout_test.py 中的 test_threading 函数。

minimize (最小化)#

此模块包含与优化相关的实用工具。

minimize.least_squares() 函数实现了一个非线性最小二乘优化器,通过 mju_boxQP 求解顺序二次规划。相关 notebook 中记录了该函数:lscolab

USD 导出器#

USD 导出器模块允许用户将场景和轨迹保存为 USD 格式,以便在外部渲染器(如 NVIDIA Omniverse 或 Blender)中进行渲染。这些渲染器提供比默认渲染器更高质量的渲染功能。此外,导出到 USD 允许用户包含不同类型的纹理贴图,使场景中的物体看起来更逼真。

安装#

为 USD 导出器安装必要要求的推荐方法是通过 PyPI

pip install mujoco[usd]

这将安装 USD 导出器所需的可选依赖项 usd-corepillow

如果您正在从源代码构建,请确保构建 Python 绑定。然后,使用 pip 安装所需的 usd-corepillow 包。

USDExporter#

mujoco.usd.exporter 模块中的 USDExporter 类除了定义自定义相机和灯光外,还允许保存完整的轨迹。USDExporter 实例的构造函数参数包括

  • model:一个 MjModel 实例。USD 导出器从模型中读取相关信息,包括相机、灯光、纹理和物体几何体的详细信息。

  • max_geom:场景中几何体的最大数量,在实例化内部 mjvScene 时需要。

  • output_directory:用于存储导出的 USD 文件和所有相关资产的目录名称。当将场景/轨迹保存为 USD 文件时,导出器会创建以下目录结构。

    output_directory_root/
    └-output_directory/
      ├-assets/
      | ├-texture_0.png
      | ├-texture_1.png
      | └-...
      └─frames/
        └-frame_301.usd
    

    使用这种文件结构使用户可以轻松归档 output_directory。USD 文件中所有资产的路径都是相对的,这有助于在另一台机器上使用 USD 归档。

  • output_directory_root:将 USD 轨迹添加到其中的根目录。

  • light_intensity:所有灯光的强度。请注意,强度的单位在不同的渲染器中可能定义不同,因此可能需要根据特定渲染器调整此值。

  • camera_names:存储在 USD 文件中的相机列表。在每个时间步,对于每个定义的相机,我们计算其位置和方向,并将其值添加到 USD 中该给定帧中。USD 允许我们存储多个相机。

  • verbose:是否打印导出器的日志消息。

如果您希望导出直接从 MJCF 加载的模型,我们提供了一个演示脚本,展示了如何操作。此演示文件也作为 USD 导出功能的示例。

基本用法#

安装可选依赖项后,可以通过 from mujoco.usd import exporter 导入 USD 导出器。

下面,我们演示一个使用 USDExporter 的简单示例。在初始化期间,USDExporter 会创建一个空的 USD stage,如果 assets 和 frames 目录尚不存在,也会创建它们。此外,它会为模型中定义的每个纹理生成 .png 文件。每次调用 update_scene 时,导出器会记录场景中所有几何体、灯光和相机的位置和方向。

USDExporter 通过维护一个帧计数器来内部跟踪帧。每次调用 update_scene 时,计数器都会递增,并为相应的帧保存所有几何体、相机和灯光的位置。重要的是要注意,您可以在调用 update_scene 之前多次步进仿真。最终的 USD 文件将仅存储几何体、灯光和相机在上次 update_scene 调用时的位置。

import mujoco
from mujoco.usd import exporter

m = mujoco.MjModel.from_xml_path('/path/to/mjcf.xml')
d = mujoco.MjData(m)

# Create the USDExporter
exp = exporter.USDExporter(model=m)

duration = 5
framerate = 60
while d.time < duration:

  # Step the physics
  mujoco.mj_step(m, d)

  if exp.frame_count < d.time * framerate:
    # Update the USD with a new frame
    exp.update_scene(data=d)

# Export the USD file
exp.save_scene(filetype="usd")

USD 导出 API#

  • update_scene(self, data, scene_option):使用用户传入的最新仿真数据更新场景。此函数更新场景中的几何体、相机和灯光。

  • add_light(self, pos, intensity, radius, color, obj_name, light_type):事后向 USD 场景添加具有给定属性的灯光。

  • add_camera(self, pos, rotation_xyz, obj_name):事后向 USD 场景添加具有给定属性的相机。

  • save_scene(self, filetype):使用 USD 文件扩展名之一(.usd.usda.usdc)导出 USD 场景。

缺少的功能#

下面,我们列出了 USD 导出器中剩余的待办事项。请随时通过在 GitHub 中创建新的功能请求来建议其他请求。

  • 添加对附加纹理贴图的支持,包括金属感、遮挡、粗糙度、凹凸等。

  • 添加对使用 Isaac 进行在线渲染的支持。

  • 添加对自定义相机的支持。

实用工具#

python/mujoco 目录也包含实用脚本。

msh2obj.py#

msh2obj.py 脚本将曲面网格的旧版 .msh 格式(与也使用 .msh 的可能体积gmsh 格式不同)转换为 OBJ 文件。旧版格式已被弃用,并将在未来版本中移除。请将所有旧版文件转换为 OBJ。

mujoco-py 迁移#

在 mujoco-py 中,主要的入口点是 MjSim 类。用户从 MJCF 模型构建一个有状态的 MjSim 实例(类似于 dm_control.Physics),并且此实例持有对 mjModel 实例及其关联的 mjData 的引用。相比之下,MuJoCo Python 绑定(mujoco)采用了更低层级的方法,如上所述:遵循 C 库的设计原则,mujoco 模块本身是无状态的,仅仅封装了底层的原生结构体和函数。

虽然对 mujoco-py 进行全面调查超出了本文档的范围,但我们在下面提供了一些关于非穷尽性特定 mujoco-py 功能的实现说明。

mujoco_py.load_model_from_xml(bstring)

此工厂函数构建一个有状态的 MjSim 实例。使用 mujoco 时,用户应调用工厂函数 mujoco.MjModel.from_xml_*,如上文所述。用户随后负责持有生成的 MjModel 结构体实例,并通过调用 mujoco.MjData(model) 显式生成相应的 MjData

sim.reset(), sim.forward(), sim.step()

与上面类似,mujoco 用户需要调用底层的库函数,传入 MjModelMjData 实例:mujoco.mj_resetData(model, data), mujoco.mj_forward(model, data), 和 mujoco.mj_step(model, data)

sim.get_state(), sim.set_state(state), sim.get_flattened_state(), sim.set_state_from_flattened(state)

编程部分所述,给定特定的输入,MuJoCo 库的计算是确定性的。mujoco-py 实现了获取和设置一些相关字段的方法(类似地,dm_control.Physics 提供了对应于扁平化情况的方法)。mujoco 不提供此类抽象,用户需要显式地获取/设置相关字段的值。

sim.model.get_joint_qvel_addr(joint_name)

这是 mujoco-py 中的一个便利方法,它返回一个与此关节对应的连续索引列表。该列表从 model.jnt_qposadr[joint_index] 开始,其长度取决于关节类型。mujoco 不提供此功能,但可以使用 model.jnt_qposadr[joint_index]xrange 轻松构建此列表。

sim.model.*_name2id(name)

mujoco-py 在 MjSim 中创建字典,以便高效查找不同类型对象的索引:site_name2id, body_name2id 等。这些函数替代了函数 mujoco.mj_name2id(model, type_enum, name)mujoco 提供了使用实体名称的不同方法——命名访问,以及对原生 mj_name2id 的访问。

sim.save(fstream, format_name)

这是 MuJoCo 库(以及 mujoco)有状态的唯一上下文:它在内存中保留了上次编译的 XML 的副本,该副本用于 mujoco.mj_saveLastXML(fname)。请注意,mujoco-py 的实现有一个便利的额外功能,即在保存之前将姿态(由 sim.data 的状态确定)转换为添加到模型的关键帧。此额外功能目前在 mujoco 中不可用。