Rendering#
Gymnasium-Planar-Robotics offers various viewers for 2D and 3D rendering as well as off-screen rendering.
3D Viewer and Off-Screen Rendering#
- class gymnasium_planar_robotics.utils.rendering.MujocoViewerCollection(model: MjModel, data: MjData, default_cam_config: dict | None = None, width_no_camera_specified: int = 1240, height_no_camera_specified: int = 1080, use_mj_passive_viewer: bool = False)[source]
A manager for all renderers for a MuJoCo environment. It provides the possibility to manage one renderer with render_mode ‘human’ and multiple offscreen renderers.
- Parameters:
model – mjModel of the MuJoCo environment
data – mjData of the MuJoCo environment
default_cam_config – dictionary with attribute values of the viewer’s default camera (see https://mujoco.readthedocs.io/en/latest/XMLreference.html?highlight=camera#visual-global), defaults to None
width_no_camera_specified – if render_mode != ‘human’ and no width is specified, this value is used, defaults to 1240
height_no_camera_specified – if render_mode != ‘human’ and no height is specified, this value is used, defaults to 1080
use_mj_passive_viewer – whether the MuJoCo passive_viewer should be used, defaults to False. If set to False, the Gymnasium MuJoCo WindowViewer with custom overlays is used.
- close()
Close the OpenGL rendering contexts of all viewer modes
- reload_model(model: MjModel, data: MjData) None [source]
Reload the model and data of each viewer. The intended use of this method is as follows: Some environments contain objects with changing parameters, e.g. mass, friction coefficients, size or shape. To train a RL agent that generalizes to new objects, it can be desirable to change the object’s parameters when
env.reset()
is called. To ensure that the MuJoCo simulation behaves as intended, a new model XML string should be generated and loaded. In this case, the viewer also needs to be updated, which is possible with this method.- Parameters:
model – the new mjModel of the MuJoCo environment
data – the new mjData of the MuJoCo environment
- render(render_mode: str, camera_id: int | None = None, camera_name: str | None = None, width: int = 64, height: int = 64, geomgroup: ndarray | None = None) ndarray | None [source]
Render a frame of the specified camera.
- Parameters:
render_mode – ‘human’, ‘rgb_array’ or ‘depth_array’
camera_id – the id of the camera used for rendering (only used if render_mode != ‘human’), defaults to None
camera_name – the name of the camera used for rendering (only used if render_mode != ‘human’), defaults to None. You cannot specify both camera_id and camera_name.
width – width of the OpenGL rendering context (only used if render_mode != ‘human’), defaults to 64
height – height of the OpenGL rendering context (only used if render_mode != ‘human’), defaults to 64
geomgroup – a numpy array of shape (6,), where each entry is either 0 or 1, specifying the groups of geoms to be rendered by the camera (only used if render_mode != ‘human’), defaults to None (vopt.geomgroup is not changed)
- Raises:
ValueError – if render_mode != ‘human’ and
camera_id
andcamera_name
are specified at the same time- Returns:
returns a numpy array if render_mode != ‘human’, otherwise it returns None (render_mode ‘human’)
- window_viewer_is_running() bool [source]
Check whether the window renderer (render_mode ‘human’) is active, i.e. the window is open.
- Returns:
True if the window is open, False otherwise
- class gymnasium_planar_robotics.utils.rendering.MujocoOffScreenViewer(model: MjModel, data: MjData, width: int, height: int, geomgroup: ndarray | None = None)[source]
An extension of the Gymnasium OffScreenViewer which allows to also specify the groups of geoms to be rendered by the offscreen renderer.
- Parameters:
model – mjModel of the MuJoCo environment
data – mjData of the MuJoCo environment
width – width of the OpenGL rendering context
height – height of the OpenGL rendering context
geomgroup – a numpy array of shape (6,), where each entry is either 0 or 1, specifying the groups of geoms to be rendered by the camera, defaults to None (vopt.geomgroup is not changed)
- add_overlay(gridpos: int, text1: str, text2: str)
Overlays text on the scene.
- close()
Override close in your rendering subclass to perform any necessary cleanup after env.close() is called.
- set_geomgroup(geomgroup: ndarray) None [source]
Set the groups of geoms that should be rendered.
- Parameters:
geomgroup – a numpy array of shape (6,), where each entry is either 0 or 1, specifying the groups of geoms to be rendered by the camera
2D Matplotlib Viewer#
Note
The 2D viewer is intended for debugging and analyzing certain situations during motion planning. Therefore, it is not a 2D equivalent to the 3D viewer, but rather a simplified version of it that only displays the tile layout, the movers, and their collision shapes/offsets. Other objects that may be part of an environment are not displayed.
- class gymnasium_planar_robotics.utils.rendering.Matplotlib2DViewer(layout_tiles: ndarray, num_movers: int, mover_sizes: ndarray, mover_colors: list[str], tile_size: ndarray, x_pos_tiles: ndarray, y_pos_tiles: ndarray, c_shape: str = 'circle', c_size: ndarray | float = 0.11, c_size_offset: float = 0.0, arrow_scale: float = 0.3, figure_size: tuple = (7, 7))[source]
A class to easily plot the tile and mover configuration along with the mover collision offsets using matplotlib. This class should primarily be used for debugging and analysis of specific planning situations. It is not included in the MujocoViewerCollection, as it offers fewer possibilities compared to the MuJoCo 3D Viewer (render_mode ‘human’). Thus, it must be integrated into the environment by the user, e.g. using the
render_callback()
.- Parameters:
layout_tiles – a numpy array of shape (num_tiles_x, num_tiles_y) indicating where to add a tile (use 1 to add a tile and 0 to leave cell empty). The x-axis and y-axis correspond to the axes of the numpy array, so the origin of the base frame is in the upper left corner.
num_movers – the number of movers to plot
mover_sizes – a numpy array of shape (3,) or (num_movers,3) specifying the half-sizes of each mover (x,y,z)
mover_colors – a list of strings specifying a color for each mover
tile_size – a numpy array of shape (3,) specifying the half-sizes of a tile (x,y,z)
x_pos_tiles – the x-positions of the tiles specified as a numpy array of shape (num_tiles_x, num_tiles_y)
y_pos_tiles – the y-positions of the tiles specified as a numpy array of shape (num_tiles_x, num_tiles_y)
c_shape – collision shape; can be ‘box’ or ‘circle’, defaults to ‘circle’
c_size –
the size of the collision shape, defaults to 0.11:
- collision shape ‘circle’:
a single float value which corresponds to the radius of the circle, or a numpy array of shape (num_movers,) to specify individual values for each mover
- collision shape ‘box’:
a numpy array of shape (2,) to specify x and y half-size of the box, or a numpy array of shape (num_movers, 2) to specify individual sizes for each mover
c_size_offset – an additional safety offset that is added to the size of the collision shape, defaults to 0.0. Think of this offset as increasing the size of a mover by a safety margin.
arrow_scale – the scaling factor of the arrow length, which displays the current (x,y)-velocity of a mover, defaults to 0.3
figure_size – the size of the matplotlib figure, defaults to (7,7)
- close()[source]
Close the figure.
- render(mover_qpos: ndarray, mover_qvel: ndarray, mover_goals: ndarray | None = None) None [source]
Render the next frame.
- Parameters:
mover_qpos – a numpy array of shape (num_movers,7) containing the qpos (x_p,y_p,z_p,w_o,x_o,y_o,z_o) of each mover
mover_qvel – a numpy array of shape (num_movers,6) containing the qvel (x,y,z,a,b,c) of each mover
mover_goals – None or a numpy array of shape (num_movers,2) containing the (x,y) goal positions of each mover, defaults to None. If set to None, no goals are displayed.