robosuite.utils package

Submodules

robosuite.utils.buffers module

Collection of Buffer objects with general functionality

class robosuite.utils.buffers.Buffer

Bases: object

Abstract class for different kinds of data buffers. Minimum API should have a “push” and “clear” method

clear()
push(value)

Pushes a new @value to the buffer

Parameters

value – Value to push to the buffer

class robosuite.utils.buffers.DelayBuffer(dim, length)

Bases: robosuite.utils.buffers.RingBuffer

Modified RingBuffer that returns delayed values when polled

get_delayed_value(delay)

Returns value @delay increments behind most recent value.

Parameters

delay (int) – How many steps backwards from most recent value to grab value. Note that this should not be greater than the buffer’s length

Returns

delayed value

Return type

np.array

class robosuite.utils.buffers.DeltaBuffer(dim, init_value=None)

Bases: robosuite.utils.buffers.Buffer

Simple 2-length buffer object to streamline grabbing delta values between “current” and “last” values

Constructs delta object.

Parameters
  • dim (int) – Size of numerical arrays being inputted

  • init_value (None or Iterable) – Initial value to fill “last” value with initially. If None (default), last array will be filled with zeros

property average

Returns the average between the current and last value

Returns

Averaged value of all elements in buffer

Return type

float or np.array

clear()

Clears last and current value

property delta

Returns the delta between last value and current value. If abs_value is set to True, then returns the absolute value between the values

Parameters

abs_value (bool) – Whether to return absolute value or not

Returns

difference between current and last value

Return type

float or np.array

push(value)

Pushes a new value into the buffer; current becomes last and @value becomes current

Parameters

value (int or float or array) – Value(s) to push into the array (taken as a single new element)

class robosuite.utils.buffers.RingBuffer(dim, length)

Bases: robosuite.utils.buffers.Buffer

Simple RingBuffer object to hold values to average (useful for, e.g.: filtering D component in PID control)

Note that the buffer object is a 2D numpy array, where each row corresponds to individual entries into the buffer

Parameters
  • dim (int) – Size of entries being added. This is, e.g.: the size of a state vector that is to be stored

  • length (int) – Size of the ring buffer

property average

Gets the average of components in buffer

Returns

Averaged value of all elements in buffer

Return type

float or np.array

clear()

Clears buffer and reset pointer

property current

Gets the most recent value pushed to the buffer

Returns

Most recent value in buffer

Return type

float or np.array

push(value)

Pushes a new value into the buffer

Parameters

value (int or float or array) – Value(s) to push into the array (taken as a single new element)

robosuite.utils.camera_utils module

This module includes:

  • Utility classes for modifying sim cameras

  • Utility functions for performing common camera operations such as retrieving

camera matrices and transforming from world to camera frame or vice-versa.

class robosuite.utils.camera_utils.CameraMover(env, camera='frontview', init_camera_pos=None, init_camera_quat=None)

Bases: object

A class for manipulating a camera.

WARNING: This class will initially RE-INITIALIZE the environment.

Parameters
  • env (MujocoEnv) – Mujoco environment to modify camera

  • camera (str) – Which camera to mobilize during playback, e.g.: frontview, agentview, etc.

  • init_camera_pos (None or 3-array) – If specified, should be the (x,y,z) global cartesian pos to initialize camera to

  • init_camera_quat (None or 4-array) – If specified, should be the (x,y,z,w) global quaternion orientation to initialize camera to

get_camera_pose()

Grab the current camera pose, which optionally includes position and / or quaternion

Returns

  • 3-array: (x,y,z) camera global cartesian pos

  • 4-array: (x,y,z,w) camera global quaternion orientation

Return type

2-tuple

modify_xml_for_camera_movement(xml, camera_name)

Cameras in mujoco are ‘fixed’, so they can’t be moved by default. Although it’s possible to hack position movement, rotation movement does not work. An alternative is to attach a camera to a mocap body, and move the mocap body.

This function modifies the camera with name @camera_name in the xml by attaching it to a mocap body that can move around freely. In this way, we can move the camera by moving the mocap body.

See http://www.mujoco.org/forum/index.php?threads/move-camera.2201/ for further details.

Parameters
  • xml (str) – Mujoco sim XML file as a string

  • camera_name (str) – Name of camera to tune

move_camera(direction, scale)

Move the camera view along a direction (in the camera frame).

Parameters
  • direction (3-array) – direction vector for where to move camera in camera frame

  • scale (float) – how much to move along that direction

rotate_camera(point, axis, angle)

Rotate the camera view about a direction (in the camera frame).

Parameters
  • point (None or 3-array) – (x,y,z) cartesian coordinates about which to rotate camera in camera frame. If None, assumes the point is the current location of the camera

  • axis (3-array) – (ax,ay,az) axis about which to rotate camera in camera frame

  • angle (float) – how much to rotate about that direction

Returns

pos: (x,y,z) updated camera position quat: (x,y,z,w) updated camera quaternion orientation

Return type

2-tuple

set_camera_pose(pos=None, quat=None)

Sets the camera pose, which optionally includes position and / or quaternion

Parameters
  • pos (None or 3-array) – If specified, should be the (x,y,z) global cartesian pos to set camera to

  • quat (None or 4-array) – If specified, should be the (x,y,z,w) global quaternion orientation to set camera to

class robosuite.utils.camera_utils.DemoPlaybackCameraMover(demo, env_config=None, replay_from_actions=False, visualize_sites=False, camera='frontview', init_camera_pos=None, init_camera_quat=None, use_dr=False, dr_args=None)

Bases: robosuite.utils.camera_utils.CameraMover

A class for playing back demonstrations and recording the resulting frames with the flexibility of a mobile camera that can be set manually or panned automatically frame-by-frame

Note: domain randomization is also supported for playback!

Parameters
  • demo (str) – absolute fpath to .hdf5 demo

  • env_config (None or dict) – (optional) values to override inferred environment information from demonstration. (e.g.: camera h / w, depths, segmentations, etc…) Any value not specified will be inferred from the extracted demonstration metadata Note that there are some specific arguments that MUST be set a certain way, if any of these values are specified with @env_config, an error will be raised

  • replay_from_actions (bool) – If True, will replay demonstration’s actions. Otherwise, replays will be hardcoded from the demonstration states

  • visualize_sites (bool) – If True, will visualize sites during playback. Note that this CANNOT be paired simultaneously with camera segmentations

  • camera (str) – Which camera to mobilize during playback, e.g.: frontview, agentview, etc.

  • init_camera_pos (None or 3-array) – If specified, should be the (x,y,z) global cartesian pos to initialize camera to

  • init_camera_quat (None or 4-array) – If specified, should be the (x,y,z,w) global quaternion orientation to initialize camera to

  • use_dr (bool) – If True, will use domain randomization during playback

  • dr_args (None or dict) – If specified, will set the domain randomization wrapper arguments if using dr

grab_episode_frames(demo_num, pan_point=(0, 0, 0.8), pan_axis=(0, 0, 1), pan_rate=0.01)
Playback entire episode @demo_num, while optionally rotating the camera about point @pan_point and

axis @pan_axis if @pan_rate > 0

Parameters
  • demo_num (int) – Demonstration episode number to load for playback

  • pan_point (3-array) – (x,y,z) cartesian coordinates about which to rotate camera in camera frame

  • pan_direction (3-array) – (ax,ay,az) axis about which to rotate camera in camera frame

  • pan_rate (float) – how quickly to pan camera if not 0

Returns

Keyword-mapped stacked np.arrays from the demonstration sequence, corresponding to all image

modalities used in the playback environment (e.g.: “image”, “depth”, “segmentation_instance”)

Return type

dict

grab_next_frame()

Grabs the next frame in the demo sequence by stepping the simulation and returning the resulting value(s)

Returns

Keyword-mapped np.arrays from the demonstration sequence, corresponding to all image modalities used

in the playback environment (e.g.: “image”, “depth”, “segmentation_instance”)

Return type

dict

load_episode_xml(demo_num)

Loads demo episode with specified @demo_num into the simulator.

Parameters

demo_num (int) – Demonstration number to load

robosuite.utils.camera_utils.bilinear_interpolate(im, x, y)

Bilinear sampling for pixel coordinates x and y from source image im. Taken from https://stackoverflow.com/questions/12729228/simple-efficient-bilinear-interpolation-of-images-in-numpy-and-python

robosuite.utils.camera_utils.get_camera_extrinsic_matrix(sim, camera_name)

Returns a 4x4 homogenous matrix corresponding to the camera pose in the world frame. MuJoCo has a weird convention for how it sets up the camera body axis, so we also apply a correction so that the x and y axis are along the camera view and the z axis points along the viewpoint. Normal camera convention: https://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html

Parameters
  • sim (MjSim) – simulator instance

  • camera_name (str) – name of camera

Returns

4x4 camera extrinsic matrix

Return type

R (np.array)

robosuite.utils.camera_utils.get_camera_intrinsic_matrix(sim, camera_name, camera_height, camera_width)

Obtains camera intrinsic matrix.

Parameters
  • sim (MjSim) – simulator instance

  • camera_name (str) – name of camera

  • camera_height (int) – height of camera images in pixels

  • camera_width (int) – width of camera images in pixels

Returns

3x3 camera matrix

Return type

K (np.array)

robosuite.utils.camera_utils.get_camera_segmentation(sim, camera_name, camera_height, camera_width)

Obtains camera segmentation matrix.

Parameters
  • sim (MjSim) – simulator instance

  • camera_name (str) – name of camera

  • camera_height (int) – height of camera images in pixels

  • camera_width (int) – width of camera images in pixels

Returns

2-channel segmented image where the first contains the

geom types and the second contains the geom IDs

Return type

im (np.array)

robosuite.utils.camera_utils.get_camera_transform_matrix(sim, camera_name, camera_height, camera_width)

Camera transform matrix to project from world coordinates to pixel coordinates.

Parameters
  • sim (MjSim) – simulator instance

  • camera_name (str) – name of camera

  • camera_height (int) – height of camera images in pixels

  • camera_width (int) – width of camera images in pixels

Returns

4x4 camera matrix to project from world coordinates to pixel coordinates

Return type

K (np.array)

robosuite.utils.camera_utils.get_real_depth_map(sim, depth_map)

By default, MuJoCo will return a depth map that is normalized in [0, 1]. This helper function converts the map so that the entries correspond to actual distances.

