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, initial_qpos=None, initialization_noise=None, mount_type='default', control_freq=20)
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
mount_type (str) – type of mount, used to instantiate mount models from mount factory. Default is “default”, which is the default mount associated with this robot’s corresponding model. None results in no mount, and any other (valid) model overrides the default mount.
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_model()
Loads robot and optionally add grippers.
- reset_sim(sim: mujoco_py.cymj.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, 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
- 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
- visualize(vis_settings)
Do any necessary visualization for this robot
- Parameters
vis_settings (dict) – Visualization keywords mapped to T/F, determining whether that specific component should be visualized. Should have “robots” keyword as well as any other robot-specific options specified.
- 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
- 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
- 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 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).
- property js_energy
Returns: np.array: the energy consumed by each joint between previous and current steps
- property joint_indexes
Returns: list: mujoco internal indexes for the robot joints
- property _joint_positions
Returns: np.array: joint positions (in angles / radians)
- property _joint_velocities
Returns: np.array: joint velocities (angular velocity)
Manipulator Robot
- class robosuite.robots.manipulator.Manipulator(robot_type: str, idn=0, initial_qpos=None, initialization_noise=None, mount_type='default', control_freq=20)
Initializes a manipulator robot simulation object, as defined by a single corresponding robot arm XML and associated gripper XML
- grip_action(gripper, gripper_action)
Executes @gripper_action for specified @gripper
- Parameters
gripper (GripperModel) – Gripper to execute action for
gripper_action (float) – Value between [-1,1] to send to gripper
- property ee_ft_integral
Returns: float or dict: either single value or arm-specific entries specifying the integral over time of the applied
ee force-torque for that arm
- property ee_force
Returns: np.array or dict: either single value or arm-specific entries specifying the force applied at the force sensor
at the robot arm’s eef
- property ee_torque
Returns: np.array or dict: either single value or arm-specific entries specifying the torque applied at the torque
sensor at the robot arm’s eef
- property _hand_pose
Returns: np.array or dict: either single value or arm-specific entries specifying the eef pose in base frame of
robot.
- property _hand_quat
Returns: np.array or dict: either single value or arm-specific entries specifying the eef quaternion in base frame
of robot.
- property _hand_total_velocity
Returns: np.array or dict: either single value or arm-specific entries specifying the total eef velocity
(linear + angular) in the base frame as a numpy array of shape (6,)
- property _hand_pos
Returns: np.array or dict: either single value or arm-specific entries specifying the position of eef in base frame
of robot.
- property _hand_orn
Returns: np.array or dict: either single value or arm-specific entries specifying the orientation of eef in base
frame of robot as a rotation matrix.
- property _hand_vel
Returns: np.array or dict: either single value or arm-specific entries specifying the velocity of eef in base frame
of robot.
- property _hand_ang_vel
Returns: np.array or dict: either single value or arm-specific entries specifying the angular velocity of eef in
base frame of robot.
SingleArm Robot
- class robosuite.robots.single_arm.SingleArm(robot_type: str, idn=0, controller_config=None, initial_qpos=None, initialization_noise=None, mount_type='default', gripper_type='default', control_freq=20)
Initializes a single-armed robot simulation object.
- 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
controller_config (dict) – If set, contains relevant controller parameters for creating a custom controller. Else, uses the default controller for this specific task
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
mount_type (str) – type of mount, used to instantiate mount models from mount factory. Default is “default”, which is the default mount associated with this robot’s corresponding model. None results in no mount, and any other (valid) model overrides the default mount.
gripper_type (str) – type of gripper, used to instantiate gripper models from gripper factory. Default is “default”, which is the default gripper associated within the ‘robot’ specification. None removes the gripper, and any other (valid) model overrides the default gripper
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.
- 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
- Raises
AssertionError – [Invalid action dimension]
- property ee_ft_integral
Returns: np.array: the integral over time of the applied ee force-torque
- property ee_force
Returns: np.array: force applied at the force sensor at the robot arm’s eef
- property ee_torque
Returns torque applied at the torque sensor at the robot arm’s eef
- property _hand_pose
Returns: np.array: (4,4) array corresponding to the eef pose in base frame of robot.
- property _hand_quat
Returns: np.array: (x,y,z,w) eef quaternion in base frame of robot.
- property _hand_total_velocity
Returns: np.array: 6-array representing the total eef velocity (linear + angular) in the base frame
- property _hand_pos
Returns: np.array: 3-array representing the position of eef in base frame of robot.
- property _hand_orn
Returns: np.array: (3,3) array representing the orientation of eef in base frame of robot as a rotation matrix.
- property _hand_vel
Returns: np.array: (x,y,z) velocity of eef in base frame of robot.
- property _hand_ang_vel
Returns: np.array: (ax,ay,az) angular velocity of eef in base frame of robot.
Bimanual Robot
- class robosuite.robots.bimanual.Bimanual(robot_type: str, idn=0, controller_config=None, initial_qpos=None, initialization_noise=None, mount_type='default', gripper_type='default', control_freq=20)
Initializes a bimanual robot simulation object.
- 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
controller_config (dict or list of dict --> dict of dict) –
If set, contains relevant controller parameters for creating custom controllers. Else, uses the default controller for this specific task. Should either be single dict if same controller is to be used for both robot arms or else it should be a list of length 2.
- NOTE
In the latter case, assumes convention of [right, left]
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
mount_type (str) – type of mount, used to instantiate mount models from mount factory. Default is “default”, which is the default mount associated with this robot’s corresponding model. None results in no mount, and any other (valid) model overrides the default mount.
gripper_type (str or list of str --> dict) –
type of gripper, used to instantiate gripper models from gripper factory. Default is “default”, which is the default gripper associated within the ‘robot’ specification. None removes the gripper, and any other (valid) model overrides the default gripper. Should either be single str if same gripper type is to be used for both arms or else it should be a list of length 2
- NOTE
In the latter case, assumes convention of [right, left]
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.
- 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]
- 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.