robosuite.robots package#

Submodules#

robosuite.robots.bimanual module#

robosuite.robots.manipulator module#

robosuite.robots.robot module#

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)#

Bases: object

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.

property action_dim#

Action space dimension for this robot

property action_limits#
property arm_joint_indexes#

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

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

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

create_action_vector(action_dict)#

A helper function that creates the action vector given a dictionary

property dof#

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

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_ft_integral#

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

property ee_torque#

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

enable_parts(right=True, left=True)#
enabled(part_name)#
get_gripper_name(arm)#
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

has_part(part_name)#
property is_mobile#
property joint_indexes#

Returns: list: mujoco internal indexes for the robot joints

property js_energy#

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

load_model()#

Loads robot and optionally add grippers.

property part_controllers#

Controller dictionary for the robot

Returns:

Controller dictionary for the robot

Return type:

dict

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

print_action_info()#
print_action_info_dict()#
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]

reset_sim(sim: MjSim)#

Replaces current sim with a new sim

Parameters:

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

set_gripper_joint_positions(jpos: ndarray, gripper_arm: str | None = None)#

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

Parameters:
  • jpos (np.array) – Joint jpos to manually set the gripper to

  • gripper_arm – arm corresponding to the gripper for which to set the gripper joint jpos. If None, use default arm.

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

setup_observables()#

Sets up observables to be used for this robot

Returns:

Dictionary mapping observable names to its corresponding Observable object

Return type:

OrderedDict

setup_references()#

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

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

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.

robosuite.robots.single_arm module#

Module contents#

robosuite.robots.register_robot_class(target_type, **kwargs)#