MjSpec 教程

本文为 MjSpec 官方教程的简单翻译.

首先附上 原文链接官方 GitHub 链接.

本文为使用 mjSpec API 在 MuJoCo 中编辑模型的入门教程. 本文假设读者已经熟悉MuJoCo的基本概念, 如 introductory tutorial 中所示. 此 API 的文档可以在官方文档 (C API) 中的章节 Model EditingPython 中找到. 这里我们使用 Python API.

这些 API 的目标是允许用户在 Python 中轻松地与 MuJoCo 模型进行交互和修改, 类似于 JavaScript DOM 对 HTML 的作用.

导入相关包, 定义相关函数

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
!pip install mujoco

# Set up GPU rendering.
from google.colab import files
import distutils.util
import os
import subprocess
if subprocess.run('nvidia-smi').returncode:
raise RuntimeError(
'Cannot communicate with GPU. '
'Make sure you are using a GPU Colab runtime. '
'Go to the Runtime menu and select Choose runtime type.')

# Add an ICD config so that glvnd can pick up the Nvidia EGL driver.
# This is usually installed as part of an Nvidia driver package, but the Colab
# kernel doesn't install its driver via APT, and as a result the ICD is missing.
# (https://github.com/NVIDIA/libglvnd/blob/master/src/EGL/icd_enumeration.md)
NVIDIA_ICD_CONFIG_PATH = '/usr/share/glvnd/egl_vendor.d/10_nvidia.json'
if not os.path.exists(NVIDIA_ICD_CONFIG_PATH):
with open(NVIDIA_ICD_CONFIG_PATH, 'w') as f:
f.write("""{
"file_format_version" : "1.0.0",
"ICD" : {
"library_path" : "libEGL_nvidia.so.0"
}
}
""")

# Configure MuJoCo to use the EGL rendering backend (requires GPU)
print('Setting environment variable to use GPU rendering:')
%env MUJOCO_GL=egl

# Check if installation was succesful.
try:
print('Checking that the installation succeeded:')
import mujoco as mj
mj.MjModel.from_xml_string('<mujoco/>')
except Exception as e:
raise e from RuntimeError(
'Something went wrong during installation. Check the shell output above '
'for more information.\n'
'If using a hosted Colab runtime, make sure you enable GPU acceleration '
'by going to the Runtime menu and selecting "Choose runtime type".')

print('Installation successful.')

# Other imports and helper functions
import time
import itertools
import numpy as np

# Graphics and plotting.
print('Installing mediapy:')
!command -v ffmpeg >/dev/null || (apt update && apt install -y ffmpeg)
!pip install -q mediapy
import mediapy as media
import matplotlib.pyplot as plt

# More legible printing from numpy.
np.set_printoptions(precision=3, suppress=True, linewidth=100)

from IPython.display import clear_output, HTML, display
clear_output()

# Get MuJoCo's humanoid model and a Franka arm from the MuJoCo Menagerie.
print('Getting MuJoCo humanoid XML description from GitHub:')
!git clone https://github.com/google-deepmind/mujoco
humanoid_file = 'mujoco/model/humanoid/humanoid.xml'
humanoid100_file = 'mujoco/model/humanoid/humanoid100.xml'
print('Getting MuJoCo Menagerie Franka XML description from GitHub:')
!git clone https://github.com/google-deepmind/mujoco_menagerie
franka_file = 'mujoco_menagerie/franka_fr3/fr3.xml'

def print_xml(xml_string):
formatter = pygments.formatters.HtmlFormatter(style='lovelace')
lexer = pygments.lexers.XmlLexer()
highlighted = pygments.highlight(xml_string, lexer, formatter)
display(HTML(f"<style>{formatter.get_style_defs()}</style>{highlighted}"))

def render(model, data=None, height=250):
if data is None:
data = mj.MjData(model)
with mj.Renderer(model, 480, 640) as renderer:
mj.mj_forward(model, data)
renderer.update_scene(data)
media.show_image(renderer.render(), height=height)

将 XML 解析为 mjSpec 并编译为 mjModel

不同于 mj_loadXML 的直接包含解析和编译过程, 使用 mjSpec 时, 解析和编译是分开的, 允许编辑中间步骤:

字符串形式的静态模型

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
# A static model, from string
static_model = """
<mujoco>
<worldbody>
<light name="top" pos="0 0 1"/>
<geom name="red_box" type="box" size=".2 .2 .2" rgba="1 0 0 1"/>
<geom name="green_sphere" pos=".2 .2 .2" size=".1" rgba="0 1 0 1"/>
</worldbody>
</mujoco>
"""
spec = mj.MjSpec.from_string(static_model)
model = spec.compile()
render(model)

# Change the mjSpec, re-compile and re-render
spec.modelname = "edited model"
geoms = spec.worldbody.find_all(mj.mjtObj.mjOBJ_GEOM)
geoms[0].name = 'blue_box'
geoms[0].rgba = [0, 0, 1, 1]
geoms[1].name = 'yellow_sphere'
geoms[1].rgba = [1, 1, 0, 1]
spec.worldbody.add_geom(name='magenta cylinder',
type=mj.mjtGeom.mjGEOM_CYLINDER,
rgba=[1, 0, 1, 1],
pos=[-.2, 0, .2],
size=[.1, .1, 0])

model = spec.compile()
render(model)

mjSpec 可以将 XML 保存为字符串, 以便进行所有修改:

1
print_xml(spec.to_xml())

从头开始构建 mjSpec

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
# Building an `mjSpec` from scratch
spec = mj.MjSpec()
spec.worldbody.add_light(name="top", pos=[0, 0, 1])
body = spec.worldbody.add_body(name="box_and_sphere", euler=[0, 0, -30])
body.add_joint(name="swing", type=mj.mjtJoint.mjJNT_HINGE,
axis=[1, -1, 0], pos=[-.2, -.2, -.2])
body.add_geom(name="red_box", type=mj.mjtGeom.mjGEOM_BOX,
size=[.2, .2, .2], rgba=[1, 0, 0, 1])
body.add_geom(name="green_sphere", pos=[.2, .2, .2],
size=[.1, 0, 0], rgba=[0, 1, 0, 1])
model = spec.compile()

duration = 2 # (seconds)
framerate = 30 # (Hz)

# enable joint visualization option:
scene_option = mj.MjvOption()
scene_option.flags[mj.mjtVisFlag.mjVIS_JOINT] = True

# Simulate and display video.
frames = []
data = mj.MjData(model)
mj.mj_resetData(model, data)
with mj.Renderer(model) as renderer:
while data.time < duration:
mj.mj_step(model, data)
if len(frames) < data.time * framerate:
renderer.update_scene(data, scene_option=scene_option)
pixels = renderer.render()
frames.append(pixels)

media.show_video(frames, fps=framerate)

控制示例

该库的一个关键特性是能够轻松地将多个模型连接到一个更大的模型中. 使用用户定义的命名空间, 以消除来自不同模型或同一模型的多个实例的重名歧义.

一个示例用例是构造具有可变关节数量的机器人, 这是对运动学结构的根本改变. 下面的代码片段实现了这个场景.

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
leg_model = """
<mujoco>
<compiler angle="radian"/>

<default>
<joint damping="2" type="hinge"/>
<geom type="capsule"/>
</default>

<worldbody>
<body name="thigh">
<joint name="hip" axis="0 0 1"/>
<body name="shin">
<joint name="knee" axis="0 1 0"/>
</body>
</body>
</worldbody>

<actuator>
<position joint="hip" kp="10" name="hip"/>
<position joint="knee" kp="10" name="knee"/>
</actuator>
</mujoco>
"""

class Leg(object):
"""A 2-DoF leg with position actuators."""
def __init__(self, length, rgba):
self.spec = mj.MjSpec.from_string(leg_model)

# Thigh:
thigh = self.spec.find_body('thigh')
thigh.add_geom(fromto=[0, 0, 0, length, 0, 0], size=[length/4, 0, 0], rgba=rgba)

# Hip:
shin = self.spec.find_body('shin')
shin.add_geom(fromto=[0, 0, 0, 0, 0, -length], size=[length/5, 0, 0], rgba=rgba)
shin.pos[0] = length

Leg 类描述了一个抽象的铰接腿, 具有两个关节以及相应的 PD 控制器.