(see https://github.com/deepmind/dm_control/blob/master/dm_control/mujoco/engine.py#L742)

Parameters
  • sim (MjSim) – simulator instance

  • depth_map (np.array) – depth map with values normalized in [0, 1] (default depth map returned by MuJoCo)

Returns

depth map that corresponds to actual distances

Return type

depth_map (np.array)

robosuite.utils.camera_utils.project_points_from_world_to_camera(points, world_to_camera_transform, camera_height, camera_width)

Helper function to project a batch of points in the world frame into camera pixels using the world to camera transformation.

Parameters
  • points (np.array) – 3D points in world frame to project onto camera pixel locations. Should be shape […, 3].

  • world_to_camera_transform (np.array) – 4x4 Tensor to go from robot coordinates to pixel coordinates.

  • camera_height (int) – height of the camera image

  • camera_width (int) – width of the camera image

Returns

projected pixel indices of shape […, 2]

Return type

pixels (np.array)

robosuite.utils.camera_utils.transform_from_pixels_to_world(pixels, depth_map, camera_to_world_transform)

Helper function to take a batch of pixel locations and the corresponding depth image and transform these points from the camera frame to the world frame.

Parameters
  • pixels (np.array) – pixel coordinates of shape […, 2]

  • depth_map (np.array) – depth images of shape […, H, W, 1]

  • camera_to_world_transform (np.array) – 4x4 Tensor to go from pixel coordinates to world coordinates.

Returns

3D points in robot frame of shape […, 3]

Return type

points (np.array)

robosuite.utils.control_utils module

robosuite.utils.control_utils.nullspace_torques(mass_matrix, nullspace_matrix, initial_joint, joint_pos, joint_vel, joint_kp=10)

For a robot with redundant DOF(s), a nullspace exists which is orthogonal to the remainder of the controllable subspace of the robot’s joints. Therefore, an additional secondary objective that does not impact the original controller objective may attempt to be maintained using these nullspace torques.

This utility function specifically calculates nullspace torques that attempt to maintain a given robot joint positions @initial_joint with zero velocity using proportinal gain @joint_kp

Note

@mass_matrix, @nullspace_matrix, @joint_pos, and @joint_vel should reflect the robot’s state at the current

timestep

Parameters
  • mass_matrix (np.array) – 2d array representing the mass matrix of the robot

  • nullspace_matrix (np.array) – 2d array representing the nullspace matrix of the robot

  • initial_joint (np.array) – Joint configuration to be used for calculating nullspace torques

  • joint_pos (np.array) – Current joint positions

  • joint_vel (np.array) – Current joint velocities

  • joint_kp (float) – Proportional control gain when calculating nullspace torques

Returns

nullspace torques

Return type

np.array

robosuite.utils.control_utils.opspace_matrices(mass_matrix, J_full, J_pos, J_ori)

Calculates the relevant matrices used in the operational space control algorithm

Parameters
  • mass_matrix (np.array) – 2d array representing the mass matrix of the robot

  • J_full (np.array) – 2d array representing the full Jacobian matrix of the robot

  • J_pos (np.array) – 2d array representing the position components of the Jacobian matrix of the robot

  • J_ori (np.array) – 2d array representing the orientation components of the Jacobian matrix of the robot

Returns

  • (np.array): full lambda matrix (as 2d array)

  • (np.array): position components of lambda matrix (as 2d array)

  • (np.array): orientation components of lambda matrix (as 2d array)

  • (np.array): nullspace matrix (as 2d array)

Return type

4-tuple

robosuite.utils.control_utils.orientation_error(desired, current)

This function calculates a 3-dimensional orientation error vector for use in the impedance controller. It does this by computing the delta rotation between the inputs and converting that rotation to exponential coordinates (axis-angle representation, where the 3d vector is axis * angle). See https://en.wikipedia.org/wiki/Axis%E2%80%93angle_representation for more information. Optimized function to determine orientation error from matrices

Parameters
  • desired (np.array) – 2d array representing target orientation matrix

  • current (np.array) – 2d array representing current orientation matrix

Returns

2d array representing orientation error as a matrix

Return type

np.array

robosuite.utils.control_utils.set_goal_orientation(delta, current_orientation, orientation_limit=None, set_ori=None)

Calculates and returns the desired goal orientation, clipping the result accordingly to @orientation_limits. @delta and @current_orientation must be specified if a relative goal is requested, else @set_ori must be an orientation matrix specified to define a global orientation

Parameters
  • delta (np.array) – Desired relative change in orientation, in axis-angle form [ax, ay, az]

  • current_orientation (np.array) – Current orientation, in rotation matrix form

  • orientation_limit (None or np.array) – 2d array defining the (min, max) limits of permissible orientation goal commands

  • set_ori (None or np.array) – If set, will ignore @delta and set the goal orientation to this value

Returns

calculated goal orientation in absolute coordinates

Return type

np.array

Raises

ValueError – [Invalid orientation_limit shape]

robosuite.utils.control_utils.set_goal_position(delta, current_position, position_limit=None, set_pos=None)

Calculates and returns the desired goal position, clipping the result accordingly to @position_limits. @delta and @current_position must be specified if a relative goal is requested, else @set_pos must be specified to define a global goal position

Parameters
  • delta (np.array) – Desired relative change in position

  • current_position (np.array) – Current position

  • position_limit (None or np.array) – 2d array defining the (min, max) limits of permissible position goal commands

  • set_pos (None or np.array) – If set, will ignore @delta and set the goal position to this value

Returns

calculated goal position in absolute coordinates

Return type

np.array

Raises

ValueError – [Invalid position_limit shape]

robosuite.utils.errors module

exception robosuite.utils.errors.RandomizationError

Bases: robosuite.utils.errors.robosuiteError

Exception raised for really really bad RNG.

exception robosuite.utils.errors.SimulationError

Bases: robosuite.utils.errors.robosuiteError

Exception raised for errors during runtime.

exception robosuite.utils.errors.XMLError

Bases: robosuite.utils.errors.robosuiteError

Exception raised for errors related to xml.

exception robosuite.utils.errors.robosuiteError

Bases: Exception

Base class for exceptions in robosuite.

robosuite.utils.input_utils module

Utility functions for grabbing user inputs

robosuite.utils.input_utils.choose_controller()

Prints out controller options, and returns the requested controller name

Returns

Chosen controller name

Return type

str

robosuite.utils.input_utils.choose_environment()

Prints out environment options, and returns the selected env_name choice

Returns

Chosen environment name

Return type

str

robosuite.utils.input_utils.choose_multi_arm_config()

Prints out multi-arm environment configuration options, and returns the requested config name

Returns

Requested multi-arm configuration name

Return type

str

robosuite.utils.input_utils.choose_robots(exclude_bimanual=False)

Prints out robot options, and returns the requested robot. Restricts options to single-armed robots if @exclude_bimanual is set to True (False by default)

Parameters

exclude_bimanual (bool) – If set, excludes bimanual robots from the robot options

Returns

Requested robot name

Return type

str

robosuite.utils.input_utils.input2action(device, robot, active_arm='right', env_configuration=None)

Converts an input from an active device into a valid action sequence that can be fed into an env.step() call

If a reset is triggered from the device, immediately returns None. Else, returns the appropriate action

Parameters
  • device (Device) – A device from which user inputs can be converted into actions. Can be either a Spacemouse or Keyboard device class

  • robot (Robot) – Which robot we’re controlling

  • active_arm (str) – Only applicable for multi-armed setups (e.g.: multi-arm environments or bimanual robots). Allows inputs to be converted correctly if the control type (e.g.: IK) is dependent on arm choice. Choices are {right, left}

  • env_configuration (str or None) – Only applicable for multi-armed environments. Allows inputs to be converted correctly if the control type (e.g.: IK) is dependent on the environment setup. Options are: {bimanual, single-arm-parallel, single-arm-opposed}

Returns

  • (None or np.array): Action interpreted from @device including any gripper action(s). None if we get a

    reset signal from the device

  • (None or int): 1 if desired close, -1 if desired open gripper state. None if get a reset signal from the

    device

Return type

2-tuple

robosuite.utils.macros module

Macro settings that can be imported and toggled. Internally, specific parts of the codebase rely on these settings for determining core functionality.

To make sure global reference is maintained, should import these settings as:

import robosuite.utils.macros as macros

robosuite.utils.mjcf_utils module

class robosuite.utils.mjcf_utils.CustomMaterial(texture, tex_name, mat_name, tex_attrib=None, mat_attrib=None, shared=False)

Bases: object

Simple class to instantiate the necessary parameters to define an appropriate texture / material combo

Instantiates a nested dict holding necessary components for procedurally generating a texture / material combo

Please see http://www.mujoco.org/book/XMLreference.html#asset for specific details on

attributes expected for Mujoco texture / material tags, respectively

Note that the values in @tex_attrib and @mat_attrib can be in string or array / numerical form.

Parameters
  • texture (None or str or 4-array) – Name of texture file to be imported. If a string, should be part of ALL_TEXTURES. If texture is a 4-array, then this argument will be interpreted as an rgba tuple value and a template png will be procedurally generated during object instantiation, with any additional texture / material attributes specified. If None, no file will be linked and no rgba value will be set Note, if specified, the RGBA values are expected to be floats between 0 and 1

  • tex_name (str) – Name to reference the imported texture

  • mat_name (str) – Name to reference the imported material

  • tex_attrib (dict) – Any other optional mujoco texture specifications.

  • mat_attrib (dict) – Any other optional mujoco material specifications.

  • shared (bool) – If True, this material should not have any naming prefixes added to all names

Raises

AssertionError – [Invalid texture]

robosuite.utils.mjcf_utils.add_material(root, naming_prefix='', custom_material=None)

Iterates through all element(s) in @root recursively and adds a material / texture to all visual geoms that don’t already have a material specified.

Parameters
  • root (ET.Element) – Root of the xml element tree to start recursively searching through.

  • naming_prefix (str) – Adds this prefix to all material and texture names

  • custom_material (None or CustomMaterial) – If specified, will add this material to all visual geoms. Else, will add a default “no-change” material.

Returns

(ET.Element, ET.Element, CustomMaterial, bool) (tex_element, mat_element, material, used)

corresponding to the added material and whether the material was actually used or not.

Return type

4-tuple

robosuite.utils.mjcf_utils.add_prefix(root, prefix, tags='default', attribs='default', exclude=None)

Find all element(s) matching the requested @tag, and appends @prefix to all @attributes if they exist.

Parameters
  • root (ET.Element) – Root of the xml element tree to start recursively searching through.

  • prefix (str) – Prefix to add to all specified attributes

  • tags (str or list of str or set) – Tag(s) to search for in this ElementTree. “Default” corresponds to all tags

  • attribs (str or list of str or set) – Element attribute(s) to append prefix to. “Default” corresponds to all attributes that reference names

  • exclude (None or function) – Filtering function that should take in an ET.Element or a string (attribute) and return True if we should exclude the given element / attribute from having any prefixes added

robosuite.utils.mjcf_utils.add_to_dict(dic, fill_in_defaults=True, default_value=None, **kwargs)

Helper function to add key-values to dictionary @dic where each entry is its own array (list). :param dic: Dictionary to which new key / value pairs will be added. If the key already exists,

will append the value to that key entry

Parameters
  • fill_in_defaults (bool) – If True, will automatically add @default_value to all dictionary entries that are not explicitly specified in @kwargs

  • default_value (any) – Default value to fill (None by default)

Returns

Modified dictionary

Return type

dict

robosuite.utils.mjcf_utils.array_to_string(array)

Converts a numeric array into the string format in mujoco.

Examples

[0, 1, 2] => “0 1 2”

Parameters

array (n-array) – Array to convert to a string

Returns

String equivalent of @array

Return type

str

robosuite.utils.mjcf_utils.convert_to_string(inp)
Converts any type of {bool, int, float, list, tuple, array, string, np.str_} into an mujoco-xml compatible string.

Note that an input string / np.str_ results in a no-op action.

Parameters

inp – Input to convert to string

Returns

String equivalent of @inp

Return type

str

robosuite.utils.mjcf_utils.find_elements(root, tags, attribs=None, return_first=True)

Find all element(s) matching the requested @tag and @attributes. If @return_first is True, then will return the first element found matching the criteria specified. Otherwise, will return a list of elements that match the criteria.

Parameters
  • root (ET.Element) – Root of the xml element tree to start recursively searching through.

  • tags (str or list of str or set) – Tag(s) to search for in this ElementTree.

  • attribs (None or dict of str) – Element attribute(s) to check against for a filtered element. A match is considered found only if all attributes match. Each attribute key should have a corresponding value with which to compare against.

  • return_first (bool) – Whether to immediately return once the first matching element is found.

Returns

Matching element(s) found. Returns None if there was no match.

Return type

None or ET.Element or list of ET.Element

robosuite.utils.mjcf_utils.find_parent(root, child)

Find the parent element of the specified @child node, recurisvely searching through @root.

Parameters
  • root (ET.Element) – Root of the xml element tree to start recursively searching through.

  • child (ET.Element) – Child element whose parent is to be found

Returns

Matching parent if found, else None

Return type

None or ET.Element

robosuite.utils.mjcf_utils.get_ids(sim, elements, element_type='geom', inplace=False)

Grabs the mujoco IDs for each element in @elements, corresponding to the specified @element_type.

Parameters
  • sim (MjSim) – Active mujoco simulation object

  • elements (str or list or dict) – Element(s) to convert into IDs. Note that the return type corresponds to @elements type, where each element name is replaced with the ID

  • element_type (str) – The type of element to grab ID for. Options are {geom, body, site}

  • inplace (bool) – If False, will create a copy of @elements to prevent overwriting the original data structure

Returns

IDs corresponding to @elements.

Return type

str or list or dict

robosuite.utils.mjcf_utils.get_size(size, size_max, size_min, default_max, default_min)

Helper method for providing a size, or a range to randomize from

Parameters
  • size (n-array) – Array of numbers that explicitly define the size

  • size_max (n-array) – Array of numbers that define the custom max size from which to randomly sample

  • size_min (n-array) – Array of numbers that define the custom min size from which to randomly sample

  • default_max (n-array) – Array of numbers that define the default max size from which to randomly sample

  • default_min (n-array) – Array of numbers that define the default min size from which to randomly sample

Returns

size generated

Return type

np.array

Raises

ValueError – [Inconsistent array sizes]

robosuite.utils.mjcf_utils.new_actuator(name, joint, act_type='actuator', **kwargs)

Creates an actuator tag with attributes specified by @**kwargs.

Parameters
  • name (str) – Name for this actuator

  • joint (str) – type of actuator transmission. see all types here: http://mujoco.org/book/modeling.html#actuator

  • act_type (str) – actuator type. Defaults to “actuator”

  • **kwargs – Any additional specified attributes for the new joint

Returns

new actuator xml element

Return type

ET.Element

robosuite.utils.mjcf_utils.new_body(name, pos=(0, 0, 0), **kwargs)

Creates a body element with attributes specified by @**kwargs.

Parameters
  • name (str) – Name for this body

  • pos (3-array) – (x,y,z) 3d position of the body frame.

  • **kwargs – Any additional specified attributes for the new body

Returns

new body xml element

Return type

ET.Element

robosuite.utils.mjcf_utils.new_element(tag, name, **kwargs)

Creates a new @tag element with attributes specified by @**kwargs.

Parameters
  • tag (str) – Type of element to create

  • name (None or str) – Name for this element. Should only be None for elements that do not have an explicit name attribute (e.g.: inertial elements)

  • **kwargs – Specified attributes for the new joint

Returns

new specified xml element

Return type

ET.Element

robosuite.utils.mjcf_utils.new_geom(name, type, size, pos=(0, 0, 0), group=0, **kwargs)

Creates a geom element with attributes specified by @**kwargs.

NOTE: With the exception of @geom_type, @size, and @pos, if any arg is set to

None, the value will automatically be popped before passing the values to create the appropriate XML

Parameters
  • name (str) – Name for this geom

  • type (str) – type of the geom. see all types here: http://mujoco.org/book/modeling.html#geom

  • size (n-array of float) – geom size parameters.

  • pos (3-array) – (x,y,z) 3d position of the site.

  • group (int) – the integrer group that the geom belongs to. useful for separating visual and physical elements.

  • **kwargs – Any additional specified attributes for the new geom

Returns

new geom xml element

Return type

ET.Element

robosuite.utils.mjcf_utils.new_inertial(pos=(0, 0, 0), mass=None, **kwargs)

Creates a inertial element with attributes specified by @**kwargs.

Parameters
  • pos (3-array) – (x,y,z) 3d position of the inertial frame.

  • mass (float) – The mass of inertial

  • **kwargs – Any additional specified attributes for the new inertial element

Returns

new inertial xml element

Return type

ET.Element

robosuite.utils.mjcf_utils.new_joint(name, **kwargs)

Creates a joint tag with attributes specified by @**kwargs.

Parameters
  • name (str) – Name for this joint

  • **kwargs – Specified attributes for the new joint

Returns

new joint xml element

Return type

ET.Element

robosuite.utils.mjcf_utils.new_site(name, rgba=[1, 0, 0, 1], pos=(0, 0, 0), size=(0.005,), **kwargs)

Creates a site element with attributes specified by @**kwargs.

NOTE: With the exception of @name, @pos, and @size, if any arg is set to

None, the value will automatically be popped before passing the values to create the appropriate XML

Parameters
  • name (str) – Name for this site

  • rgba (4-array) – (r,g,b,a) color and transparency. Defaults to solid red.

  • pos (3-array) – (x,y,z) 3d position of the site.

  • size (array of float) – site size (sites are spherical by default).

  • **kwargs – Any additional specified attributes for the new site

Returns

new site xml element

Return type

ET.Element

robosuite.utils.mjcf_utils.postprocess_model_xml(xml_str)

This function postprocesses the model.xml collected from a MuJoCo demonstration in order to make sure that the STL files can be found.

Parameters

xml_str (str) – Mujoco sim demonstration XML file as string

Returns

Post-processed xml file as string

Return type

str

robosuite.utils.mjcf_utils.recolor_collision_geoms(root, rgba, exclude=None)

Iteratively searches through all elements starting with @root to find all geoms belonging to group 0 and set the corresponding rgba value to the specified @rgba argument. Note: also removes any material values for these elements.

Parameters
  • root (ET.Element) – Root of the xml element tree to start recursively searching through

  • rgba (4-array) – (R, G, B, A) values to assign to all geoms with this group.

  • exclude (None or function) – Filtering function that should take in an ET.Element and return True if we should exclude the given element / attribute from having its collision geom impacted.

robosuite.utils.mjcf_utils.save_sim_model(sim, fname)

Saves the current model xml from @sim at file location @fname.

Parameters
  • sim (MjSim) – XML file to save, in string form

  • fname (str) – Absolute filepath to the location to save the file

robosuite.utils.mjcf_utils.set_alpha(node, alpha=0.1)

Sets all a(lpha) field of the rgba attribute to be @alpha for @node and all subnodes used for managing display

Parameters
  • node (ET.Element) – Specific node element within XML tree

  • alpha (float) – Value to set alpha value of rgba tuple

robosuite.utils.mjcf_utils.sort_elements(root, parent=None, element_filter=None, _elements_dict=None)

Utility method to iteratively sort all elements based on @tags. This XML ElementTree will be parsed such that all elements with the same key as returned by @element_filter will be grouped as a list entry in the returned dictionary.

Parameters
  • root (ET.Element) – Root of the xml element tree to start recursively searching through

  • parent (ET.Element) – Parent of the root node. Default is None (no parent node initially)

  • element_filter (None or function) – Function used to filter the incoming elements. Should take in two ET.Elements (current_element, parent_element) and return a string filter_key if the element should be added to the list of values sorted by filter_key, and return None if no value should be added. If no element_filter is specified, defaults to self._element_filter.

  • _elements_dict (dict) – Dictionary that gets passed to recursive calls. Should not be modified externally by top-level call.

Returns

Filtered key-specific lists of the corresponding elements

Return type

dict

robosuite.utils.mjcf_utils.string_to_array(string)

Converts a array string in mujoco xml to np.array.

Examples

“0 1 2” => [0, 1, 2]

Parameters

string (str) – String to convert to an array

Returns

Numerical array equivalent of @string

Return type

np.array

robosuite.utils.mjcf_utils.xml_path_completion(xml_path)
Takes in a local xml path and returns a full path.

if @xml_path is absolute, do nothing if @xml_path is not absolute, load xml that is shipped by the package

Parameters

xml_path (str) – local xml path

Returns

Full (absolute) xml path

Return type

str

robosuite.utils.mjmod module

Modder classes used for domain randomization. Largely based off of the mujoco-py implementation below.

https://github.com/openai/mujoco-py/blob/1fe312b09ae7365f0dd9d4d0e453f8da59fae0bf/mujoco_py/modder.py

class robosuite.utils.mjmod.BaseModder(sim, random_state=None)

Bases: object

Base class meant to modify simulation attributes mid-sim.

Using @random_state ensures that sampling here won’t be affected by sampling that happens outside of the modders.

Parameters
  • sim (MjSim) – simulation object

  • random_state (RandomState) – instance of np.random.RandomState, specific seed used to randomize these modifications without impacting other numpy seeds / randomizations

property model

Returns: MjModel: Mujoco sim model

update_sim(sim)

Setter function to update internal sim variable

Parameters

sim (MjSim) – MjSim object

class robosuite.utils.mjmod.CameraModder(sim, random_state=None, camera_names=None, randomize_position=True, randomize_rotation=True, randomize_fovy=True, position_perturbation_size=0.01, rotation_perturbation_size=0.087, fovy_perturbation_size=5.0)

Bases: robosuite.utils.mjmod.BaseModder

Modder for modifying camera attributes in mujoco sim

Parameters
  • sim (MjSim) – MjSim object

  • random_state (None or RandomState) – instance of np.random.RandomState

  • camera_names (None or list of str) – list of camera names to use for randomization. If not provided, all cameras are used for randomization.

  • randomize_position (bool) – if True, randomize camera position

  • randomize_rotation (bool) – if True, randomize camera rotation

  • randomize_fovy (bool) – if True, randomize camera fovy

  • position_perturbation_size (float) – size of camera position perturbations to each dimension

  • rotation_perturbation_size (float) – magnitude of camera rotation perturbations in axis-angle. Default corresponds to around 5 degrees.

  • fovy_perturbation_size (float) – magnitude of camera fovy perturbations (corresponds to focusing)

Raises

AssertionError – [No randomization selected]

get_camid(name)

Grabs unique id number of a specific camera

Parameters

name (str) – Name of the camera

Returns

id of camera. -1 if not found

Return type

int

get_fovy(name)

Grabs fovy of a specific camera

Parameters

name (str) – Name of the camera

Returns

vertical field of view of the camera, expressed in degrees

Return type

float

Raises

AssertionError – Invalid camera name

get_pos(name)

Grabs position of a specific camera

Parameters

name (str) – Name of the camera

Returns

(x,y,z) position of the camera

Return type

np.array

Raises

AssertionError – Invalid camera name

get_quat(name)

Grabs orientation of a specific camera

Parameters

name (str) – Name of the camera

Returns

(w,x,y,z) orientation of the camera, expressed in quaternions

Return type

np.array

Raises

AssertionError – Invalid camera name

randomize()

Randomizes all requested camera values within the sim

restore_defaults()

Reloads the saved parameter values.

save_defaults()

Uses the current MjSim state and model to save default parameter values.

set_fovy(name, value)

Sets fovy of a specific camera

Parameters
  • name (str) – Name of the camera

  • value (float) – vertical field of view of the camera, expressed in degrees

Raises
  • AssertionError – Invalid camera name

  • AssertionError – Invalid value

set_pos(name, value)

Sets position of a specific camera

Parameters
  • name (str) – Name of the camera

  • value (np.array) – (x,y,z) position of the camera

Raises
  • AssertionError – Invalid camera name

  • AssertionError – Invalid value

set_quat(name, value)

Sets orientation of a specific camera

Parameters
  • name (str) – Name of the camera

  • value (np.array) – (w,x,y,z) orientation of the camera, expressed in quaternions

Raises
  • AssertionError – Invalid camera name

  • AssertionError – Invalid value

class robosuite.utils.mjmod.DynamicsModder(sim, random_state=None, randomize_density=True, randomize_viscosity=True, density_perturbation_ratio=0.1, viscosity_perturbation_ratio=0.1, body_names=None, randomize_position=True, randomize_quaternion=True, randomize_inertia=True, randomize_mass=True, position_perturbation_size=0.02, quaternion_perturbation_size=0.02, inertia_perturbation_ratio=0.02, mass_perturbation_ratio=0.02, geom_names=None, randomize_friction=True, randomize_solref=True, randomize_solimp=True, friction_perturbation_ratio=0.1, solref_perturbation_ratio=0.1, solimp_perturbation_ratio=0.1, joint_names=None, randomize_stiffness=True, randomize_frictionloss=True, randomize_damping=True, randomize_armature=True, stiffness_perturbation_ratio=0.1, frictionloss_perturbation_size=0.05, damping_perturbation_size=0.01, armature_perturbation_size=0.01)

Bases: robosuite.utils.mjmod.BaseModder

Modder for various dynamics properties of the mujoco model, such as friction, damping, etc. This can be used to modify parameters stored in MjModel (ie friction, damping, etc.) as well as optimizer parameters stored in PyMjOption (i.e.: medium density, viscosity, etc.) To modify a parameter, use the parameter to be changed as a keyword argument to self.mod and the new value as the value for that argument. Supports arbitrary many modifications in a single step. Example use:

sim = MjSim(…) modder = DynamicsModder(sim) modder.mod(“element1_name”, “attr1”, new_value1) modder.mod(“element2_name”, “attr2”, new_value2) … modder.update()

NOTE: It is necessary to perform modder.update() after performing all modifications to make sure

the changes are propagated

NOTE: A full list of supported randomizable parameters can be seen by calling modder.dynamics_parameters

NOTE: When modifying parameters belonging to MjModel.opt (e.g.: density, viscosity), no name should

be specified (set it as None in mod(…)). This is because opt does not have a name attribute associated with it

Parameters
  • sim (MjSim) – Mujoco sim instance

  • random_state (RandomState) – instance of np.random.RandomState

  • randomize_density (bool) – If True, randomizes global medium density

  • randomize_viscosity (bool) – If True, randomizes global medium viscosity

  • density_perturbation_ratio (float) – Relative (fraction) magnitude of default density randomization

  • viscosity_perturbation_ratio – Relative (fraction) magnitude of default viscosity randomization

  • body_names (None or list of str) – list of bodies to use for randomization. If not provided, all bodies in the model are randomized.

  • randomize_position (bool) – If True, randomizes body positions

  • randomize_quaternion (bool) – If True, randomizes body quaternions

  • randomize_inertia (bool) – If True, randomizes body inertias (only applicable for non-zero mass bodies)

  • randomize_mass (bool) – If True, randomizes body masses (only applicable for non-zero mass bodies)

  • position_perturbation_size (float) – Magnitude of body position randomization

  • quaternion_perturbation_size (float) – Magnitude of body quaternion randomization (angle in radians)

  • inertia_perturbation_ratio (float) – Relative (fraction) magnitude of body inertia randomization

  • mass_perturbation_ratio (float) – Relative (fraction) magnitude of body mass randomization

  • geom_names (None or list of str) – list of geoms to use for randomization. If not provided, all geoms in the model are randomized.

  • randomize_friction (bool) – If True, randomizes geom frictions

  • randomize_solref (bool) – If True, randomizes geom solrefs

  • randomize_solimp (bool) – If True, randomizes geom solimps

  • friction_perturbation_ratio (float) – Relative (fraction) magnitude of geom friction randomization

  • solref_perturbation_ratio (float) – Relative (fraction) magnitude of geom solref randomization

  • solimp_perturbation_ratio (float) – Relative (fraction) magnitude of geom solimp randomization

  • joint_names (None or list of str) – list of joints to use for randomization. If not provided, all joints in the model are randomized.

  • randomize_stiffness (bool) – If True, randomizes joint stiffnesses

  • randomize_frictionloss (bool) – If True, randomizes joint frictionlosses

  • randomize_damping (bool) – If True, randomizes joint dampings

  • randomize_armature (bool) – If True, randomizes joint armatures

  • stiffness_perturbation_ratio (float) – Relative (fraction) magnitude of joint stiffness randomization

  • frictionloss_perturbation_size (float) – Magnitude of joint frictionloss randomization

  • damping_perturbation_size (float) – Magnitude of joint damping randomization

  • armature_perturbation_size (float) – Magnitude of joint armature randomization

property dynamics_parameters

Returns: set: All dynamics parameters that can be randomized using this modder.

mod(name, attr, val)

General method to modify dynamics parameter @attr to be new value @val, associated with element @name.

Parameters
  • name (str) – Name of element to modify parameter. This can be a body, geom, or joint name. If modifying an opt parameter, this should be set to None

  • attr (str) – Name of the dynamics parameter to modify. Valid options are self.dynamics_parameters

  • val (int or float or n-array) – New value(s) to set for the given dynamics parameter. The type of this argument should match the expected type for the given parameter.

mod_armature(name, val)

Modifies the @name’s joint armature within the simulation. See http://www.mujoco.org/book/XMLreference.html#joint for more details.

Parameters
  • name (str) – Name for this element.

  • val (float) – New armature.

mod_damping(name, val)

Modifies the @name’s joint damping within the simulation. See http://www.mujoco.org/book/XMLreference.html#joint for more details.

NOTE: If the requested joint is a free joint, it will be ignored since it does not

make physical sense to have damping associated with this joint (air drag / damping is already captured implicitly by the medium density / viscosity values)

Parameters
  • name (str) – Name for this element.

  • val (float) – New damping.

mod_density(name=None, val=0.0)

Modifies the global medium density of the simulation. See http://www.mujoco.org/book/XMLreference.html#option for more details.

Parameters
  • name (str) – Name for this element. Should be left as None (opt has no name attribute)

  • val (float) – New density value.

mod_friction(name, val)

Modifies the @name’s geom friction within the simulation. See http://www.mujoco.org/book/XMLreference.html#geom for more details.

Parameters
  • name (str) – Name for this element.

  • val (3-array) – New (sliding, torsional, rolling) friction values.

mod_frictionloss(name, val)

Modifies the @name’s joint frictionloss within the simulation. See http://www.mujoco.org/book/XMLreference.html#joint for more details.

NOTE: If the requested joint is a free joint, it will be ignored since it does not

make physical sense to have friction loss associated with this joint (air drag / damping is already captured implicitly by the medium density / viscosity values)

Parameters
  • name (str) – Name for this element.

  • val (float) – New friction loss.

mod_inertia(name, val)

Modifies the @name’s relative body inertia within the simulation. See http://www.mujoco.org/book/XMLreference.html#body for more details.

Parameters
  • name (str) – Name for this element.

  • val (3-array) – New (ixx, iyy, izz) diagonal values in the inertia matrix.

mod_mass(name, val)

Modifies the @name’s mass within the simulation. See http://www.mujoco.org/book/XMLreference.html#body for more details.

Parameters
  • name (str) – Name for this element.

  • val (float) – New mass.

mod_position(name, val=(0, 0, 0))

Modifies the @name’s relative body position within the simulation. See http://www.mujoco.org/book/XMLreference.html#body for more details.

Parameters
  • name (str) – Name for this element.

  • val (3-array) – New (x, y, z) relative position.

mod_quaternion(name, val=(1, 0, 0, 0))

Modifies the @name’s relative body orientation (quaternion) within the simulation. See http://www.mujoco.org/book/XMLreference.html#body for more details.

Note: This method automatically normalizes the inputted value.

Parameters
  • name (str) – Name for this element.

  • val (4-array) – New (w, x, y, z) relative quaternion.

mod_solimp(name, val)

Modifies the @name’s geom contact solver impedance parameters within the simulation. See http://www.mujoco.org/book/modeling.html#CSolver for more details.

Parameters
  • name (str) – Name for this element.

  • val (5-array) – New (dmin, dmax, width, midpoint, power) solimp values.

mod_solref(name, val)

Modifies the @name’s geom contact solver parameters within the simulation. See http://www.mujoco.org/book/modeling.html#CSolver for more details.

Parameters
  • name (str) – Name for this element.

  • val (2-array) – New (timeconst, dampratio) solref values.

mod_stiffness(name, val)

Modifies the @name’s joint stiffness within the simulation. See http://www.mujoco.org/book/XMLreference.html#joint for more details.

NOTE: If the stiffness is already at 0, we IGNORE this value since a non-stiff joint (i.e.: free-turning)

joint is fundamentally different than a stiffened joint)

