Skip to content

Commit c7b20e3

Browse files
committed
RENDERER: FEATURE: Adding the new mujoco renderer. Making MUJOCO as default backend
1 parent 05a7166 commit c7b20e3

File tree

6 files changed

+46
-117
lines changed

6 files changed

+46
-117
lines changed

robohive/envs/hands/hammer_v1.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,6 @@ def reset(self, reset_qpos=None, reset_qvel=None, **kwargs):
126126
qv = self.init_qvel.copy() if reset_qvel==None else reset_qvel
127127
self.robot.reset(reset_pos=qp, reset_vel=qv, **kwargs)
128128

129-
130129
self.sim.model.body_pos[self.target_bid,2] = self.np_random.uniform(low=0.1, high=0.25)
131130
self.sim.forward()
132131
return self.get_obs()

robohive/physics/mj_sim_scene.py

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616
import_utils.mujoco_isavailable()
1717
import dm_control.mujoco as dm_mujoco
1818

19-
from robohive.renderer.mj_renderer import DMRenderer
19+
from robohive.renderer.mj_renderer import MJRenderer
2020
from robohive.physics.sim_scene import SimScene
2121

2222

@@ -52,10 +52,9 @@ def advance(self, substeps: int = 1, render:bool = True):
5252
# self.renderer.refresh_window()
5353
self.renderer.render_to_window()
5454

55-
56-
def _create_renderer(self, sim: Any) -> DMRenderer:
55+
def _create_renderer(self, sim: Any) -> MJRenderer:
5756
"""Creates a renderer for the given simulation."""
58-
return DMRenderer(sim)
57+
return MJRenderer(sim)
5958

6059
def copy_model(self) -> Any:
6160
"""Returns a copy of the MjModel object."""

robohive/physics/sim_scene.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -52,9 +52,9 @@ def create(*args, backend: Union[SimBackend, int], **kwargs) -> 'SimScene':
5252
@staticmethod
5353
def get_sim(model_handle: Any) -> 'SimScene':
5454
sim_backend = os.getenv('sim_backend')
55-
if sim_backend == 'MUJOCO_PY' or sim_backend == None:
55+
if sim_backend == 'MUJOCO_PY':
5656
return SimScene.create(model_handle=model_handle, backend=SimBackend.MUJOCO_PY)
57-
elif sim_backend == 'MUJOCO':
57+
elif sim_backend == 'MUJOCO' or sim_backend == None:
5858
return SimScene.create(model_handle=model_handle, backend=SimBackend.DM_CONTROL)
5959
else:
6060
raise ValueError("Unknown sim_backend: {}. Available choices: MUJOCO_PY, MUJOCO")

robohive/renderer/mj_renderer.py

Lines changed: 36 additions & 108 deletions
Original file line numberDiff line numberDiff line change
@@ -7,34 +7,33 @@
77

88
"""Rendering simulation using dm_control."""
99

10-
import sys
11-
1210
import numpy as np
13-
import dm_control.mujoco as dm_mujoco
14-
import dm_control.viewer as dm_viewer
15-
import dm_control._render as dm_render
11+
import mujoco
12+
from mujoco import viewer
1613

1714
from typing import Union
18-
1915
from robohive.renderer.renderer import Renderer, RenderMode
2016

2117
# Default window dimensions.
2218
DEFAULT_WINDOW_WIDTH = 640
2319
DEFAULT_WINDOW_HEIGHT = 480
2420

2521
# Default window title.
26-
DEFAULT_WINDOW_TITLE = 'MuJoCo Viewer'
22+
DEFAULT_WINDOW_TITLE = 'RoboHive Viewer'
2723

28-
# Internal renderbuffer size, in pixels.
29-
_MAX_RENDERBUFFER_SIZE = 2048
3024

31-
32-
class DMRenderer(Renderer):
25+
class MJRenderer(Renderer):
3326
"""Renders DM Control Physics objects."""
3427