请注意:

  • MJCF 属性直接对应于 add_() 方法的参数.
  • 当引用元件时, 例如当指定执行器所连接的关节时, 使用 MJCF 元件的名称字符串.
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
BODY_RADIUS = 0.1
random_state = np.random.RandomState(42)
creature_model = """
<mujoco>
<compiler angle="radian"/>

<worldbody>
<geom name="torso" type="ellipsoid" size="{} {} {}"/>
</worldbody>
</mujoco>
""".format(BODY_RADIUS, BODY_RADIUS, BODY_RADIUS / 2)

def make_creature(num_legs):
"""Constructs a creature with `num_legs` legs."""
rgba = random_state.uniform([0, 0, 0, 1], [1, 1, 1, 1])
spec = mj.MjSpec.from_string(creature_model)

# Attach legs to equidistant sites on the circumference.
spec.worldbody.first_geom().rgba = rgba
leg = Leg(length=BODY_RADIUS, rgba=rgba)
for i in range(num_legs):
theta = 2 * i * np.pi / num_legs
hip_pos = BODY_RADIUS * np.array([np.cos(theta), np.sin(theta), 0])
hip_site = spec.worldbody.add_site(pos=hip_pos, euler=[0, 0, theta])
hip_site.attach_body(leg.spec.find_body('thigh'), '', '-' + str(i))

return spec

make_creature 函数使用 attach() 方法以程序方式将腿附加到躯干. 请注意, 在这个阶段, 躯干和臀部连接点都是 worldbody 的子节点, 因为它们的父体还没有被实例化. 我们现在要做一个有方格地板和两盏灯的竞技场, 把创建的生物以网格形式排列在地板上.

地板上的六足生物

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
# Six Creatures on a floor.
arena = mj.MjSpec()

if hasattr(arena, 'compiler'):
arena.compiler.degree = False # MuJoCo dev (next release).
else:
arena.degree = False # MuJoCo release

# Make arena with textured floor.
chequered = arena.add_texture(
name="chequered", type=mj.mjtTexture.mjTEXTURE_2D,
builtin=mj.mjtBuiltin.mjBUILTIN_CHECKER,
width=300, height=300, rgb1=[.2, .3, .4], rgb2=[.3, .4, .5])
grid = arena.add_material(
name='grid', texrepeat=[5, 5], reflectance=.2
).textures[mj.mjtTextureRole.mjTEXROLE_RGB] = 'chequered'
arena.worldbody.add_geom(
type=mj.mjtGeom.mjGEOM_PLANE, size=[2, 2, .1], material='grid')
for x in [-2, 2]:
arena.worldbody.add_light(pos=[x, -1, 3], dir=[-x, 1, -2])

# Instantiate 6 creatures with 3 to 8 legs.
creatures = [make_creature(num_legs=num_legs) for num_legs in range(3, 9)]

# Place them on a grid in the arena.
height = .15
grid = 5 * BODY_RADIUS
xpos, ypos, zpos = np.meshgrid([-grid, 0, grid], [0, grid], [height])
for i, spec in enumerate(creatures):
# Place spawn sites on a grid.
spawn_pos = (xpos.flat[i], ypos.flat[i], zpos.flat[i])
spawn_site = arena.worldbody.add_site(pos=spawn_pos, group=3)
# Attach to the arena at the spawn sites, with a free joint.
spawn_body = spawn_site.attach_body(spec.worldbody, '', '-' + str(i))
spawn_body.add_freejoint()

# Instantiate the physics and render.
model = arena.compile()
render(model)

多足生物, 准备漫游! 让我们引入一些控制并观察它们的运动. 我们将生成一个固定频率和随机相位的正弦开环控制信号, 记录视频帧和躯干的几何水平位置, 以便绘制运动轨迹.

运动视频

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
# Video of the movement
data = mj.MjData(model)
duration = 10 # (Seconds)
framerate = 30 # (Hz)
video = []
pos_x = []
pos_y = []
geoms = arena.worldbody.find_all(mj.mjtObj.mjOBJ_GEOM)
torsos_data = [data.bind(geom) for geom in geoms if 'torso' in geom.name]
torsos_model = [model.bind(geom) for geom in geoms if 'torso' in geom.name]
actuators = [data.bind(actuator) for actuator in arena.actuators]

# Control signal frequency, phase, amplitude.
freq = 5
phase = 2 * np.pi * random_state.rand(len(arena.actuators))
amp = 0.9