Parameters
  • name (str) – Name for this element.

  • val (float) – New stiffness.

mod_viscosity(name=None, val=0.0)

Modifies the global medium viscosity of the simulation. See http://www.mujoco.org/book/XMLreference.html#option for more details.

Parameters
  • name (str) – Name for this element. Should be left as None (opt has no name attribute)

  • val (float) – New viscosity value.

property opt

Returns: PyMjOption: MjModel sim options

randomize()

Randomizes all enabled dynamics parameters in the simulation

restore_defaults()

Restores the default values curently saved in this modder

save_defaults()

Grabs the current values for all parameters in sim and stores them as default values

update()

Propagates the changes made up to this point through the simulation

update_sim(sim)

In addition to super method, update internal default values to match the current values from (the presumably new) @sim.

Parameters

sim (MjSim) – MjSim object

class robosuite.utils.mjmod.LightingModder(sim, random_state=None, light_names=None, randomize_position=True, randomize_direction=True, randomize_specular=True, randomize_ambient=True, randomize_diffuse=True, randomize_active=True, position_perturbation_size=0.1, direction_perturbation_size=0.35, specular_perturbation_size=0.1, ambient_perturbation_size=0.1, diffuse_perturbation_size=0.1)

Bases: robosuite.utils.mjmod.BaseModder

