Robot

Contents

Robot#

The Robot class defines a simulation object encapsulating a robot model, gripper model, and controller. Robosuite uses class extensions of this base class to model different robotic domains. The current release focuses on manipulation, and includes a Manipulator class, which itself is extended by SingleArm and Bimanual classes representing the two different types of supported robots.

Base Robot#

class robosuite.robots.robot.Robot(robot_type: str, idn=0, composite_controller_config=None, initial_qpos=None, initialization_noise=None, base_type='default', gripper_type='default', control_freq=20, lite_physics=True)#

Initializes a robot simulation object, as defined by a single corresponding robot XML

Parameters:
  • robot_type (str) – Specification for specific robot arm to be instantiated within this env (e.g: “Panda”)

  • idn (int or str) – Unique ID of this robot. Should be different from others

  • initial_qpos (sequence of float) – If set, determines the initial joint positions of the robot to be instantiated for the task

  • initialization_noise (dict) –

    Dict containing the initialization noise parameters. The expected keys and corresponding value types are specified below:

    ’magnitude’:

    The scale factor of uni-variate random noise applied to each of a robot’s given initial joint positions. Setting this value to “None” or 0.0 results in no noise being applied. If “gaussian” type of noise is applied then this magnitude scales the standard deviation applied, If “uniform” type of noise is applied then this magnitude sets the bounds of the sampling range

    ’type’:

    Type of noise to apply. Can either specify “gaussian” or “uniform”

    Note:

    Specifying None will automatically create the required dict with “magnitude” set to 0.0

  • base_type (str) – type of base, used to instantiate base models from base factory. Default is “default”, which is the default base associated with this robot’s corresponding model. None results in no base, and any other (valid) model overrides the default base.

  • control_freq (float) – how many control signals to receive in every second. This sets the amount of simulation time that passes between every action input.

_load_controller()#

Loads controller to be used for dynamic trajectories.

_postprocess_part_controller_config()#

Update part_controller_config with values from composite_controller_config for each body part. Remove unused parts that are not in the controller. Called by _load_controller() function

load_model()#

Loads robot and optionally add grippers.

reset_sim(sim: MjSim)#

Replaces current sim with a new sim

Parameters:

sim (MjSim) – New simulation being instantiated to replace the old one

reset(deterministic=False)#

Sets initial pose of arm and grippers. Overrides robot joint configuration if we’re using a deterministic reset (e.g.: hard reset from xml file)

Parameters:

deterministic (bool) – If true, will not randomize initializations within the sim

Raises:

ValueError – [Invalid noise type]

setup_references()#

Sets up necessary reference for robots, bases, grippers, and objects.

setup_observables()#

Sets up observables to be used for this robot

Returns:

Dictionary mapping observable names to its corresponding Observable object

Return type:

OrderedDict

_create_arm_sensors(arm, modality)#

Helper function to create sensors for a given arm. This is abstracted in a separate function call so that we don’t have local function naming collisions during the _setup_observables() call.

Parameters:
  • arm (str) – Arm to create sensors for

  • modality (str) – Modality to assign to all sensors

Returns:

sensors (list): Array of sensors for the given arm names (list): array of corresponding observable names

Return type:

2-tuple

_create_base_sensors(modality)#

Helper function to create sensors for the robot base. This will be overriden by subclasses.

Parameters:

modality (str) – Type/modality of the created sensor

control(action, policy_step=False)#

Actuate the robot with the passed joint velocities and gripper control.

Parameters:
  • action (np.array) – The control to apply to the robot. The first @self.robot_model.dof dimensions should be the desired normalized joint velocities and if the robot has a gripper, the next @self.gripper.dof dimensions should be actuation controls for the gripper.

  • policy_step (bool) – Whether a new policy step (action) is being taken

check_q_limits()#

Check if this robot is either very close or at the joint limits

Returns:

True if this arm is near its joint limits

Return type:

bool

property is_mobile#
property action_limits#
_input2dict(inp)#

Helper function that converts an input that is either a single value or a list into a dict with keys for each arm: “right”, “left”

Parameters:

inp (str or list or None) – Input value to be converted to dict

:param : Note: If inp is a list, then assumes format is [right, left]

Returns:

Inputs mapped for each robot arm

Return type:

dict

property torque_limits#

Torque lower/upper limits per dimension.

Returns:

  • (np.array) minimum (low) torque values

  • (np.array) maximum (high) torque values

Return type:

2-tuple

property action_dim#

Action space dimension for this robot

property dof#

Returns: int: the active DoF of the robot (Number of robot joints + active gripper DoF).

pose_in_base_from_name(name)#