# Simulate, saving video frames and torso locations.
mj.mj_resetData(model, data)
with mj.Renderer(model) as renderer:
while data.time < duration:
# Inject controls and step the physics.
for i, actuator in enumerate(actuators):
actuator.ctrl = amp * np.sin(freq * data.time + phase[i])
mj.mj_step(model, data)

# Save torso horizontal positions using name indexing.
pos_x.append([torso.xpos[0] for torso in torsos_data])
pos_y.append([torso.xpos[1] for torso in torsos_data])

# Save video frames.
if len(video) < data.time * framerate:
renderer.update_scene(data)
pixels = renderer.render()
video.append(pixels.copy())

media.show_video(video, fps=framerate)

运动轨迹

1
2
3
4
5
# Movement trajectories
creature_colors = [torso.rgba[:3] for torso in torsos_model]
fig, ax = plt.subplots(figsize=(4, 4))
ax.set_prop_cycle(color=creature_colors)
_ = ax.plot(pos_x, pos_y, linewidth=4)

上图显示了生物位置的相应运动轨迹. 注意 mjSpec 属性 id 是如何用来访问 xposrgba 值的. 此属性仅在模型编译后才有效.

模型编辑

mjSpec元素可以通过两种方式遍历:

  • 对于运动树内部的元素, 可以使用 firstnext 函数遍历树.
  • 对于所有其他元素, 我们提供一个列表.

遍历 spec

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
# Traversing the spec.
spec = mj.MjSpec.from_file(humanoid_file)

# Function that recursively prints all body names
def print_bodies(parent, level=0):
body = parent.first_body()
while body:
print(''.join(['-' for i in range(level)]) + body.name)
print_bodies(body, level + 1)
body = parent.next_body(body)

print("The spec has the following actuators:")
for actuator in spec.actuators:
print(actuator.name)

print("\nThe spec has the following bodies:")
print_bodies(spec.worldbody)

The spec has the following actuators:
abdomen_z
abdomen_y
abdomen_x
hip_x_right
hip_z_right
hip_y_right
knee_right
ankle_y_right
ankle_x_right
hip_x_left
hip_z_left
hip_y_left
knee_left
ankle_y_left
ankle_x_left
shoulder1_right
shoulder2_right
elbow_right
shoulder1_left
shoulder2_left
elbow_left

The spec has the following bodies:
torso
-head
-waist_lower
--pelvis
---thigh_right
----shin_right
-----foot_right
---thigh_left
----shin_left
-----foot_left
-upper_arm_right
--lower_arm_right
---hand_right
-upper_arm_left
--lower_arm_left
---hand_left

一个 mjSpec 可以被编译多次. 如果必须在不同的编译之间保留状态, 则必须使用函数 recompile(), 该函数返回包含映射状态的新 mjData, 可能具有与源不同的维度.

保持状态的模型重编译

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
# Model re-compilation with state preservation.
spec = mj.MjSpec.from_file(humanoid100_file)
model = spec.compile()
data = mj.MjData(model)

# Run for 5 seconds
for i in range(1000):
mj.mj_step(model, data)

# Show result
render(model, data)

# Create list of all bodies we want to delete
body = spec.worldbody.first_body()
delete_list = []
while body:
geom_type = body.first_geom().type
if (geom_type == mj.mjtGeom.mjGEOM_BOX or
geom_type == mj.mjtGeom.mjGEOM_ELLIPSOID):
delete_list.append(body)
body = spec.worldbody.next_body(body)

# Remove all bodies in the list from the spec
for body in delete_list:
spec.detach_body(body)

# # Add another humanoid
spec_humanoid = mj.MjSpec.from_file(humanoid_file)
attachment_frame = spec.worldbody.add_frame(pos=[0, -1, 2])
attachment_frame.attach_body(spec_humanoid.find_body('torso'), 'a', 'b')

# Recompile preserving the state
new_model, new_data = spec.recompile(model, data)

# Show result
render(new_model, new_data)

让我们加载人形模型并检查它.

Humanoid 模型

1
2
3
4
5
# Humanoid model.
spec = mj.MjSpec.from_file(humanoid_file)

model = spec.compile()
render(model)

把模型手臂去掉, 换上腿. 这可以通过提前存储躯干坐标系中的手臂位置来完成. 然后就可以把手臂拆卸下来, 再将腿部安装到坐标系中.