Modder to modify lighting within a Mujoco simulation.

Parameters
  • sim (MjSim) – MjSim object

  • random_state (RandomState) – instance of np.random.RandomState

  • light_names (None or list of str) – list of lights to use for randomization. If not provided, all lights in the model are randomized.

  • randomize_position (bool) – If True, randomizes position of lighting

  • randomize_direction (bool) – If True, randomizes direction of lighting

  • randomize_specular (bool) – If True, randomizes specular attribute of lighting

  • randomize_ambient (bool) – If True, randomizes ambient attribute of lighting

  • randomize_diffuse (bool) – If True, randomizes diffuse attribute of lighting

  • randomize_active (bool) – If True, randomizes active nature of lighting

  • position_perturbation_size (float) – Magnitude of position randomization

  • direction_perturbation_size (float) – Magnitude of direction randomization

  • specular_perturbation_size (float) – Magnitude of specular attribute randomization

  • ambient_perturbation_size (float) – Magnitude of ambient attribute randomization

  • diffuse_perturbation_size (float) – Magnitude of diffuse attribute randomization

get_active(name)

Grabs active nature of a specific light source

Parameters

name (str) – Name of the lighting source

Returns

Whether light source is active (1) or not (0)

Return type

int

Raises

AssertionError – Invalid light name

