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 应用程序相同的代码库。支持三种不同的使用场景:托管查看器独立应用被动查看器

托管查看器#

函数 viewer.launch 启动交互式查看器并阻塞用户代码,这对于支持物理循环的精确计时非常有用。如果用户代码实现为引擎插件物理回调,并且在 mj_step 期间由 MuJoCo 调用,则应使用此模式。

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

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

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

独立应用#

mujoco.viewer Python 包使用 if __name__ == '__main__' 机制,允许托管查看器直接从命令行作为独立应用调用。

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

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

被动查看器#

viewer.launch_passive 函数以非阻塞方式启动交互式查看器,允许用户代码继续执行。在此模式下,用户的脚本负责计时和推进物理状态,除非用户明确同步传入的事件,否则鼠标拖动扰动将不起作用。

警告

在 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(state_only=False):在用户的 mjModelmjData 和 GUI 之间进行同步。为了允许用户脚本对 mjModelmjData 进行任意修改而无需持有查看器锁,被动查看器在 sync 调用之外不会访问或修改这些结构体。如果 state_only 参数为 True,则不是同步所有内容,而只同步与 mjSTATE_INTEGRATION 对应的 mjData 字段,然后调用 mj_forward。后一种选项速度快得多,但不会像默认情况那样捕捉到任意更改。通过 GUI 进行的更改在两种情况下都会被捕捉,但例如,通过代码更改 mjModel.geom_rgbastate_only=False 时会被捕捉,但在 state_only=True 时则不会。

    用户脚本必须调用 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_connector 来向 user_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_step,那么 qpos_slice 中的值将会被改变。

为了符合 PEP 8 命名准则,结构体名称以大写字母开头,例如 C 中的 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, [the new mjvScene instance], 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') 返回一个访问器,用于访问 MjModel 对象 m 中与名为“gizmo”的几何体相关的数组。

  • 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)与自由度(DoF)相关联,而不是关节。这是因为不同类型的关节具有不同数量的自由度。尽管如此,我们将这些字段与其对应的关节关联起来,例如通过 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 错误转换为 mujoco.FatalError 类型的 Python 异常,这些异常可以以通常的 Pythonic 方式被捕获和处理。此外,它使用一个当前为私有的 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>

附加#

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

  • 将子 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 是附加的 worldbody 转换而成的。该 site 必须属于子 spec。Prefix 和 suffix 也可以作为关键字参数指定。

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

附加的默认行为是不复制,因此所有子引用(除了 worldbody)在父级中仍然有效,因此修改子级将修改父级。这不适用于 MJCF 中的 attachreplicate 元元素,它们在附加时会创建深拷贝。但是,可以通过将 spec.copy_during_attach 设置为 True 来覆盖默认行为。在这种情况下,子 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 中所有网格的列表。实现了以下属性:sites, geoms, joints, lights, cameras, bodies, frames, materials, meshes, pairs, equalities, tendons, actuators, skins, textures, texts, tuples, flexes, hfields, keys, numerics, excludes, sensors, plugins

元素移除#

方法 delete() 从 spec 中移除相应的元素,例如 spec.delete(spec.geom('my_geom')) 将移除名为 "my_geom" 的 geom 以及所有引用它的元素。对于可以有子元素的元素(bodies 和 defaults),delete 也会移除它们的所有子元素。在删除 body 子树时,所有引用该子树中元素的元素也将被移除。

树遍历#

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

直接子元素

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

递归搜索

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

父级

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

序列化#

MjSpec 对象及其所有资源可以使用函数 spec.to_zip(file) 进行序列化,其中 file 可以是文件路径或文件对象。要从 zip 文件加载 spec,请使用 spec = MjSpec.from_zip(file),其中 file 是 zip 文件的路径或 zip 文件对象。

网格创建#

mjsMesh 对象包含用于模型创建的便利方法,这些方法具有命名属性,对应于 mesh/builtin 语义。请参见 specs_test.py

mesh = spec.add_mesh(name='prism')
mesh.make_cone(nedge=5, radius=1)

PyMJCFbind 的关系#

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

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

PyMJCF 提供了一个“绑定”的概念,通过一个辅助类来访问 mjModelmjData 的值。在原生 API 中,不需要辅助类,因此可以直接将 mjs 对象绑定到 mjModelmjData。例如,假设我们有多个名称中包含字符串“torso”的 geom。我们想从 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 方法要求 mjModelmjData 是从 :ref:`mjSpec 编译而来的。如果在上次编译后从 mjSpec 中添加或删除了对象,则会引发错误。

说明#

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

从源代码构建#

注意

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

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

  2. 从 GitHub 克隆整个 mujoco 仓库。

    git clone https://github.com/google-deepmind/mujoco.git
    
  3. 安装 MuJoCo。您可以从 GitHub 下载最新的二进制发行版(在 macOS 上,下载对应一个 DMG 文件,您可以通过双击或运行 hdiutil attach <dmg_file> 来挂载它),或者按照从源代码构建中的说明从源代码构建安装它。

  4. cd 进入克隆的 MuJoCo 代码库的 python 目录。

    cd mujoco/python
    
  5. 创建一个虚拟环境。

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

    bash make_sdist.sh
    

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

  7. 使用生成的源代码分发来构建和安装绑定。您需要在 MUJOCO_PATH 环境变量中指定您之前下载或构建并安装的 MuJoCo 库的路径,并在 MUJOCO_PLUGIN_PATH 环境变量中指定 MuJoCo 插件目录的路径。您可以将 MUJOCO_PLUGIN_PATH 环境变量指向您克隆的 MuJoCo 代码库的 plugin 文件夹。

    注意

    对于 macOS,需要从 DMG 文件中提取文件。按照步骤 2 挂载后,mujoco.framework 目录可以在 /Volumes/MuJoCo 中找到,插件目录可以在 /Volumes/MuJoCo/MuJoCo.app/Contents/MacOS/mujoco_plugin 中找到。这两个目录可以复制到方便的地方,或者您可以使用 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"

提示

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

模块#

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 的兼容 MjData 序列。

  • 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 发散,当前状态和传感器值将用于填充轨迹的剩余部分。因此,非递增的时间值可用于检测发散的 rollout。

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: 场景中 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 舞台,如果 assets 和 frames 目录不存在,则会创建它们。此外,它会为模型中定义的每个纹理生成 .png 文件。每次调用 update_scene 时,导出器都会记录场景中所有 geom、灯光和相机的位置和方向。

USDExporter 通过维护一个帧计数器来内部跟踪帧。每次调用 update_scene 时,计数器会递增,并保存相应帧的所有 geom、相机和灯光的姿态。值得注意的是,您可以在调用 update_scene 之前多次步进模拟。最终的 USD 文件将只存储最后一次调用 update_scene 时 geom、灯光和相机的姿态。

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): 使用用户传入的最新模拟数据更新场景。此函数会更新场景中的 geom、相机和灯光。

  • 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 提供了对应于扁平化情况的方法)。此功能在状态部分有描述。

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_name2idbody_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 中不可用。