robomimic.envs package#

Submodules#

robomimic.envs.env_base module#

This file contains the base class for environment wrappers that are used to provide a standardized environment API for training policies and interacting with metadata present in datasets.

class robomimic.envs.env_base.EnvBase(env_name, render=False, render_offscreen=False, use_image_obs=False, postprocess_visual_obs=True, **kwargs)#

Bases: abc.ABC

A base class method for environments used by this repo.

abstract property action_dimension#

Returns dimension of actions (int).

abstract classmethod create_for_data_processing(camera_names, camera_height, camera_width, reward_shaping, **kwargs)#

Create environment for processing datasets, which includes extracting observations, labeling dense / sparse rewards, and annotating dones in transitions.

Parameters
  • camera_names ([str]) – list of camera names that correspond to image observations

  • camera_height (int) – camera height for all cameras

  • camera_width (int) – camera width for all cameras

  • reward_shaping (bool) – if True, use shaped environment rewards, else use sparse task completion rewards

Returns

env (EnvBase instance)

abstract get_goal()#

Get goal observation. Not all environments support this.

abstract get_observation()#

Get environment observation

abstract get_reward()#

Get current reward.

abstract get_state()#

Get environment simulator state, compatible with @reset_to

abstract is_done()#

Check if the task is done (not necessarily successful).

abstract is_success()#

Check if the task condition(s) is reached. Should return a dictionary { str: bool } with at least a “task” key for the overall task success, and additional optional keys corresponding to other task criteria.

abstract property name#

Returns name of environment name (str).

abstract render(mode='human', height=None, width=None, camera_name=None)#

Render

abstract reset()#

Reset environment.

Returns

initial observation dictionary.

Return type

observation (dict)

abstract reset_to(state)#

Reset to a specific simulator state.

Parameters

state (dict) – current simulator state

Returns

observation dictionary after setting the simulator state

Return type

observation (dict)

abstract property rollout_exceptions#

Return tuple of exceptions to except when doing rollouts. This is useful to ensure that the entire training run doesn’t crash because of a bad policy that causes unstable simulation computations.

abstract serialize()#

Save all information needed to re-instantiate this environment in a dictionary. This is the same as @env_meta - environment metadata stored in hdf5 datasets, and used in utils/env_utils.py.

abstract set_goal(**kwargs)#

Set goal observation with external specification. Not all environments support this.

abstract step(action)#

Step in the environment with an action.

Parameters

action (np.array) – action to take

Returns

new observation dictionary reward (float): reward for this step done (bool): whether the task is done info (dict): extra information

Return type

observation (dict)

abstract property type#

Returns environment type (int) for this kind of environment. This helps identify this env class.

class robomimic.envs.env_base.EnvType#

Bases: object

Holds environment types - one per environment class. These act as identifiers for different environments.

GYM_TYPE = 2#
IG_MOMART_TYPE = 3#
ROBOSUITE_TYPE = 1#

robomimic.envs.env_gym module#

robomimic.envs.env_ig_momart module#

robomimic.envs.env_robosuite module#

This file contains the robosuite environment wrapper that is used to provide a standardized environment API for training policies and interacting with metadata present in datasets.

class robomimic.envs.env_robosuite.EnvRobosuite(env_name, render=False, render_offscreen=False, use_image_obs=False, postprocess_visual_obs=True, **kwargs)#

Bases: robomimic.envs.env_base.EnvBase

Wrapper class for robosuite environments (https://github.com/ARISE-Initiative/robosuite)

property action_dimension#

Returns dimension of actions (int).

classmethod create_for_data_processing(env_name, camera_names, camera_height, camera_width, reward_shaping, **kwargs)#

Create environment for processing datasets, which includes extracting observations, labeling dense / sparse rewards, and annotating dones in transitions.

Parameters
  • env_name (str) – name of environment

  • camera_names (list of str) – list of camera names that correspond to image observations

  • camera_height (int) – camera height for all cameras

  • camera_width (int) – camera width for all cameras

  • reward_shaping (bool) – if True, use shaped environment rewards, else use sparse task completion rewards

get_goal()#

Get goal observation. Not all environments support this.

get_observation(di=None)#

Get current environment observation dictionary.

Parameters

di (dict) – current raw observation dictionary from robosuite to wrap and provide as a dictionary. If not provided, will be queried from robosuite.

get_reward()#

Get current reward.

get_state()#

Get current environment simulator state as a dictionary. Should be compatible with @reset_to.

is_done()#

Check if the task is done (not necessarily successful).

is_success()#

Check if the task condition(s) is reached. Should return a dictionary { str: bool } with at least a “task” key for the overall task success, and additional optional keys corresponding to other task criteria.

property name#

Returns name of environment name (str).

render(mode='human', height=None, width=None, camera_name='agentview')#

Render from simulation to either an on-screen window or off-screen to RGB array.

Parameters
  • mode (str) – pass “human” for on-screen rendering or “rgb_array” for off-screen rendering

  • height (int) – height of image to render - only used if mode is “rgb_array”

  • width (int) – width of image to render - only used if mode is “rgb_array”

  • camera_name (str) – camera name to use for rendering

reset()#

Reset environment.

Returns

initial observation dictionary.

Return type

observation (dict)

reset_to(state)#

Reset to a specific simulator state.

Parameters

state (dict) – current simulator state that contains one or more of: - states (np.ndarray): initial state of the mujoco environment - model (str): mujoco scene xml

Returns

observation dictionary after setting the simulator state (only

if “states” is in @state)

Return type

observation (dict)

property rollout_exceptions#

Return tuple of exceptions to except when doing rollouts. This is useful to ensure that the entire training run doesn’t crash because of a bad policy that causes unstable simulation computations.

serialize()#

Save all information needed to re-instantiate this environment in a dictionary. This is the same as @env_meta - environment metadata stored in hdf5 datasets, and used in utils/env_utils.py.

set_goal(**kwargs)#

Set goal observation with external specification. Not all environments support this.

step(action)#

Step in the environment with an action.

Parameters

action (np.array) – action to take

Returns

new observation dictionary reward (float): reward for this step done (bool): whether the task is done info (dict): extra information

Return type

observation (dict)

property type#

Returns environment type (int) for this kind of environment. This helps identify this env class.

Module contents#