get_ambient(name)

Grabs ambient attribute of a specific light source

Parameters

name (str) – Name of the lighting source

Returns

(r,g,b) ambient color of lighting source

Return type

np.array

Raises

AssertionError – Invalid light name

get_diffuse(name)

Grabs diffuse attribute of a specific light source

Parameters

name (str) – Name of the lighting source

Returns

(r,g,b) diffuse color of lighting source

Return type

np.array

Raises

AssertionError – Invalid light name

get_dir(name)

Grabs direction of a specific light source

Parameters

name (str) – Name of the lighting source

Returns

(x,y,z) direction of lighting source

Return type

np.array

Raises

AssertionError – Invalid light name

get_lightid(name)

Grabs unique id number of a specific light source

Parameters

name (str) – Name of the lighting source

Returns

id of lighting source. -1 if not found

Return type

int

get_pos(name)

Grabs position of a specific light source

Parameters

name (str) – Name of the lighting source

Returns

(x,y,z) position of lighting source

Return type

np.array

Raises

AssertionError – Invalid light name

get_specular(name)

Grabs specular attribute of a specific light source

Parameters

name (str) – Name of the lighting source

Returns

(r,g,b) specular color of lighting source

Return type

np.array

Raises

AssertionError – Invalid light name

randomize()

Randomizes all requested lighting values within the sim

restore_defaults()

Reloads the saved parameter values.

save_defaults()

Uses the current MjSim state and model to save default parameter values.

set_active(name, value)

Sets active nature of a specific light source

Parameters
  • name (str) – Name of the lighting source

  • value (int) – Whether light source is active (1) or not (0)

Raises

AssertionError – Invalid light name

set_ambient(name, value)

Sets ambient attribute of a specific light source

Parameters
  • name (str) – Name of the lighting source

  • value (np.array) – (r,g,b) ambient color to set lighting source to

Raises
  • AssertionError – Invalid light name

  • AssertionError – Invalid @value

set_diffuse(name, value)

Sets diffuse attribute of a specific light source

Parameters
  • name (str) – Name of the lighting source

  • value (np.array) – (r,g,b) diffuse color to set lighting source to

Raises
  • AssertionError – Invalid light name

  • AssertionError – Invalid @value

set_dir(name, value)

Sets direction of a specific light source

Parameters
  • name (str) – Name of the lighting source

  • value (np.array) – (ax,ay,az) direction to set lighting source to

Raises
  • AssertionError – Invalid light name

  • AssertionError – Invalid @value

set_pos(name, value)

Sets position of a specific light source

Parameters
  • name (str) – Name of the lighting source

  • value (np.array) – (x,y,z) position to set lighting source to

Raises
  • AssertionError – Invalid light name

  • AssertionError – Invalid @value

set_specular(name, value)

Sets specular attribute of a specific light source

Parameters
  • name (str) – Name of the lighting source

  • value (np.array) – (r,g,b) specular color to set lighting source to

Raises
  • AssertionError – Invalid light name

  • AssertionError – Invalid @value

class robosuite.utils.mjmod.Texture(model, tex_id)

Bases: object

Helper class for operating on the MuJoCo textures.

Parameters
  • model (MjModel) – Mujoco sim model

  • tex_id (int) – id of specific texture in mujoco sim

property bitmap

Grabs color bitmap associated with this texture from the mujoco sim.

Returns

3d-array representing the rgb texture bitmap

Return type

np.array

height
id
tex_adr
tex_rgb
type
width
class robosuite.utils.mjmod.TextureModder(sim, random_state=None, geom_names=None, randomize_local=False, randomize_material=False, local_rgb_interpolation=0.1, local_material_interpolation=0.2, texture_variations=('rgb', 'checker', 'noise', 'gradient'), randomize_skybox=True)

Bases: robosuite.utils.mjmod.BaseModder

Modify textures in model. Example use:

sim = MjSim(…) modder = TextureModder(sim) modder.whiten_materials() # ensures materials won’t impact colors modder.set_checker(‘some_geom’, (255, 0, 0), (0, 0, 0)) modder.rand_all(‘another_geom’)

Note: in order for the textures to take full effect, you’ll need to set the rgba values for all materials to [1, 1, 1, 1], otherwise the texture colors will be modulated by the material colors. Call the whiten_materials helper method to set all material colors to white.

Parameters
  • sim (MjSim) – MjSim object

  • random_state (RandomState) – instance of np.random.RandomState

  • geom_names ([string]) – list of geom names to use for randomization. If not provided, all geoms are used for randomization.

  • randomize_local (bool) – if True, constrain RGB color variations to be close to the original RGB colors per geom and texture. Otherwise, RGB color values will be sampled uniformly at random.

  • randomize_material (bool) – if True, randomizes material properties associated with a given texture (reflectance, shininess, specular)

  • local_rgb_interpolation (float) – determines the size of color variations from the base geom colors when @randomize_local is True.

  • local_material_interpolation (float) – determines the size of material variations from the base material when @randomize_local and @randomize_material are both True.

  • texture_variations (list of str) – a list of texture variation strings. Each string must be either ‘rgb’, ‘checker’, ‘noise’, or ‘gradient’ and corresponds to a specific kind of texture randomization. For each geom that has a material and texture, a random variation from this list is sampled and applied.

  • randomize_skybox (bool) – if True, apply texture variations to the skybox as well.

get_checker_matrices(name)

Grabs checker pattern matrix associated with @name.

Parameters

name (str) – Name of geom

Returns

3d-array representing rgb checker pattern

Return type

np.array

get_geom_rgb(name)

Grabs rgb color of a specific geom

Parameters

name (str) – Name of the geom

Returns

(r,g,b) geom colors

Return type

np.array

get_material(name)

Grabs material of a specific geom

Parameters

name (str) – Name of the geom

Returns

(reflectance, shininess, specular) material properties associated with the geom

Return type

np.array

get_rand_rgb(n=1)

Grabs a batch of random rgb tuple combos

Parameters

n (int) – How many sets of rgb tuples to randomly generate

Returns

if n > 1, each tuple entry is a rgb tuple. else, single (r,g,b) array

Return type

np.array or n-tuple

get_texture(name)

Grabs texture of a specific geom

Parameters

name (str) – Name of the geom

Returns

texture associated with the geom

Return type

Texture

rand_checker(name)

Generates a random checker pattern for a specific geom

Parameters

name (str) – Name of the geom to randomize for

rand_gradient(name)

Generates a random gradient pattern for a specific geom

Parameters

name (str) – Name of the geom to randomize for

rand_noise(name)

Generates a random RGB noise pattern for a specific geom

Parameters

name (str) – Name of the geom to randomize for

rand_rgb(name)

Generates a random RGB color for a specific geom

Parameters

name (str) – Name of the geom to randomize for

randomize()