A helper function that takes in a named data field and returns the pose of that object in the base frame.

Parameters:

name (str) – Name of body in sim to grab pose

Returns:

(4,4) array corresponding to the pose of @name in the base frame

Return type:

np.array

set_robot_joint_positions(jpos)#

Helper method to force robot joint positions to the passed values.

Parameters:

jpos (np.array) – Joint positions to manually set the robot to

property js_energy#

Returns: np.array: the energy consumed by each joint between previous and current steps

property _joint_positions#

Returns: np.array: joint positions (in angles / radians)

property _joint_velocities#

Returns: np.array: joint velocities (angular velocity)

property joint_indexes#

Returns: list: mujoco internal indexes for the robot joints

property arm_joint_indexes#

Returns: list: mujoco internal indexes for the robot arm joints

get_sensor_measurement(sensor_name)#

Grabs relevant sensor data from the sim object

Parameters:

sensor_name (str) – name of the sensor

Returns:

sensor values

Return type:

np.array

visualize(vis_settings)#

Do any necessary visualization for this manipulator

Parameters:

vis_settings (dict) – Visualization keywords mapped to T/F, determining whether that specific component should be visualized. Should have “robots” and “grippers” keyword as well as any other robot-specific options specified.

_visualize_grippers(visible)#

Visualizes the gripper site(s) if applicable.

Parameters:

visible (bool) – True if visualizing the gripper for this arm.

property action_limits#
property is_mobile#
property ee_ft_integral#

Returns: dict: each arm-specific entry specifies the integral over time of the applied ee force-torque for that arm

property ee_force#

Returns: dict: each arm-specific entry specifies the force applied at the force sensor at the robot arm’s eef

property ee_torque#

Returns: dict: each arm-specific entry specifies the torque applied at the torque sensor at the robot arm’s eef

property _hand_pose#

Returns: dict: each arm-specific entry specifies the eef pose in base frame of robot.

property _hand_quat#

Returns: dict: each arm-specific entry specifies the eef quaternion in base frame of robot.

property _hand_total_velocity#

Returns: dict: each arm-specific entry specifies the total eef velocity (linear + angular) in the base frame as a numpy array of shape (6,)

property _hand_pos#

Returns: dict: each arm-specific entry specifies the position of eef in base frame of robot.

property _hand_orn#

Returns: dict: each arm-specific entry specifies the orientation of eef in base frame of robot as a rotation matrix.

property _hand_vel#

Returns: dict: each arm-specific entry specifies the velocity of eef in base frame of robot.

property _hand_ang_vel#

Returns: dict: each arm-specific entry specifies the angular velocity of eef in base frame of robot.

_load_arm_controllers()#
enable_parts(right=True, left=True)#
enabled(part_name)#
create_action_vector(action_dict)#

A helper function that creates the action vector given a dictionary

print_action_info()#
print_action_info_dict()#
get_gripper_name(arm)#
has_part(part_name)#
property _joint_split_idx#

Returns: int: the index that correctly splits the right arm from the left arm joints

property part_controllers#

Controller dictionary for the robot

Returns:

Controller dictionary for the robot

Return type:

dict

Fixed Base Robot#

Tabletop manipulators.

class robosuite.robots.fixed_base_robot.FixedBaseRobot(robot_type: str, idn=0, composite_controller_config=None, initial_qpos=None, initialization_noise=None, base_type='default', gripper_type='default', control_freq=20, lite_physics=True)#

Initializes a robot with a fixed base.

Mobile Base Robot#

WheeledRobot and LeggedRobot are two types of mobile base robots supported in robosuite.

Mobile robot#

Base class for wheeled and legged robots.

class robosuite.robots.mobile_robot.MobileRobot(robot_type: str, idn=0, composite_controller_config=None, initial_qpos=None, initialization_noise=None, base_type='default', gripper_type='default', control_freq=20, lite_physics=True)#

Initializes a robot with a fixed base.

_load_controller()#

Loads controller to be used for dynamic trajectories

_load_base_controller()#

Load base controller

_load_torso_controller()#

Load torso controller

_load_head_controller()#

Load head controller

load_model()#

Loads robot and optionally add grippers.

reset(deterministic=False)#

Sets initial pose of arm and grippers. Overrides gripper joint configuration if we’re using a deterministic reset (e.g.: hard reset from xml file)

Parameters:

deterministic (bool) – If true, will not randomize initializations within the sim

setup_references()#

Sets up necessary reference for robots, grippers, and objects.

Note that this should get called during every reset from the environment

control(action, policy_step=False)#

Actuate the robot with the passed joint velocities and gripper control.