35-
def __init__(self, sim: dm_mujoco.Physics):
28+
def __init__(self, sim):
3629
super().__init__(sim)
3730
self._window = None
31+
self._renderer = None
32+
33+
34+
def setup_renderer(self, model, height, width):
35+
self._renderer = mujoco.Renderer(model, height=height, width=width)
36+
3837

3938
def render_to_window(self):
4039
"""Renders the Physics object to a window.
@@ -44,22 +43,23 @@ def render_to_window(self):
4443
This function is a no-op if the window was already created.
4544
"""
4645
if not self._window:
47-
self._window = DMRenderWindow()
48-
self._window.load_model(self._sim)
49-
self._update_camera_properties(self._window.camera)
46+
self._window = viewer.launch_passive(self._sim.model.ptr, self._sim.data.ptr)
47+
self._update_camera_properties(self._window.cam)
48+
49+
self._window.cam.azimuth+=.1 # trick to rotate camera for 360 videos
50+
self.refresh_window()
5051

51-
self._window.run_frame()
5252

5353
def refresh_window(self):
5454
"""Refreshes the rendered window if one is present."""
5555
if self._window is None:
5656
return
57-
self._window.run_frame()
57+
self._window.sync()
58+
5859

5960
def render_offscreen(self,
60-
width: int,
61-
height: int,
62-
# mode: RenderMode = RenderMode.RGB,
61+
width: int = DEFAULT_WINDOW_WIDTH,
62+
height: int = DEFAULT_WINDOW_HEIGHT,
6363
rgb: bool = True,
6464
depth: bool = False,
6565
segmentation: bool = False,
@@ -77,36 +77,29 @@ def render_offscreen(self,
7777
Returns:
7878
A numpy array of the pixels.
7979
"""
80-
assert width > 0 and height > 0
81-
82-
if isinstance(camera_id, str):
83-
camera_id = self._sim.model.name2id(camera_id, 'camera')
84-
elif camera_id == None:
85-
camera_id = -1
86-
87-
# TODO(michaelahn): Consider caching the camera.
88-
camera = dm_mujoco.Camera(
89-
physics=self._sim, height=height, width=width, camera_id=camera_id)
90-
91-
# Update the camera configuration for the free-camera.
92-
if camera_id == -1:
93-
self._update_camera_properties(camera._render_camera) # pylint: disable=protected-access
80+
if camera_id == None:
81+
camera_id = 0
82+
if self._renderer is None:
83+
self.setup_renderer(self._sim.model.ptr, width=width, height=height)
9484

95-
# image = camera.render(
96-
# depth=(mode == RenderMode.DEPTH),
97-
# segmentation=(mode == RenderMode.SEGMENTATION))
9885
rgb_arr = None; dpt_arr = None; seg_arr = None
9986
if rgb:
100-
rgb_arr = camera.render()
101-
# rgb_arr = rgb_arr[::-1, :, :]
87+
self._renderer.update_scene(self._sim.data.ptr, camera=camera_id)
88+
rgb_arr = self._renderer.render()
10289
if depth:
103-
dpt_arr = camera.render(depth=True)
90+
self._renderer.enable_depth_rendering()
91+
self._renderer.update_scene(self._sim.data.ptr, camera=camera_id)
92+
dpt_arr = self._renderer.render()
10493
dpt_arr = dpt_arr[::-1, :]
94+
self._renderer.disable_depth_rendering()
10595
if segmentation:
106-
seg_arr = camera.render(segmentation=True)
96+
self._renderer.enable_segmentation_rendering()
97+
self._renderer.update_scene(self._sim.data.ptr, camera=camera_id)
98+
dpt_arr = self._renderer.render()
99+
dpt_arr = dpt_arr[::-1, :]
100+
self._renderer.disable_segmentation_rendering()
107101
seg_arr = seg_arr[::-1, :]
108102

109-
camera._scene.free() # pylint: disable=protected-access
110103
if depth and segmentation:
111104
return rgb_arr, dpt_arr, seg_arr
112105
elif depth:
@@ -121,69 +114,4 @@ def close(self):
121114
"""Cleans up any resources being used by the renderer."""
122115
if self._window:
123116
self._window.close()
124-
self._window = None
125-
126-
127-
class DMRenderWindow:
128-
"""Class that encapsulates a graphical window."""
129-
130-
def __init__(self,
131-
width: int = DEFAULT_WINDOW_WIDTH,
132-
height: int = DEFAULT_WINDOW_HEIGHT,
133-
title: str = DEFAULT_WINDOW_TITLE):
134-
"""Creates a graphical render window.
135-
136-
Args:
137-
width: The width of the window.
138-
height: The height of the window.
139-
title: The title of the window.
140-
"""
141-
self._viewport = dm_viewer.renderer.Viewport(width, height)
142-
self._window = dm_viewer.gui.RenderWindow(width, height, title)
143-
self._viewer = dm_viewer.viewer.Viewer(
144-
self._viewport, self._window.mouse, self._window.keyboard)
145-
self._draw_surface = None
146-
self._renderer = dm_viewer.renderer.NullRenderer()
147-
148-
@property
149-
def camera(self):
150-
return self._viewer._camera._camera # pylint: disable=protected-access
151-
152-
def close(self):
153-
self._viewer.deinitialize()
154-
self._renderer.release()
155-
self._draw_surface.free()
156-
self._window.close()
157-
158-
def load_model(self, physics):
159-
"""Loads the given Physics object to render."""
160-
self._viewer.deinitialize()
161-
162-
self._draw_surface = dm_render.Renderer(
163-
max_width=_MAX_RENDERBUFFER_SIZE, max_height=_MAX_RENDERBUFFER_SIZE)
164-
self._renderer = dm_viewer.renderer.OffScreenRenderer(
165-
physics.model, self._draw_surface)
166-
167-
self._viewer.initialize(physics, self._renderer, touchpad=False)
168-
169-
def run_frame(self):
170-
"""Renders one frame of the simulation.
171-
172-
NOTE: This is extremely slow at the moment.
173-
"""
174-
# pylint: disable=protected-access
175-
glfw = dm_viewer.gui.glfw_gui.glfw
176-
glfw_window = self._window._context.window
177-
if glfw.window_should_close(glfw_window):
178-
sys.exit(0)
179-
180-
self._viewport.set_size(*self._window.shape)
181-
self._viewer.render()
182-
pixels = self._renderer.pixels
183-
184-
with self._window._context.make_current() as ctx:
185-
ctx.call(self._window._update_gui_on_render_thread, glfw_window,
186-
pixels)
187-
self._window._mouse.process_events()
188-
self._window._keyboard.process_events()
189-
# pylint: enable=protected-access
117+
self._window = None

robohive/renderer/mjpy_renderer.py

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,21 +23,24 @@ def __init__(self, sim):
2323
self._onscreen_renderer = None
2424
self._offscreen_renderer = None
2525

26+
2627
def render_to_window(self):
2728
"""Renders the simulation to a window."""
2829
if not self._onscreen_renderer:
2930
self._onscreen_renderer = mujoco_py.MjViewer(self._sim)
3031
self._update_camera_properties(self._onscreen_renderer.cam)
3132

32-
self._onscreen_renderer.render()
33+
self.refresh_window()
3334
# self._onscreen_renderer.cam.azimuth+=.1 # trick to rotate camera for 360 videos
3435

36+
3537
def refresh_window(self):
3638
"""Refreshes the rendered window if one is present."""
3739
if self._onscreen_renderer is None:
3840
return
3941
self._onscreen_renderer.render()
4042

43+
4144
def render_offscreen(self,
4245
width: int,
4346
height: int,

setup.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ def package_files(directory):
5353
extras_require={
5454
# To use mujoco bindings, run (pip install -e ".[mujoco]") and set sim_backend=MUJOCO
5555
'mujoco':[
56-
'mujoco==2.3.3',
56+
'mujoco==2.3.5',
5757
'dm-control==1.0.11'
5858
],
5959
# To use hardware dependencies, run (pip install -e ".[a0]") and follow install instructions inside robot

0 commit comments

Comments
 (0)