Overrides mujoco-py implementation to also randomize color for geoms that have no material.

restore_defaults()

Reloads the saved parameter values.

save_defaults()

Uses the current MjSim state and model to save default parameter values.

set_checker(name, rgb1, rgb2, perturb=False)

Use the two checker matrices to create a checker pattern from the two colors, and set it as the texture for geom @name.

Parameters
  • name (str) – Name of geom

  • rgb1 (3-array) – (r,g,b) value for one half of checker pattern

  • rgb2 (3-array) – (r,g,b) value for other half of checker pattern

  • perturb (bool) – Whether to perturb the resulting checker pattern or not

set_geom_rgb(name, rgb)

Sets rgb color of a specific geom

Parameters
  • name (str) – Name of the geom

  • rgb (np.array) – (r,g,b) geom colors

set_gradient(name, rgb1, rgb2, vertical=True, perturb=False)

Creates a linear gradient from rgb1 to rgb2.

Parameters
  • name (str) – Name of geom

  • rgb1 (3-array) – start color

  • rgb2 (3- array) – end color

  • vertical (bool) – if True, the gradient in the positive y-direction, if False it’s in the positive x-direction.

  • perturb (bool) – Whether to perturb the resulting gradient pattern or not

set_material(name, material, perturb=False)

Sets the material that corresponds to geom @name.

If @perturb is True, then use the computed material to perturb the default material slightly, instead of replacing it.

Parameters
  • name (str) – Name of the geom

  • material (np.array) – (reflectance, shininess, specular) material properties associated with the geom

  • perturb (bool) – Whether to perturb the inputted material properties or not

set_noise(name, rgb1, rgb2, fraction=0.9, perturb=False)

Sets the texture bitmap for geom @name to a noise pattern

Parameters
  • name (str) – name of geom

  • rgb1 (3-array) – background color

  • rgb2 (3-array) – color of random noise foreground color

  • fraction (float) – fraction of pixels with foreground color

  • perturb (bool) – Whether to perturb the resulting color pattern or not

set_rgb(name, rgb, perturb=False)

Just set the texture bitmap for geom @name to a constant rgb value.

Parameters
  • name (str) – Name of geom

  • rgb (3-array) – desired (r,g,b) color

  • perturb (bool) – Whether to perturb the resulting color pattern or not

set_texture(name, bitmap, perturb=False)

Sets the bitmap for the texture that corresponds to geom @name.

If @perturb is True, then use the computed bitmap to perturb the default bitmap slightly, instead of replacing it.

Parameters
  • name (str) – Name of the geom

  • bitmap (np.array) – 3d-array representing rgb pixel-wise values

  • perturb (bool) – Whether to perturb the inputted bitmap or not

upload_texture(name)

Uploads the texture to the GPU so it’s available in the rendering.

Parameters

name (str) – name of geom

whiten_materials()

Extends modder.TextureModder to also whiten geom_rgba

Helper method for setting all material colors to white, otherwise the texture modifications won’t take full effect.

robosuite.utils.numba module

Numba utils.

robosuite.utils.numba.jit_decorator(func)

robosuite.utils.observables module

robosuite.utils.observables.NO_CORRUPTION(inp)
robosuite.utils.observables.NO_DELAY()
robosuite.utils.observables.NO_FILTER(inp)
class robosuite.utils.observables.Observable(name, sensor, corrupter=None, filter=None, delayer=None, sampling_rate=20, enabled=True, active=True)

Bases: object

Base class for all observables – defines interface for interacting with sensors

Parameters
  • name (str) – Name for this observable

  • sensor (function with sensor decorator) – Method to grab raw sensor data for this observable. Should take in a single dict argument (observation cache if a pre-computed value is required) and return the raw sensor data for the current timestep. Must handle case if inputted argument is empty ({}), and should have sensor decorator when defined

  • corrupter (None or function) – Method to corrupt the raw sensor data for this observable. Should take in the output of @sensor and return the same type (corrupted data). If None, results in default no corruption

  • filter (None or function) – Method to filter the outputted reading for this observable. Should take in the output of @corrupter and return the same type (filtered data). If None, results in default no filter. Note that this function can also double as an observer, where sampled data is recorded by this function.

  • delayer (None or function) – Method to delay the raw sensor data when polling this observable. Should take in no arguments and return a float, for the number of seconds to delay the measurement by. If None, results in default no delayer

  • sampling_rate (float) – Sampling rate for this observable (Hz)

  • enabled (bool) – Whether this sensor is enabled or not. If enabled, this observable’s values are continually computed / updated every time update() is called.

  • active (bool) – Whether this sensor is active or not. If active, this observable’s current observed value is returned from self.obs, otherwise self.obs returns None.

is_active()

Determines whether observable is active or not. This observable is considered active if its current observation value is being returned in self.obs.

Returns

True if this observable is active

Return type

bool

is_enabled()

Determines whether observable is enabled or not. This observable is considered enabled if its values are being continually computed / updated during each update() call.

Returns

True if this observable is enabled

Return type

bool

property modality

Modality of this sensor

Returns

Modality name for this observable

Return type

str

property obs

Current observation from this observable

Returns

If active, current observed value from this observable. Otherwise, None

Return type

None or float or np.array

reset()

Resets this observable’s internal values (but does not reset its sensor, corrupter, delayer, or filter)

set_active(active)

Sets whether this observable is active or not. If active, this observable’s current observed value is returned from self.obs, otherwise self.obs returns None.

Parameters

active (bool) – True if this observable should be active

set_corrupter(corrupter)

Sets the corrupter for this observable.

Parameters

corrupter (None or function) – Method to corrupt the raw sensor data for this observable. Should take in the output of self.sensor and return the same type (corrupted data). If None, results in default no corruption

set_delayer(delayer)

Sets the delayer for this observable.

Parameters

delayer (None or function) – Method to delay the raw sensor data when polling this observable. Should take in no arguments and return a float, for the number of seconds to delay the measurement by. If None, results in default no filter

set_enabled(enabled)

Sets whether this observable is enabled or not. If enabled, this observable’s values are continually computed / updated every time update() is called.

Parameters

enabled (bool) – True if this observable should be enabled

set_filter(filter)

Sets the filter for this observable. Note that this function can also double as an observer, where sampled data is recorded by this function.

Parameters

filter (None or function) – Method to filter the outputted reading for this observable. Should take in the output of @corrupter and return the same type (filtered data). If None, results in default no filter

set_sampling_rate(rate)

Sets the sampling rate for this observable.

Parameters

rate (int) – New sampling rate for this observable (Hz)

set_sensor(sensor)

Sets the sensor for this observable.

Parameters

sensor (function with sensor decorator) – Method to grab raw sensor data for this observable. Should take in a single dict argument (observation cache if a pre-computed value is required) and return the raw sensor data for the current timestep. Must handle case if inputted argument is empty ({}), and should have sensor decorator when defined

update(timestep, obs_cache, force=False)

Updates internal values for this observable, if enabled.

Parameters
  • timestep (float) – Amount of simulation time (in sec) that has passed since last call.

  • obs_cache (dict) – Observation cache mapping observable names to pre-computed values to pass to sensor. This will be updated in-place during this call.

  • force (bool) – If True, will force the observable to update its internal value to the newest value.

robosuite.utils.observables.create_deterministic_corrupter(corruption, low=- inf, high=inf)

Creates a deterministic corrupter that applies the same corrupted value to all sensor values

Parameters
  • corruption (float) – Corruption to apply

  • low (float) – Minimum value for output for clipping

  • high (float) – Maximum value for output for clipping

Returns

corrupter

Return type

function

robosuite.utils.observables.create_deterministic_delayer(delay)

Create a deterministic delayer that always returns the same delay value

Parameters

delay (float) – Delay value to return

Returns

delayer

Return type

function

robosuite.utils.observables.create_gaussian_noise_corrupter(mean, std, low=- inf, high=inf)

Creates a corrupter that applies gaussian noise to a given input with mean @mean and std dev @std

Parameters
  • mean (float) – Mean of the noise to apply

  • std (float) – Standard deviation of the noise to apply

  • low (float) – Minimum value for output for clipping

  • high (float) – Maxmimum value for output for clipping

Returns

corrupter

Return type

function

robosuite.utils.observables.create_gaussian_sampled_delayer(mean, std)

Creates a gaussian sampled delayer, with average delay @mean which varies by standard deviation @std

Parameters
  • mean (float) – Average delay

  • std (float) – Standard deviation of the delay variation

Returns

delayer

Return type

function

robosuite.utils.observables.create_uniform_noise_corrupter(min_noise, max_noise, low=- inf, high=inf)

Creates a corrupter that applies uniform noise to a given input within range @low to @high

Parameters
  • min_noise (float) – Minimum noise to apply

  • max_noise (float) – Maximum noise to apply

  • low (float) – Minimum value for output for clipping

  • high (float) – Maxmimum value for output for clipping

Returns

corrupter

Return type

function

robosuite.utils.observables.create_uniform_sampled_delayer(min_delay, max_delay)

Creates uniformly sampled delayer, with minimum delay @low and maximum delay @high, both inclusive

Parameters
  • min_delay (float) – Minimum possible delay

  • max_delay (float) – Maxmimum possible delay

Returns

delayer

Return type

function

robosuite.utils.observables.sensor(modality)

Decorator that should be added to any sensors that will be an observable.

Decorated functions should have signature:

any = func(obs_cache)

Where @obs_cache is a dictionary mapping observable keys to pre-computed values, and @any is either a scalar or array. This function should also handle the case if obs_cache is either None or an empty dict.

An example use case is shown below:

>>> @sensor(modality="proprio")
>>> def joint_pos(obs_cache):
        # Always handle case if obs_cache is empty
        if not obs_cache:
            return np.zeros(7)
        # Otherwise, run necessary calculations and return output
        ...
        out = ...
        return out
Parameters

modality (str) – Modality for this sensor

Returns

decorator function

Return type

function

robosuite.utils.placement_samplers module

class robosuite.utils.placement_samplers.ObjectPositionSampler(name, mujoco_objects=None, ensure_object_boundary_in_range=True, ensure_valid_placement=True, reference_pos=(0, 0, 0), z_offset=0.0)

Bases: object

Base class of object placement sampler.

Parameters
  • name (str) – Name of this sampler.

  • mujoco_objects (None or MujocoObject or list of MujocoObject) – single model or list of MJCF object models

  • ensure_object_boundary_in_range (bool) – If True, will ensure that the object is enclosed within a given boundary (should be implemented by subclass)

  • ensure_valid_placement (bool) – If True, will check for correct (valid) object placements

  • reference_pos (3-array) – global (x,y,z) position relative to which sampling will occur

  • z_offset (float) – Add a small z-offset to placements. This is useful for fixed objects that do not move (i.e. no free joint) to place them above the table.