将 Humanoid 的手臂换成腿部

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
# Humanoid with arms replaced by legs.
spec = mj.MjSpec.from_file(humanoid_file)

# Get the torso, arm, and leg bodies
arm_left = spec.find_body('upper_arm_left')
arm_right = spec.find_body('upper_arm_right')
leg_left = spec.find_body('thigh_left')
leg_right = spec.find_body('thigh_right')
torso = spec.find_body('torso')

# Attach frames at the arm positions
shoulder_left = torso.add_frame(pos=arm_left.pos)
shoulder_right = torso.add_frame(pos=arm_right.pos)

# Remove the arms
spec.detach_body(arm_left)
spec.detach_body(arm_right)

# Add new legs
shoulder_left.attach_body(leg_left, 'shoulder', 'left')
shoulder_right.attach_body(leg_right, 'shoulder', 'right')

model = spec.compile()
render(model, height=400)

同样, 不同的模型可以连接在一起. 比如, 把右臂拆下来, 再把来自不同模型的机器人手臂连接上.

带 Franka 手臂的 Humanoid

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
# Humanoid with Franka arm.
spec = mj.MjSpec.from_file(humanoid_file)
franka = mj.MjSpec.from_file(franka_file)

if hasattr(spec, 'compiler'):
spec.compiler.degree = False # MuJoCo dev (next release).
else:
spec.degree = False # MuJoCo release

# Replace right arm with frame
arm_right = spec.find_body('upper_arm_right')
torso = spec.find_body('torso')
shoulder_right = torso.add_frame(pos=arm_right.pos, quat=[0, 0.8509035, 0, 0.525322])
spec.detach_body(arm_right)

# Attach Franka arm to humanoid
franka_arm = franka.find_body('fr3_link2')
shoulder_right.attach_body(franka_arm, 'franka', '')

model = spec.compile()
render(model, height=400)

执行此操作时, 执行器和附加子树引用的所有其他对象将导入新模型中. 所有资源当前都已导入, 无论是否被引用.

导入的驱动器

1
2
3
# Imported actuators.
for actuator in spec.actuators:
print(actuator.name)

abdomen_z
abdomen_y
abdomen_x
hip_x_right
hip_z_right
hip_y_right
knee_right
ankle_y_right
ankle_x_right
hip_x_left
hip_z_left
hip_y_left
knee_left
ankle_y_left
ankle_x_left
shoulder1_left
shoulder2_left
elbow_left
frankafr3_joint2
frankafr3_joint3
frankafr3_joint4
frankafr3_joint5
frankafr3_joint6
frankafr3_joint7

域随机化可以通过多次附加相同的 spec 来执行, 每次使用随机化参数的新实例进行编辑.

具有随机头部和手臂姿态的 Humanoid

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
#@title Humanoid with randomized heads and arm poses.{vertical-output: true}
humanoid = mj.MjSpec.from_file(humanoid_file)
spec = mj.MjSpec()

# Delete all key frames to avoid name conflicts
while humanoid.keys:
humanoid.keys[-1].delete()

# Create a grid of humanoids by attaching humanoid to spec multiple times
for i in range(4):
for j in range(4):
humanoid.materials[0].rgba = [
np.random.uniform(), np.random.uniform(),
np.random.uniform(), 1] # Randomize color
humanoid.find_body('head').first_geom().size = [
.18*np.random.uniform(), 0, 0] # Randomize head size
humanoid.find_body('upper_arm_left').quat = [
np.random.uniform(), np.random.uniform(),
np.random.uniform(), np.random.uniform()] # Randomize left arm orientation
humanoid.find_body('upper_arm_right').quat = [
np.random.uniform(), np.random.uniform(),
np.random.uniform(), np.random.uniform()] # Randomize right arm orientation

# attach randomized humanoid to parent spec
frame = spec.worldbody.add_frame(pos=[i, j, 0])
frame.attach_body(humanoid.find_body('torso'), str(i), str(j))

spec.worldbody.add_light(mode=mj.mjtCamLight.mjCAMLIGHT_TARGETBODYCOM,
targetbody='3torso3', diffuse=[.8, .8, .8],
specular=[0.3, 0.3, 0.3], pos=[0, -6, 4], cutoff=30)
model = spec.compile()
render(model, height=400)