Parameters:
  • action (np.array) –

    The control to apply to the robot. The first @self.robot_model.dof dimensions should be the desired normalized joint velocities and if the robot has a gripper, the next @self.gripper.dof dimensions should be actuation controls for the gripper.

    NOTE:

    Assumes inputted actions are of form: [right_arm_control, right_gripper_control, left_arm_control, left_gripper_control]

  • policy_step (bool) – Whether a new policy step (action) is being taken

Raises:

AssertionError – [Invalid action dimension]

setup_observables()#

Sets up observables to be used for this robot

Returns:

Dictionary mapping observable names to its corresponding Observable object

Return type:

OrderedDict

_create_base_sensors(modality)#

Creates base sensors for the robot.

Parameters:

modality (str) – Type/modality of the created sensor

enable_parts(right=True, left=True, torso=True, head=True, base=True, legs=True)#
property is_mobile#
property base#
property torso#
property head#
property legs#
property _action_split_indexes#

Dictionary of split indexes for each part of the robot

Returns:

Dictionary of split indexes for each part of the robot

Return type:

dict

Wheeled Robot#

Mobile robots with wheeled bases.

class robosuite.robots.wheeled_robot.WheeledRobot(robot_type: str, idn=0, composite_controller_config=None, initial_qpos=None, initialization_noise=None, base_type='default', gripper_type='default', control_freq=20, lite_physics=True)#

Initializes a robot with a wheeled base.

_load_controller()#

Loads controller to be used for dynamic trajectories

load_model()#

Loads robot and optionally add grippers.

reset(deterministic=False)#

Sets initial pose of arm and grippers. Overrides gripper joint configuration if we’re using a deterministic reset (e.g.: hard reset from xml file)

Parameters:

deterministic (bool) – If true, will not randomize initializations within the sim

setup_references()#

Sets up necessary reference for robots, grippers, and objects.

Note that this should get called during every reset from the environment

control(action, policy_step=False)#

Actuate the robot with the passed joint velocities and gripper control.

Parameters:
  • action (np.array) –

    The control to apply to the robot. The first @self.robot_model.dof dimensions should be the desired normalized joint velocities and if the robot has a gripper, the next @self.gripper.dof dimensions should be actuation controls for the gripper.

    NOTE:

    Assumes inputted actions are of form: [right_arm_control, right_gripper_control, left_arm_control, left_gripper_control]

  • policy_step (bool) – Whether a new policy step (action) is being taken

Raises:

AssertionError – [Invalid action dimension]

setup_observables()#

Sets up observables to be used for this robot

Returns:

Dictionary mapping observable names to its corresponding Observable object

Return type:

OrderedDict

property action_limits#

Action lower/upper limits per dimension.

Returns:

  • (np.array) minimum (low) action values

  • (np.array) maximum (high) action values

Return type:

2-tuple

Legged Robot#

Robots with legs.

class robosuite.robots.legged_robot.LeggedRobot(robot_type: str, idn=0, composite_controller_config=None, initial_qpos=None, initialization_noise=None, base_type='default', gripper_type='default', control_freq=20, lite_physics=True)#

Initializes a robot with a wheeled base.

_load_leg_controllers()#
_load_controller()#

Loads controller to be used for dynamic trajectories

load_model()#

Loads robot and optionally add grippers.

reset(deterministic=False)#

Sets initial pose of arm and grippers. Overrides gripper joint configuration if we’re using a deterministic reset (e.g.: hard reset from xml file)

Parameters:

deterministic (bool) – If true, will not randomize initializations within the sim

setup_references()#

Sets up necessary reference for robots, grippers, and objects.

Note that this should get called during every reset from the environment

control(action, policy_step=False)#

Actuate the robot with the passed joint velocities and gripper control.

Parameters:
  • action (np.array) –

    The control to apply to the robot. The first @self.robot_model.dof dimensions should be the desired normalized joint velocities and if the robot has a gripper, the next @self.gripper.dof dimensions should be actuation controls for the gripper.

    NOTE:

    Assumes inputted actions are of form: [right_arm_control, right_gripper_control, left_arm_control, left_gripper_control]

  • policy_step (bool) – Whether a new policy step (action) is being taken

Raises:

AssertionError – [Invalid action dimension]

setup_observables()#

Sets up observables to be used for this robot

Returns:

Dictionary mapping observable names to its corresponding Observable object

Return type:

OrderedDict

property action_limits#

Action lower/upper limits per dimension.

Returns:

  • (np.array) minimum (low) action values

  • (np.array) maximum (high) action values

Return type:

2-tuple

property is_legs_actuated#
property num_leg_joints#