add_objects(mujoco_objects)

Add additional objects to this sampler. Checks to make sure there’s no identical objects already stored.

Parameters

mujoco_objects (MujocoObject or list of MujocoObject) – single model or list of MJCF object models

reset()

Resets this sampler. Removes all mujoco objects from this sampler.

sample(fixtures=None, reference=None, on_top=True)

Uniformly sample on a surface (not necessarily table surface).

Parameters
  • fixtures (dict) – dictionary of current object placements in the scene as well as any other relevant obstacles that should not be in contact with newly sampled objects. Used to make sure newly generated placements are valid. Should be object names mapped to (pos, quat, MujocoObject)

  • reference (str or 3-tuple or None) – if provided, sample relative placement. Can either be a string, which corresponds to an existing object found in @fixtures, or a direct (x,y,z) value. If None, will sample relative to this sampler’s ‘reference_pos’ value.

  • on_top (bool) – if True, sample placement on top of the reference object.

Returns

dictionary of all object placements, mapping object_names to (pos, quat, obj), including the

placements specified in @fixtures. Note quat is in (w,x,y,z) form

Return type

dict

class robosuite.utils.placement_samplers.SequentialCompositeSampler(name)

Bases: robosuite.utils.placement_samplers.ObjectPositionSampler

Samples position for each object sequentially. Allows chaining multiple placement initializers together - so that object locations can be sampled on top of other objects or relative to other object placements.

Parameters

name (str) – Name of this sampler.

add_objects(mujoco_objects)

Override super method to make sure user doesn’t call this (all objects should implicitly belong to sub-samplers)

add_objects_to_sampler(sampler_name, mujoco_objects)

Adds specified @mujoco_objects to sub-sampler with specified @sampler_name.

Parameters
  • sampler_name (str) – Existing sub-sampler name

  • mujoco_objects (MujocoObject or list of MujocoObject) – Object(s) to add

append_sampler(sampler, sample_args=None)

Adds a new placement initializer with corresponding @sampler and arguments

Parameters
  • sampler (ObjectPositionSampler) – sampler to add

  • sample_args (None or dict) – If specified, should be additional arguments to pass to @sampler’s sample() call. Should map corresponding sampler’s arguments to values (excluding @fixtures argument)

Raises

AssertionError – [Object name in samplers]

hide(mujoco_objects)

Helper method to remove an object from the workspace.

Parameters

mujoco_objects (MujocoObject or list of MujocoObject) – Object(s) to hide

reset()

Resets this sampler. In addition to base method, iterates over all sub-samplers and resets them

sample(fixtures=None, reference=None, on_top=True)

Sample from each placement initializer sequentially, in the order that they were appended.

Parameters
  • fixtures (dict) – dictionary of current object placements in the scene as well as any other relevant obstacles that should not be in contact with newly sampled objects. Used to make sure newly generated placements are valid. Should be object names mapped to (pos, quat, MujocoObject)

  • reference (str or 3-tuple or None) – if provided, sample relative placement. This will override each sampler’s @reference argument if not already specified. Can either be a string, which corresponds to an existing object found in @fixtures, or a direct (x,y,z) value. If None, will sample relative to this sampler’s ‘reference_pos’ value.

  • on_top (bool) – if True, sample placement on top of the reference object. This will override each sampler’s @on_top argument if not already specified. This corresponds to a sampled z-offset of the current sampled object’s bottom_offset + the reference object’s top_offset (if specified)

Returns

dictionary of all object placements, mapping object_names to (pos, quat, obj), including the

placements specified in @fixtures. Note quat is in (w,x,y,z) form

Return type

dict

Raises

RandomizationError – [Cannot place all objects]

class robosuite.utils.placement_samplers.UniformRandomSampler(name, mujoco_objects=None, x_range=(0, 0), y_range=(0, 0), rotation=None, rotation_axis='z', ensure_object_boundary_in_range=True, ensure_valid_placement=True, reference_pos=(0, 0, 0), z_offset=0.0)

Bases: robosuite.utils.placement_samplers.ObjectPositionSampler

Places all objects within the table uniformly random.

Parameters
  • name (str) – Name of this sampler.

  • mujoco_objects (None or MujocoObject or list of MujocoObject) – single model or list of MJCF object models

  • x_range (2-array of float) – Specify the (min, max) relative x_range used to uniformly place objects

  • y_range (2-array of float) – Specify the (min, max) relative y_range used to uniformly place objects

  • rotation (None or float or Iterable) –

    None

    Add uniform random random rotation

    Iterable (a,b)

    Uniformly randomize rotation angle between a and b (in radians)

    value

    Add fixed angle rotation

  • rotation_axis (str) – Can be ‘x’, ‘y’, or ‘z’. Axis about which to apply the requested rotation

  • ensure_object_boundary_in_range (bool) –

    True

    The center of object is at position: [uniform(min x_range + radius, max x_range - radius)], [uniform(min x_range + radius, max x_range - radius)]

    False

    [uniform(min x_range, max x_range)], [uniform(min x_range, max x_range)]

  • ensure_valid_placement (bool) – If True, will check for correct (valid) object placements

  • reference_pos (3-array) – global (x,y,z) position relative to which sampling will occur

  • z_offset (float) – Add a small z-offset to placements. This is useful for fixed objects that do not move (i.e. no free joint) to place them above the table.

sample(fixtures=None, reference=None, on_top=True)

Uniformly sample relative to this sampler’s reference_pos or @reference (if specified).

Parameters
  • fixtures (dict) – dictionary of current object placements in the scene as well as any other relevant obstacles that should not be in contact with newly sampled objects. Used to make sure newly generated placements are valid. Should be object names mapped to (pos, quat, MujocoObject)

  • reference (str or 3-tuple or None) – if provided, sample relative placement. Can either be a string, which corresponds to an existing object found in @fixtures, or a direct (x,y,z) value. If None, will sample relative to this sampler’s ‘reference_pos’ value.

  • on_top (bool) – if True, sample placement on top of the reference object. This corresponds to a sampled z-offset of the current sampled object’s bottom_offset + the reference object’s top_offset (if specified)

Returns

dictionary of all object placements, mapping object_names to (pos, quat, obj), including the

placements specified in @fixtures. Note quat is in (w,x,y,z) form

Return type

dict

Raises
  • RandomizationError – [Cannot place all objects]

  • AssertionError – [Reference object name does not exist, invalid inputs]

robosuite.utils.robot_utils module

robosuite.utils.robot_utils.check_bimanual(robot_name)

Utility function that returns whether the inputted robot_name is a bimanual robot or not

Parameters

robot_name (str) – Name of the robot to check

Returns

True if the inputted robot is a bimanual robot

Return type

bool

robosuite.utils.transform_utils module

Utility functions of matrix and vector transformations.

NOTE: convention for quaternions is (x, y, z, w)

robosuite.utils.transform_utils.axisangle2quat(vec)

Converts scaled axis-angle to quat.

Parameters

vec (np.array) – (ax,ay,az) axis-angle exponential coordinates

Returns

(x,y,z,w) vec4 float angles

Return type

np.array

robosuite.utils.transform_utils.clip_rotation(quat, limit)

Limits a (delta) rotation to a specified limit

Converts rotation to axis-angle, clips, then re-converts back into quaternion

Parameters
  • quat (np.array) – (x,y,z,w) rotation being clipped

  • limit (float) – Value to limit rotation by – magnitude (scalar, in radians)

Returns

  • (np.array) Clipped rotation quaternion (x, y, z, w)

  • (bool) whether the value was clipped or not

Return type

2-tuple

robosuite.utils.transform_utils.clip_translation(dpos, limit)

Limits a translation (delta position) to a specified limit

Scales down the norm of the dpos to ‘limit’ if norm(dpos) > limit, else returns immediately

Parameters
  • dpos (n-array) – n-dim Translation being clipped (e,g.: (x, y, z)) – numpy array

  • limit (float) – Value to limit translation by – magnitude (scalar, in same units as input)

Returns

  • (np.array) Clipped translation (same dimension as inputs)

  • (bool) whether the value was clipped or not

Return type

2-tuple

robosuite.utils.transform_utils.convert_quat(q, to='xyzw')

Converts quaternion from one convention to another. The convention to convert TO is specified as an optional argument. If to == ‘xyzw’, then the input is in ‘wxyz’ format, and vice-versa.

Parameters
  • q (np.array) – a 4-dim array corresponding to a quaternion

  • to (str) – either ‘xyzw’ or ‘wxyz’, determining which convention to convert to.

robosuite.utils.transform_utils.euler2mat(euler)

Converts euler angles into rotation matrix form

Parameters

euler (np.array) – (r,p,y) angles

Returns

3x3 rotation matrix

Return type

np.array

Raises

AssertionError – [Invalid input shape]

robosuite.utils.transform_utils.force_in_A_to_force_in_B(force_A, torque_A, pose_A_in_B)

Converts linear and rotational force at a point in frame A to the equivalent in frame B.

Parameters
  • force_A (np.array) – (fx,fy,fz) linear force in A

  • torque_A (np.array) – (tx,ty,tz) rotational force (moment) in A

  • pose_A_in_B (np.array) – 4x4 matrix corresponding to the pose of A in frame B

Returns

  • (np.array) (fx,fy,fz) linear forces in frame B

  • (np.array) (tx,ty,tz) moments in frame B

Return type

2-tuple

robosuite.utils.transform_utils.get_orientation_error(target_orn, current_orn)

Returns the difference between two quaternion orientations as a 3 DOF numpy array. For use in an impedance controller / task-space PD controller.

Parameters
  • target_orn (np.array) – (x, y, z, w) desired quaternion orientation

  • current_orn (np.array) – (x, y, z, w) current quaternion orientation

Returns

(ax,ay,az) current orientation error, corresponds to

(target_orn - current_orn)

Return type

orn_error (np.array)

robosuite.utils.transform_utils.get_pose_error(target_pose, current_pose)

Computes the error corresponding to target pose - current pose as a 6-dim vector. The first 3 components correspond to translational error while the last 3 components correspond to the rotational error.

Parameters
  • target_pose (np.array) – a 4x4 homogenous matrix for the target pose

  • current_pose (np.array) – a 4x4 homogenous matrix for the current pose

Returns

6-dim pose error.

Return type

np.array

robosuite.utils.transform_utils.make_pose(translation, rotation)

