import distutils.util 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.')
# Configure dm_control to use the EGL rendering backend (requires GPU) %env MUJOCO_GL=egl
print('Checking that the dm_control installation succeeded...') try: from dm_control import suite env = suite.load('cartpole', 'swingup') pixels = env.physics.render() 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".') else: del pixels, suite
#@title All `dm_control` imports required for this tutorial
# The basic mujoco wrapper. from dm_control import mujoco
# Access to enums and MuJoCo library functions. from dm_control.mujoco.wrapper.mjbindings import enums from dm_control.mujoco.wrapper.mjbindings import mjlib
# PyMJCF from dm_control import mjcf
# Composer high level imports from dm_control import composer from dm_control.composer.observation import observable from dm_control.composer import variation
# Imports for Composer tutorial example from dm_control.composer.variation import distributions from dm_control.composer.variation import noises from dm_control.locomotion.arenas import floors
# Control Suite from dm_control import suite
# Run through corridor example from dm_control.locomotion.walkers import cmu_humanoid from dm_control.locomotion.arenas import corridors as corridor_arenas from dm_control.locomotion.tasks import corridors as corridor_tasks
# Soccer from dm_control.locomotion import soccer
# Manipulation from dm_control import manipulation
# General import copy import os import itertools from IPython.display import clear_output import numpy as np
# Graphics-related import matplotlib import matplotlib.animation as animation import matplotlib.pyplot as plt from IPython.display import HTML import PIL.Image # Internal loading of video libraries.
# Use svg backend for figure rendering %config InlineBackend.figure_format = 'svg'
# Font sizes SMALL_SIZE = 8 MEDIUM_SIZE = 10 BIGGER_SIZE = 12 plt.rc('font', size=SMALL_SIZE) # controls default text sizes plt.rc('axes', titlesize=SMALL_SIZE) # fontsize of the axes title plt.rc('axes', labelsize=MEDIUM_SIZE) # fontsize of the x and y labels plt.rc('xtick', labelsize=SMALL_SIZE) # fontsize of the tick labels plt.rc('ytick', labelsize=SMALL_SIZE) # fontsize of the tick labels plt.rc('legend', fontsize=SMALL_SIZE) # legend fontsize plt.rc('figure', titlesize=BIGGER_SIZE) # fontsize of the figure title
# Inline video helper function if os.environ.get('COLAB_NOTEBOOK_TEST', False): # We skip video generation during tests, as it is quite expensive. display_video = lambda *args, **kwargs: None else: defdisplay_video(frames, framerate=30): height, width, _ = frames[0].shape dpi = 70 orig_backend = matplotlib.get_backend() matplotlib.use('Agg') # Switch to headless 'Agg' to inhibit figure rendering. fig, ax = plt.subplots(1, 1, figsize=(width / dpi, height / dpi), dpi=dpi) matplotlib.use(orig_backend) # Switch back to the original backend. ax.set_axis_off() ax.set_aspect('equal') ax.set_position([0, 0, 1, 1]) im = ax.imshow(frames[0]) defupdate(frame): im.set_data(frame) return [im] interval = 1000/framerate anim = animation.FuncAnimation(fig=fig, func=update, frames=frames, interval=interval, blit=True, repeat=False) return HTML(anim.to_html5_video())
# Seed numpy's global RNG so that cell outputs are deterministic. We also try to # use RandomState instances that are local to a single cell wherever possible. np.random.seed(42)
# depth is a float array, in meters. depth = physics.render(depth=True) # Shift nearest values to the origin. depth -= depth.min() # Scale by 2 mean distances of near rays. depth /= 2*depth[depth <= 1].mean() # Scale to [0, 255] pixels = 255*np.clip(depth, 0, 1) PIL.Image.fromarray(pixels.astype(np.uint8))
seg = physics.render(segmentation=True) # Display the contents of the first channel, which contains object # IDs. The second channel, seg[:, :, 1], contains object types. geom_ids = seg[:, :, 0] # Infinity is mapped to -1 geom_ids = geom_ids.astype(np.float64) + 1 # Scale to [0, 1] geom_ids = geom_ids / geom_ids.max() pixels = 255*geom_ids PIL.Image.fromarray(pixels.astype(np.uint8))
#@title Projecting from world to camera coordinates {vertical-output: true}
# Get the world coordinates of the box corners box_pos = physics.named.data.geom_xpos['red_box'] box_mat = physics.named.data.geom_xmat['red_box'].reshape(3, 3) box_size = physics.named.model.geom_size['red_box'] offsets = np.array([-1, 1]) * box_size[:, None] xyz_local = np.stack(itertools.product(*offsets)).T xyz_global = box_pos[:, None] + box_mat @ xyz_local
# Camera matrices multiply homogenous [x, y, z, 1] vectors. corners_homogeneous = np.ones((4, xyz_global.shape[1]), dtype=float) corners_homogeneous[:3, :] = xyz_global
# Get the camera matrix. camera = mujoco.Camera(physics) camera_matrix = camera.matrix
# Project world coordinates into pixel space. See: # https://en.wikipedia.org/wiki/3D_projection#Mathematical_formula xs, ys, s = camera_matrix @ corners_homogeneous # x and y are in the pixel coordinate system. x = xs / s y = ys / s
# Render the camera view and overlay the projected corner coordinates. pixels = camera.render() fig, ax = plt.subplots(1, 1) ax.imshow(pixels) ax.plot(x, y, '+', c='w') ax.set_axis_off()
# Simulate and save data physics.reset(0) while physics.data.time < duration: physics.step() timevals.append(physics.data.time) angular_velocity.append(physics.data.qvel[3:6].copy()) stem_height.append(physics.named.data.geom_xpos['stem', 'z'])
defmake_creature(num_legs): """Constructs a creature with `num_legs` legs.""" rgba = random_state.uniform([0, 0, 0, 1], [1, 1, 1, 1]) model = mjcf.RootElement() model.compiler.angle = 'radian'# Use radians.
# Make the torso geom. model.worldbody.add( 'geom', name='torso', type='ellipsoid', size=BODY_SIZE, rgba=rgba)
# Attach legs to equidistant sites on the circumference. for i inrange(num_legs): theta = 2 * i * np.pi / num_legs hip_pos = BODY_RADIUS * np.array([np.cos(theta), np.sin(theta), 0]) hip_site = model.worldbody.add('site', pos=hip_pos, euler=[0, 0, theta]) leg = Leg(length=BODY_RADIUS, rgba=rgba) hip_site.attach(leg.model)
# Instantiate 6 creatures with 3 to 8 legs. creatures = [make_creature(num_legs=num_legs) for num_legs inrange(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, model inenumerate(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_site.attach(model).add('freejoint')
# Instantiate the physics and render. physics = mjcf.Physics.from_mjcf_model(arena) PIL.Image.fromarray(physics.render())
#@title Random initialiser using `composer.variation`
classUniformCircle(variation.Variation): """A uniformly sampled horizontal point on a circle of radius `distance`.""" def__init__(self, distance): self._distance = distance self._heading = distributions.Uniform(0, 2*np.pi)
for i, key inenumerate(time_step.observation): data = np.asarray([observations[j][key] for j inrange(len(observations))]) ax[i+1].plot(ticks, data, label=key) ax[i+1].set_ylabel(key)
#@title Visualizing an initial state of one task per domain in the Control Suite domains_tasks = {domain: task for domain, task in suite.ALL_TASKS} random_state = np.random.RandomState(42) num_domains = len(domains_tasks) n_col = num_domains // int(np.sqrt(num_domains)) n_row = num_domains // n_col + int(0 < num_domains % n_col) _, ax = plt.subplots(n_row, n_col, figsize=(12, 12)) for a in ax.flat: a.axis('off') a.grid(False)
print(f'Iterating over all {num_domains} domains in the Suite:') for j, [domain, task] inenumerate(domains_tasks.items()): print(domain, task)
# Step the environment through a full episode using random actions and record # the camera observations. frames = [] timestep = env.reset() frames.append(timestep.observation['front_close']) whilenot timestep.last(): timestep = env.step(sample_random_action()) frames.append(timestep.observation['front_close']) all_frames = np.concatenate(frames, axis=0) display_video(all_frames, 30)