Description
The following errors show up when using egl
and osmesa
for rendering via Python bindings. Could you take a look at this? Thank you!
Minimal example is the same as tutorial as below,
import os
os.environ['MUJOCO_GL']='egl'
import mujoco
import numpy as np
import matplotlib.pyplot as plt
if "MUJOCO_GL" in os.environ:
print(os.getenv('MUJOCO_GL'))
print(os.getenv('PYOPENGL_PLATFORM'))
xml = """
<mujoco>
<worldbody>
<light name="top" pos="0 0 1"/>
<body name="box_and_sphere" euler="0 0 -30">
<joint name="swing" type="hinge" axis="1 -1 0" pos="-.2 -.2 -.2"/>
<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"/>
</body>
</worldbody>
</mujoco>
"""
model = mujoco.MjModel.from_xml_string(xml)
renderer = mujoco.Renderer(model)
data = mujoco.MjData(model)
renderer.enable_depth_rendering()
mujoco.mj_forward(model, data)
renderer.update_scene(data)
depth = renderer.render()
depth -= depth.min()
depth /= 2 * depth[depth <= 1].mean()
img = 255 * np.clip(depth, 0, 1)
plt.imshow(img.astype(np.uint8))
plt.colorbar(label='Distance to Camera')
plt.show()
For EGL
option, rendering is successful but the __del__
failed,
Exception ignored in: <function GLContext.del at 0x7fa98b52ee50>
Traceback (most recent call last):
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/mujoco/egl/init.py", line 130, in del
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/mujoco/egl/init.py", line 123, in free
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/OpenGL/error.py", line 230, in glCheckError
OpenGL.raw.EGL._errors.EGLError: <exception str() failed>
For osmesa
,
Traceback (most recent call last):
File "test.py", line 4, in
import mujoco
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/mujoco/init.py", line 46, in
from mujoco.gl_context import *
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/mujoco/gl_context.py", line 38, in
from mujoco.osmesa import GLContext as _GLContext
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/mujoco/osmesa/init.py", line 31, in
from OpenGL import GL
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/OpenGL/GL/init.py", line 4, in
from OpenGL.GL.VERSION.GL_1_1 import *
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/OpenGL/GL/VERSION/GL_1_1.py", line 14, in
from OpenGL.raw.GL.VERSION.GL_1_1 import *
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/OpenGL/raw/GL/VERSION/GL_1_1.py", line 7, in
from OpenGL.raw.GL import _errors
File "/home/anaconda3/envs/env1/lib/python3.8/site-packages/OpenGL/raw/GL/_errors.py", line 4, in
_error_checker = _ErrorChecker( _p, _p.GL.glGetError )
AttributeError: 'NoneType' object has no attribute 'glGetError'
- Include the following context:
- Operating system.
Ubuntu 22.04.1 LTS
NVIDIA-SMI 470.161.03 Driver Version: 470.161.03 CUDA Version: 11.4
- MuJoCo version (and if the bug is new, the version where it used to work).
- 2.3.1.post1
- For Python issues, what bindings are you using (i.e
mujoco
,dm_control
,mujoco-py
)?mujoco