Makes a homogeneous pose matrix from a translation vector and a rotation matrix.

Parameters
  • translation (np.array) – (x,y,z) translation value

  • rotation (np.array) – a 3x3 matrix representing rotation

Returns

a 4x4 homogeneous matrix

Return type

pose (np.array)

robosuite.utils.transform_utils.mat2euler(rmat, axes='sxyz')

Converts given rotation matrix to euler angles in radian.

Parameters
  • rmat (np.array) – 3x3 rotation matrix

  • axes (str) – One of 24 axis sequences as string or encoded tuple (see top of this module)

Returns

(r,p,y) converted euler angles in radian vec3 float

Return type

np.array

robosuite.utils.transform_utils.mat2pose(hmat)

Converts a homogeneous 4x4 matrix into pose.

Parameters

hmat (np.array) – a 4x4 homogeneous matrix

Returns

  • (np.array) (x,y,z) position array in cartesian coordinates

  • (np.array) (x,y,z,w) orientation array in quaternion form

Return type

2-tuple

robosuite.utils.transform_utils.mat2quat(rmat)

Converts given rotation matrix to quaternion.

Parameters

rmat (np.array) – 3x3 rotation matrix

Returns

(x,y,z,w) float quaternion angles

Return type

np.array

robosuite.utils.transform_utils.mat4(array)

Converts an array to 4x4 matrix.

Parameters

array (n-array) – the array in form of vec, list, or tuple

Returns

a 4x4 numpy matrix

Return type

np.array

robosuite.utils.transform_utils.matrix_inverse(matrix)

Helper function to have an efficient matrix inversion function.

Parameters

matrix (np.array) – 2d-array representing a matrix

Returns

2d-array representing the matrix inverse

Return type

np.array

robosuite.utils.transform_utils.pose2mat(pose)

Converts pose to homogeneous matrix.

Parameters

pose (2-tuple) – a (pos, orn) tuple where pos is vec3 float cartesian, and orn is vec4 float quaternion.

Returns

4x4 homogeneous matrix

Return type

np.array

robosuite.utils.transform_utils.pose_in_A_to_pose_in_B(pose_A, pose_A_in_B)

Converts a homogenous matrix corresponding to a point C in frame A to a homogenous matrix corresponding to the same point C in frame B.

Parameters
  • pose_A (np.array) – 4x4 matrix corresponding to the pose of C in frame A

  • pose_A_in_B (np.array) – 4x4 matrix corresponding to the pose of A in frame B

Returns

4x4 matrix corresponding to the pose of C in frame B

Return type

np.array

robosuite.utils.transform_utils.pose_inv(pose)

Computes the inverse of a homogeneous matrix corresponding to the pose of some frame B in frame A. The inverse is the pose of frame A in frame B.

Parameters

pose (np.array) – 4x4 matrix for the pose to inverse

Returns

4x4 matrix for the inverse pose

Return type

np.array

robosuite.utils.transform_utils.quat2axisangle(quat)

Converts quaternion to axis-angle format. Returns a unit vector direction scaled by its angle in radians.

Parameters

quat (np.array) – (x,y,z,w) vec4 float angles

Returns

(ax,ay,az) axis-angle exponential coordinates

Return type

np.array

robosuite.utils.transform_utils.quat2mat(quaternion)

Converts given quaternion to matrix.

Parameters

quaternion (np.array) – (x,y,z,w) vec4 float angles

Returns

3x3 rotation matrix

Return type

np.array

robosuite.utils.transform_utils.quat_conjugate(quaternion)

Return conjugate of quaternion.

E.g.: >>> q0 = random_quaternion() >>> q1 = quat_conjugate(q0) >>> q1[3] == q0[3] and all(q1[:3] == -q0[:3]) True

Parameters

quaternion (np.array) – (x,y,z,w) quaternion

Returns

(x,y,z,w) quaternion conjugate

Return type

np.array

robosuite.utils.transform_utils.quat_distance(quaternion1, quaternion0)

Returns distance between two quaternions, such that distance * quaternion0 = quaternion1

Parameters
  • quaternion1 (np.array) – (x,y,z,w) quaternion

  • quaternion0 (np.array) – (x,y,z,w) quaternion

Returns

(x,y,z,w) quaternion distance

Return type

np.array

robosuite.utils.transform_utils.quat_inverse(quaternion)

Return inverse of quaternion.

E.g.: >>> q0 = random_quaternion() >>> q1 = quat_inverse(q0) >>> np.allclose(quat_multiply(q0, q1), [0, 0, 0, 1]) True

Parameters

quaternion (np.array) – (x,y,z,w) quaternion

Returns

(x,y,z,w) quaternion inverse

Return type

np.array

robosuite.utils.transform_utils.quat_multiply(quaternion1, quaternion0)

Return multiplication of two quaternions (q1 * q0).

E.g.: >>> q = quat_multiply([1, -2, 3, 4], [-5, 6, 7, 8]) >>> np.allclose(q, [-44, -14, 48, 28]) True

Parameters
  • quaternion1 (np.array) – (x,y,z,w) quaternion

  • quaternion0 (np.array) – (x,y,z,w) quaternion

Returns

(x,y,z,w) multiplied quaternion

Return type

np.array

robosuite.utils.transform_utils.quat_slerp(quat0, quat1, fraction, shortestpath=True)

Return spherical linear interpolation between two quaternions.

E.g.: >>> q0 = random_quat() >>> q1 = random_quat() >>> q = quat_slerp(q0, q1, 0.0) >>> np.allclose(q, q0) True

>>> q = quat_slerp(q0, q1, 1.0)
>>> np.allclose(q, q1)
True
>>> q = quat_slerp(q0, q1, 0.5)
>>> angle = math.acos(np.dot(q0, q))
>>> np.allclose(2.0, math.acos(np.dot(q0, q1)) / angle) or         np.allclose(2.0, math.acos(-np.dot(q0, q1)) / angle)
True
Parameters
  • quat0 (np.array) – (x,y,z,w) quaternion startpoint

  • quat1 (np.array) – (x,y,z,w) quaternion endpoint

  • fraction (float) – fraction of interpolation to calculate

  • shortestpath (bool) – If True, will calculate the shortest path

Returns

(x,y,z,w) quaternion distance

Return type

np.array

robosuite.utils.transform_utils.random_axis_angle(angle_limit=None, random_state=None)

Samples an axis-angle rotation by first sampling a random axis and then sampling an angle. If @angle_limit is provided, the size of the rotation angle is constrained.

If @random_state is provided (instance of np.random.RandomState), it will be used to generate random numbers.

Parameters
  • angle_limit (None or float) – If set, determines magnitude limit of angles to generate

  • random_state (None or RandomState) – RNG to use if specified

Raises

AssertionError – [Invalid RNG]

robosuite.utils.transform_utils.random_quat(rand=None)

Return uniform random unit quaternion.

E.g.: >>> q = random_quat() >>> np.allclose(1.0, vector_norm(q)) True >>> q = random_quat(np.random.random(3)) >>> q.shape (4,)

Parameters

rand (3-array or None) – If specified, must be three independent random variables that are uniformly distributed between 0 and 1.

Returns

(x,y,z,w) random quaternion

Return type

np.array

robosuite.utils.transform_utils.rotation_matrix(angle, direction, point=None)

Returns matrix to rotate about axis defined by point and direction.

E.g.:
>>> angle = (random.random() - 0.5) * (2*math.pi)
>>> direc = numpy.random.random(3) - 0.5
>>> point = numpy.random.random(3) - 0.5
>>> R0 = rotation_matrix(angle, direc, point)
>>> R1 = rotation_matrix(angle-2*math.pi, direc, point)
>>> is_same_transform(R0, R1)
True
>>> R0 = rotation_matrix(angle, direc, point)
>>> R1 = rotation_matrix(-angle, -direc, point)
>>> is_same_transform(R0, R1)
True
>>> I = numpy.identity(4, numpy.float32)
>>> numpy.allclose(I, rotation_matrix(math.pi*2, direc))
True
>>> numpy.allclose(2., numpy.trace(rotation_matrix(math.pi/2,
...                                                direc, point)))
True
Parameters
  • angle (float) – Magnitude of rotation

  • direction (np.array) – (ax,ay,az) axis about which to rotate

  • point (None or np.array) – If specified, is the (x,y,z) point about which the rotation will occur

Returns

4x4 homogeneous matrix that includes the desired rotation

Return type

np.array

robosuite.utils.transform_utils.unit_vector(data, axis=None, out=None)

Returns ndarray normalized by length, i.e. eucledian norm, along axis.

E.g.:
>>> v0 = numpy.random.random(3)
>>> v1 = unit_vector(v0)
>>> numpy.allclose(v1, v0 / numpy.linalg.norm(v0))
True
>>> v0 = numpy.random.rand(5, 4, 3)
>>> v1 = unit_vector(v0, axis=-1)
>>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=2)), 2)
>>> numpy.allclose(v1, v2)
True
>>> v1 = unit_vector(v0, axis=1)
>>> v2 = v0 / numpy.expand_dims(numpy.sqrt(numpy.sum(v0*v0, axis=1)), 1)
>>> numpy.allclose(v1, v2)
True
>>> v1 = numpy.empty((5, 4, 3), dtype=numpy.float32)
>>> unit_vector(v0, axis=1, out=v1)
>>> numpy.allclose(v1, v2)
True
>>> list(unit_vector([]))
[]
>>> list(unit_vector([1.0]))
[1.0]
Parameters
  • data (np.array) – data to normalize

  • axis (None or int) – If specified, determines specific axis along data to normalize

  • out (None or np.array) – If specified, will store computation in this variable

Returns

If @out is not specified, will return normalized vector. Otherwise, stores the output in @out

Return type

None or np.array

robosuite.utils.transform_utils.vec(values)

Converts value tuple into a numpy vector.

Parameters

values (n-array) – a tuple of numbers

Returns

vector of given values

Return type

np.array

robosuite.utils.transform_utils.vel_in_A_to_vel_in_B(vel_A, ang_vel_A, pose_A_in_B)

Converts linear and angular velocity of a point in frame A to the equivalent in frame B.

Parameters
  • vel_A (np.array) – (vx,vy,vz) linear velocity in A

  • ang_vel_A (np.array) – (wx,wy,wz) angular velocity in A

  • pose_A_in_B (np.array) – 4x4 matrix corresponding to the pose of A in frame B

Returns

  • (np.array) (vx,vy,vz) linear velocities in frame B

  • (np.array) (wx,wy,wz) angular velocities in frame B

Return type

2-tuple

Module contents