Controller

Contents

Controller#

Every Robot is equipped with a controller, which determines both the action space as well as how its values are mapped into command torques. By default, all controllers have a pre-defined set of methods and properities, though specific controllers may extend and / or override the default functionality found in the base class.

Composite Controllers#

Composite controllers are controllers that are composed of multiple sub-controllers. They are used to control the entire robot, including all of its parts. What happens is that when an action vector is commanded to the robot, the action will be split into multipl sub-actions, each of which will be sent to the corresponding sub-controller. To understand the action split, use the function robosuite.robots.robot.print_action_info(). To create the action easily, we also provide a helper function robosuite.robots.robot.create_action_vector() which takes the action dictionary as inputs and return the action vector with correct dimensions. For controller actions whose input dimentions does not match the robot’s degrees of freedoms, you need to write your own create_action_vector() function inside the custom composite controller so that the robot’s function can retrieve the information properly.

Composite Controller (Base class)#

class robosuite.controllers.composite.composite_controller.CompositeController(sim: MjSim, robot_model: RobotModel, grippers: Dict[str, GripperModel])#

This is the parent class for all composite controllers. If you want to develop an advanced version of your controller, you should subclass from this composite controller.

load_controller_config(part_controller_config, composite_controller_specific_config: Dict | None = None)#
_init_controllers()#
_validate_composite_controller_specific_config()#

Some aspects of composite controller specific configs, if they exist, may only be verified once the part controller are initialized.

setup_action_split_idx()#
set_goal(all_action)#
reset()#
run_controller(enabled_parts)#
get_control_dim(part_name)#
get_controller_base_pose(controller_name)#
update_state()#
get_controller(part_name)#
property action_limits#

HybridMobileBase#

class robosuite.controllers.composite.composite_controller.HybridMobileBase(sim: MjSim, robot_model: RobotModel, grippers: Dict[str, GripperModel])#
set_goal(all_action)#
property action_limits#
create_action_vector(action_dict)#

A helper function that creates the action vector given a dictionary

WholeBody#

class robosuite.controllers.composite.composite_controller.WholeBody(sim: MjSim, robot_model: RobotModel, grippers: Dict[str, GripperModel])#
_init_controllers()#
_init_joint_action_policy()#

Joint action policy initialization.

Joint action policy converts input targets (such as end-effector poses, head poses) to joint actions (such as joint angles or joint torques).

Examples of joint_action_policy could be an IK policy, a neural network policy, a model predictive controller, etc.

setup_action_split_idx()#

Action split indices for the underlying factorized controllers.

WholeBody controller takes in a different action space from the underlying factorized controllers for individual body parts.

setup_whole_body_controller_action_split_idx()#

Action split indices for the composite controller’s input action space.

WholeBodyIK composite controller takes in a different action space from the underlying factorized controllers.

set_goal(all_action)#
update_state()#
property action_limits#

Returns the action limits for the whole body controller. Corresponds to each term in the action vector passed to env.step().

create_action_vector(action_dict: Dict[str, ndarray]) ndarray#
print_action_info()#
print_action_info_dict(name: str = '')#

WholeBodyIK#

class robosuite.controllers.composite.composite_controller.WholeBodyIK(sim: MjSim, robot_model: RobotModel, grippers: Dict[str, GripperModel])#
_validate_composite_controller_specific_config() None#

Some aspects of composite controller specific configs, if they exist, may only be verified once the part controller are initialized.

_init_joint_action_policy()#

Joint action policy initialization.

Joint action policy converts input targets (such as end-effector poses, head poses) to joint actions (such as joint angles or joint torques).

Examples of joint_action_policy could be an IK policy, a neural network policy, a model predictive controller, etc.

Part Controllers#

Part controllers are equivalent to controllers in robosuite up to v1.4. Starting from v1.5, we need to accommodate the diverse embodiments, and the original controllers are changed to controllers for specific parts, such as arms, heads, legs, torso, etc.

Controller (Base class)#

class robosuite.controllers.parts.controller.Controller(sim, joint_indexes, actuator_range, ref_name=None, part_name=None, naming_prefix=None, lite_physics=True)#

General controller interface.

Requires reference to mujoco sim object, ref_name of specific robot, relevant joint_indexes to that robot, and whether an initial_joint is used for nullspace torques or not

Parameters:
  • sim (MjSim) – Simulator instance this controller will pull robot state updates from

  • ref_name (str) – Name of controlled robot arm’s end effector (from robot XML)

  • joint_indexes (dict) –

    Each key contains sim reference indexes to relevant robot joint information, namely:

    ’joints’:

    list of indexes to relevant robot joints

    ’qpos’:

    list of indexes to relevant robot joint positions

    ’qvel’:

    list of indexes to relevant robot joint velocities

  • actuator_range (2-tuple of array of float) – 2-Tuple (low, high) representing the robot joint actuator range

  • lite_physics (bool) – Whether to optimize for mujoco forward and step calls to reduce total simulation overhead. Ignores all self.update() calls, unless set to force=True Set to False to preserve backward compatibility with datasets collected in robosuite <= 1.4.1.

abstract run_controller()#

Abstract method that should be implemented in all subclass controllers, and should convert a given action into torques (pre gravity compensation) to be executed on the robot. Additionally, resets the self.new_update flag so that the next self.update call will occur

scale_action(action)#

Clips @action to be within self.input_min and self.input_max, and then re-scale the values to be within the range self.output_min and self.output_max

Parameters:

action (Iterable) – Actions to scale

Returns:

Re-scaled action

Return type:

np.array

update_reference_data()#
_update_single_reference(name: str, index: int)#
update(force=False)#

Updates the state of the robot arm, including end effector pose / orientation / velocity, joint pos/vel, jacobian, and mass matrix. By default, since this is a non-negligible computation, multiple redundant calls will be ignored via the self.new_update attribute flag. However, if the @force flag is set, the update will occur regardless of that state of self.new_update. This base class method of @run_controller resets the self.new_update flag

Parameters:

force (bool) – Whether to force an update to occur or not

update_origin(origin_pos, origin_ori)#

Optional function to implement in subclass controllers that will take in @origin_pos and @origin_ori and update internal configuration to account for changes in the respective states. Useful for controllers in which the origin is a frame of reference that is dynamically changing, e.g., adapting the arm to move along with a moving base.

Parameters:
  • origin_pos (3-tuple) – x,y,z position of controller reference in mujoco world coordinates

  • origin_ori (np.array) – 3x3 rotation matrix orientation of controller reference in mujoco world coordinates

update_initial_joints(initial_joints)#

Updates the internal attribute self.initial_joints. This is useful for updating changes in controller-specific behavior, such as with OSC where self.initial_joints is used for determine nullspace actions

This function can also be extended by subclassed controllers for additional controller-specific updates

Parameters:

initial_joints (Iterable) – Array of joint position values to update the initial joints

clip_torques(torques)#

Clips the torques to be within the actuator limits

Parameters:

torques (Iterable) – Torques to clip

Returns:

Clipped torques

Return type:

np.array

reset_goal()#

Resets the goal – usually by setting to the goal to all zeros, but in some cases may be different (e.g.: OSC)

static nums2array(nums, dim)#

Convert input @nums into numpy array of length @dim. If @nums is a single number, broadcasts it to the corresponding dimension size @dim before converting into a numpy array

Parameters:
  • nums (numeric or Iterable) – Either single value or array of numbers

  • dim (int) – Size of array to broadcast input to env.sim.data.actuator_force

Returns:

Array filled with values specified in @nums

Return type:

np.array

property torque_compensation#

Gravity compensation for this robot arm

Returns:

torques

Return type:

np.array

property actuator_limits#

Torque limits for this controller

Returns:

  • (np.array) minimum actuator torques

  • (np.array) maximum actuator torques

Return type:

2-tuple

property control_limits#

Limits over this controller’s action space, which defaults to input min/max

Returns:

  • (np.array) minimum action values

  • (np.array) maximum action values

Return type:

2-tuple

property name#

Name of this controller

Returns:

controller name

Return type:

str

Joint Position Controller (generic)#

class robosuite.controllers.parts.generic.joint_pos.JointPositionController(sim, joint_indexes, actuator_range, ref_name=None, input_max=1, input_min=-1, output_max=0.05, output_min=-0.05, kp=50, damping_ratio=1, impedance_mode='fixed', kp_limits=(0, 300), damping_ratio_limits=(0, 100), policy_freq=20, lite_physics=True, qpos_limits=None, interpolator=None, input_type: Literal['delta', 'absolute'] = 'delta', **kwargs)#

Controller for controlling robot arm via impedance control. Allows position control of the robot’s joints.

NOTE: Control input actions assumed to be taken relative to the current joint positions. A given action to this controller is assumed to be of the form: (dpos_j0, dpos_j1, … , dpos_jn-1) for an n-joint robot

Parameters:
  • sim (MjSim) – Simulator instance this controller will pull robot state updates from

  • eef_name (str) – Name of controlled robot arm’s end effector (from robot XML)

  • joint_indexes (dict) –

    Each key contains sim reference indexes to relevant robot joint information, namely:

    ’joints’:

    list of indexes to relevant robot joints

    ’qpos’:

    list of indexes to relevant robot joint positions

    ’qvel’:

    list of indexes to relevant robot joint velocities

  • actuator_range (2-tuple of array of float) – 2-Tuple (low, high) representing the robot joint actuator range

  • input_max (float or Iterable of float) – Maximum above which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • input_min (float or Iterable of float) – Minimum below which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_max (float or Iterable of float) – Maximum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_min (float or Iterable of float) – Minimum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • kp (float or Iterable of float) – positional gain for determining desired torques based upon the joint pos error. Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)

  • damping_ratio (float or Iterable of float) – used in conjunction with kp to determine the velocity gain for determining desired torques based upon the joint pos errors. Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)

  • impedance_mode (str) – Impedance mode with which to run this controller. Options are {“fixed”, “variable”, “variable_kp”}. If “fixed”, the controller will have fixed kp and damping_ratio values as specified by the @kp and @damping_ratio arguments. If “variable”, both kp and damping_ratio will now be part of the controller action space, resulting in a total action space of num_joints * 3. If “variable_kp”, only kp will become variable, with damping_ratio fixed at 1 (critically damped). The resulting action space will then be num_joints * 2.

  • kp_limits (2-list of float or 2-list of Iterable of floats) – Only applicable if @impedance_mode is set to either “variable” or “variable_kp”. This sets the corresponding min / max ranges of the controller action space for the varying kp values. Can be either be a 2-list (same min / max for all kp action dims), or a 2-list of list (specific min / max for each kp dim)

  • damping_ratio_limits (2-list of float or 2-list of Iterable of floats) – Only applicable if @impedance_mode is set to “variable”. This sets the corresponding min / max ranges of the controller action space for the varying damping_ratio values. Can be either be a 2-list (same min / max for all damping_ratio action dims), or a 2-list of list (specific min / max for each damping_ratio dim)

  • policy_freq (int) – Frequency at which actions from the robot policy are fed into this controller

  • qpos_limits (2-list of float or 2-list of Iterable of floats) – Limits (rad) below and above which the magnitude of a calculated goal joint position will be clipped. Can be either be a 2-list (same min/max value for all joint dims), or a 2-list of list (specific min/max values for each dim)

  • interpolator (Interpolator) – Interpolator object to be used for interpolating from the current joint position to the goal joint position during each timestep between inputted actions

  • **kwargs – Does nothing; placeholder to “sink” any additional arguments so that instantiating this controller via an argument dict that has additional extraneous arguments won’t raise an error

Raises:

AssertionError – [Invalid impedance mode]

set_goal(action, set_qpos=None)#

Sets goal based on input @action. If self.impedance_mode is not “fixed”, then the input will be parsed into the delta values to update the goal position / pose and the kp and/or damping_ratio values to be immediately updated internally before executing the proceeding control loop.

Note that @action expected to be in the following format, based on impedance mode!

Mode ‘fixed’:

[joint pos command]

Mode ‘variable’:

[damping_ratio values, kp values, joint pos command]

Mode ‘variable_kp’:

[kp values, joint pos command]

Parameters:
  • action (Iterable) – Desired relative joint position goal state

  • set_qpos (Iterable) – If set, overrides @action and sets the desired absolute joint position goal state

Raises:

AssertionError – [Invalid action dimension size]

run_controller()#

Calculates the torques required to reach the desired setpoint

Returns:

Command torques

Return type:

np.array

reset_goal()#

Resets joint position goal to be current position

property control_limits#

Returns the limits over this controller’s action space, overrides the superclass property Returns the following (generalized for both high and low limits), based on the impedance mode:

Mode ‘fixed’:

[joint pos command]

Mode ‘variable’:

[damping_ratio values, kp values, joint pos command]

Mode ‘variable_kp’:

[kp values, joint pos command]

Returns:

  • (np.array) minimum action values

  • (np.array) maximum action values

Return type:

2-tuple

property name#

Name of this controller

Returns:

controller name

Return type:

str

Joint Velocity Controller (generic)#

class robosuite.controllers.parts.generic.joint_vel.JointVelocityController(sim, joint_indexes, actuator_range, ref_name=None, input_max=1, input_min=-1, output_max=1, output_min=-1, kp=0.25, policy_freq=20, lite_physics=True, velocity_limits=None, interpolator=None, **kwargs)#

Controller for controlling the robot arm’s joint velocities. This is simply a P controller with desired torques (pre gravity compensation) taken to be proportional to the velocity error of the robot joints.

NOTE: Control input actions assumed to be taken as absolute joint velocities. A given action to this controller is assumed to be of the form: (vel_j0, vel_j1, … , vel_jn-1) for an n-joint robot

Parameters:
  • sim (MjSim) – Simulator instance this controller will pull robot state updates from

  • eef_name (str) – Name of controlled robot arm’s end effector (from robot XML)

  • joint_indexes (dict) –

    Each key contains sim reference indexes to relevant robot joint information, namely:

    ’joints’:

    list of indexes to relevant robot joints

    ’qpos’:

    list of indexes to relevant robot joint positions

    ’qvel’:

    list of indexes to relevant robot joint velocities

  • actuator_range (2-tuple of array of float) – 2-Tuple (low, high) representing the robot joint actuator range

  • input_max (float or list of float) – Maximum above which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • input_min (float or list of float) – Minimum below which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_max (float or list of float) – Maximum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_min (float or list of float) – Minimum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • kp (float or list of float) – velocity gain for determining desired torques based upon the joint vel errors. Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)

  • policy_freq (int) – Frequency at which actions from the robot policy are fed into this controller

  • velocity_limits (2-list of float or 2-list of list of floats) – Limits (m/s) below and above which the magnitude of a calculated goal joint velocity will be clipped. Can be either be a 2-list (same min/max value for all joint dims), or a 2-list of list (specific min/max values for each dim)

  • interpolator (Interpolator) – Interpolator object to be used for interpolating from the current joint velocities to the goal joint velocities during each timestep between inputted actions

  • **kwargs – Does nothing; placeholder to “sink” any additional arguments so that instantiating this controller via an argument dict that has additional extraneous arguments won’t raise an error

set_goal(velocities)#

Sets goal based on input @velocities.

Parameters:

velocities (Iterable) – Desired joint velocities

Raises:

AssertionError – [Invalid action dimension size]

run_controller()#

Calculates the torques required to reach the desired setpoint

Returns:

Command torques

Return type:

np.array

reset_goal()#

Resets joint velocity goal to be all zeros

property name#

Name of this controller

Returns:

controller name

Return type:

str

Joint Torque Controller (generic)#

class robosuite.controllers.parts.generic.joint_tor.JointTorqueController(sim, joint_indexes, actuator_range, ref_name=None, input_max=1, input_min=-1, output_max=0.05, output_min=-0.05, policy_freq=20, lite_physics=True, torque_limits=None, interpolator=None, **kwargs)#

Controller for controlling the robot arm’s joint torques. As the actuators at the mujoco sim level are already torque actuators, this “controller” usually simply “passes through” desired torques, though it also includes the typical input / output scaling and clipping, as well as interpolator features seen in other controllers classes as well

NOTE: Control input actions assumed to be taken as absolute joint torques. A given action to this controller is assumed to be of the form: (torq_j0, torq_j1, … , torq_jn-1) for an n-joint robot

Parameters:
  • sim (MjSim) – Simulator instance this controller will pull robot state updates from

  • eef_name (str) – Name of controlled robot arm’s end effector (from robot XML)

  • joint_indexes (dict) –

    Each key contains sim reference indexes to relevant robot joint information, namely:

    ’joints’:

    list of indexes to relevant robot joints

    ’qpos’:

    list of indexes to relevant robot joint positions

    ’qvel’:

    list of indexes to relevant robot joint velocities

  • actuator_range (2-tuple of array of float) – 2-Tuple (low, high) representing the robot joint actuator range

  • input_max (float or list of float) – Maximum above which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • input_min (float or list of float) – Minimum below which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_max (float or list of float) – Maximum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_min (float or list of float) – Minimum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • policy_freq (int) – Frequency at which actions from the robot policy are fed into this controller

  • torque_limits (2-list of float or 2-list of list of floats) – Limits (N-m) below and above which the magnitude of a calculated goal joint torque will be clipped. Can be either be a 2-list (same min/max value for all joint dims), or a 2-list of list (specific min/max values for each dim) If not specified, will automatically set the limits to the actuator limits for this robot arm

  • interpolator (Interpolator) – Interpolator object to be used for interpolating from the current joint torques to the goal joint torques during each timestep between inputted actions

  • **kwargs – Does nothing; placeholder to “sink” any additional arguments so that instantiating this controller via an argument dict that has additional extraneous arguments won’t raise an error

set_goal(torques)#

Sets goal based on input @torques.

Parameters:

torques (Iterable) – Desired joint torques

Raises:

AssertionError – [Invalid action dimension size]

run_controller()#

Calculates the torques required to reach the desired setpoint

Returns:

Command torques

Return type:

np.array

reset_goal()#

Resets joint torque goal to be all zeros (pre-compensation)

property name#

Name of this controller

Returns:

controller name

Return type:

str

Operational Space Controller (arm)#

Inverse Kinematics Controller (arm)#

class robosuite.controllers.parts.arm.ik.InverseKinematicsController(sim, ref_name: List[str] | str, joint_indexes, robot_name, actuator_range, eef_rot_offset=None, bullet_server_id=0, policy_freq=20, load_urdf=True, ik_pos_limit=None, ik_ori_limit=None, interpolator_pos=None, interpolator_ori=None, converge_steps=5, kp: int = 100, kv: int = 10, control_delta: bool = True, **kwargs)#

Controller for controlling robot arm via inverse kinematics. Allows position and orientation control of the robot’s end effector.

We use differential inverse kinematics with posture control in the null space to generate joint positions (see kevinzakka/mjctrl) which are fed to the JointPositionController.

NOTE: Control input actions are assumed to be relative to the current position / orientation of the end effector and are taken as the array (x_dpos, y_dpos, z_dpos, x_rot, y_rot, z_rot).

However, confusingly, x_dpos, y_dpos, z_dpos are relative to the mujoco world frame, while x_rot, y_rot, z_rot are relative to the current end effector frame.

Parameters:
  • sim (MjSim) – Simulator instance this controller will pull robot state updates from

  • ref_name – Name of controlled robot arm’s end effector (from robot XML)

  • joint_indexes (dict) –

    Each key contains sim reference indexes to relevant robot joint information, namely:

    ’joints’:

    list of indexes to relevant robot joints

    ’qpos’:

    list of indexes to relevant robot joint positions

    ’qvel’:

    list of indexes to relevant robot joint velocities

  • robot_name (str) – Name of robot being controlled. Can be {“Sawyer”, “Panda”, or “Baxter”}

  • actuator_range (2-tuple of array of float) – 2-Tuple (low, high) representing the robot joint actuator range

  • eef_rot_offset (4-array) – Quaternion (x,y,z,w) representing rotational offset between the final robot arm link coordinate system and the end effector coordinate system (i.e: the gripper)

  • policy_freq (int) – Frequency at which actions from the robot policy are fed into this controller

  • ik_pos_limit (float) – Limit (meters) above which the magnitude of a given action’s positional inputs will be clipped

  • ik_ori_limit (float) – Limit (radians) above which the magnitude of a given action’s orientation inputs will be clipped

  • interpolator (Interpolator) – Interpolator object to be used for interpolating from the current state to the goal state during each timestep between inputted actions

  • converge_steps (int) – How many iterations to run the inverse kinematics solver to converge to a solution

  • **kwargs – Does nothing; placeholder to “sink” any additional arguments so that instantiating this controller via an argument dict that has additional extraneous arguments won’t raise an error

Raises:

AssertionError – [Unsupported robot]

get_control(dpos=None, rotation=None, update_targets=False)#

Returns joint positions to control the robot after the target end effector position and orientation are updated from arguments @dpos and @rotation. If no arguments are provided, joint positions will be computed based on the previously recorded target.

Parameters:
  • dpos (np.array) – a 3 dimensional array corresponding to the desired change in x, y, and z end effector position.

  • rotation (np.array) – a rotation matrix of shape (3, 3) corresponding to the desired rotation from the current orientation of the end effector.

  • update_targets (bool) – whether to update ik target pos / ori attributes or not

Returns:

a flat array of joint position commands to apply to try and achieve the desired input control.

Return type:

np.array

static compute_joint_positions(sim: ~robosuite.utils.binding_utils.MjSim, initial_joint: ~numpy.ndarray, joint_indices: ~numpy.ndarray, ref_name: ~typing.List[str] | str, control_freq: float, velocity_limits: ~numpy.ndarray | None = None, use_delta: bool = True, dpos: ~numpy.ndarray | None = None, drot: ~numpy.ndarray | None = None, Kn: ~numpy.ndarray | None = array([10., 10., 10., 10., 5., 5., 5.]), damping_pseudo_inv: float = 0.05, Kpos: float = 0.95, Kori: float = 0.95, jac: ~numpy.ndarray | None = None, joint_names: ~typing.List[str] | None = None, nullspace_joint_weights: ~typing.Dict[str, float] = Field(name=None, type=None, default=<dataclasses._MISSING_TYPE object>, default_factory=<class 'dict'>, init=True, repr=True, hash=None, compare=True, metadata=mappingproxy({}), kw_only=<dataclasses._MISSING_TYPE object>, _field_type=None), integration_dt: float = 0.1, damping: float = 0.5, max_dq: int = 4) ndarray#

Returns joint positions to control the robot after the target end effector position and orientation are updated from arguments @dpos and @drot. If no arguments are provided, joint positions will be set as zero.

Parameters:
  • sim (MjSim) – The simulation object.

  • initial_joint (np.array) – Initial joint positions.

  • joint_indices (np.array) – Indices of the joints.

  • ref_name – Reference site name.

  • control_freq (float) – Control frequency.

  • velocity_limits (np.array) – Limits on joint velocities.

  • use_delta – Whether or not to use delta commands. If so, use dpos, drot to compute joint positions. If not, assume dpos, drot are absolute commands (in mujoco world frame).

  • dpos (Optional[np.array]) – Desired change in end-effector position if use_delta=True, otherwise desired end-effector position.

  • drot (Optional[np.array]) – Desired change in orientation for the reference site (e.g end effector) if use_delta=True, otherwise desired end-effector orientation.

  • update_targets (bool) – Whether to update ik target pos / ori attributes or not.

  • Kpos (float) – Position gain. Between 0 and 1. 0 means no movement, 1 means move end effector to desired position in one integration step.

  • Kori (float) – Orientation gain. Between 0 and 1.

  • jac (Optional[np.array]) – Precomputed jacobian matrix.

Returns:

A flat array of joint position commands to apply to try and achieve the desired input control.

Return type:

np.array

set_goal(delta, set_ik=None)#

Sets the internal goal state of this controller based on @delta

Note that this controller wraps a PositionController, and so determines the desired positions to achieve the inputted pose, and sets its internal setpoint in terms of joint positions

TODO: Add feature so that using @set_ik automatically sets the target values to these absolute values

Parameters:
  • delta (Iterable) – Desired relative position / orientation goal state

  • set_ik (Iterable) – If set, overrides @delta and sets the desired global position / orientation goal state

run_controller()#

Calculates the torques required to reach the desired setpoint

Returns:

Command torques

Return type:

np.array

update_initial_joints(initial_joints)#

Updates the internal attribute self.initial_joints. This is useful for updating changes in controller-specific behavior, such as with OSC where self.initial_joints is used for determine nullspace actions

This function can also be extended by subclassed controllers for additional controller-specific updates

Parameters:

initial_joints (Iterable) – Array of joint position values to update the initial joints

reset_goal()#

Resets the goal to the current pose of the robot

_clip_ik_input(dpos, rotation)#

Helper function that clips desired ik input deltas into a valid range.

Parameters:
  • dpos (np.array) – a 3 dimensional array corresponding to the desired change in x, y, and z end effector position.

  • rotation (np.array) – relative rotation in scaled axis angle form (ax, ay, az) corresponding to the (relative) desired orientation of the end effector.

Returns:

  • (np.array) clipped dpos

  • (np.array) clipped rotation

Return type:

2-tuple

_make_input(action, old_quat)#

Helper function that returns a dictionary with keys dpos, rotation from a raw input array. The first three elements are taken to be displacement in position, and a quaternion indicating the change in rotation with respect to @old_quat. Additionally clips @action as well

Parameters:
  • action (np.array) – [dx, dy, dz, ax, ay, az] (orientation in scaled axis-angle form)

  • old_quat (np.array)

static _get_current_error(current, set_point)#

Returns an array of differences between the desired joint positions and current joint positions. Useful for PID control.

Parameters:
  • current (np.array) – the current joint positions

  • set_point (np.array) – the joint positions that are desired as a numpy array

Returns:

the current error in the joint positions

Return type:

np.array

property control_limits#

The limits over this controller’s action space, as specified by self.ik_pos_limit and self.ik_ori_limit and overriding the superclass method

Returns:

  • (np.array) minimum control values

  • (np.array) maximum control values

Return type:

2-tuple

property name#

Name of this controller

Returns:

controller name

Return type:

str

Mobile Base Controller (mobile base)#

class robosuite.controllers.parts.mobile_base.mobile_base_controller.MobileBaseController(sim, joint_indexes, actuator_range, naming_prefix=None)#

General controller interface.

Requires reference to mujoco sim object, relevant joint_indexes to that robot, and whether an initial_joint is used for nullspace torques or not

Parameters:
  • sim (MjSim) – Simulator instance this controller will pull robot state updates from

  • joint_indexes (dict) –

    Each key contains sim reference indexes to relevant robot joint information, namely:

    ’joints’:

    list of indexes to relevant robot joints

    ’qpos’:

    list of indexes to relevant robot joint positions

    ’qvel’:

    list of indexes to relevant robot joint velocities

  • actuator_range (2-tuple of array of float) – 2-Tuple (low, high) representing the robot joint actuator range

get_base_pose()#
reset()#
abstract run_controller()#

Abstract method that should be implemented in all subclass controllers, and should convert a given action into torques (pre gravity compensation) to be executed on the robot. Additionally, resets the self.new_update flag so that the next self.update call will occur

scale_action(action)#

Clips @action to be within self.input_min and self.input_max, and then re-scale the values to be within the range self.output_min and self.output_max

Parameters:

action (Iterable) – Actions to scale

Returns:

Re-scaled action

Return type:

np.array

update(force=False)#

Updates the state of the robot arm, including end effector pose / orientation / velocity, joint pos/vel, jacobian, and mass matrix. By default, since this is a non-negligible computation, multiple redundant calls will be ignored via the self.new_update attribute flag. However, if the @force flag is set, the update will occur regardless of that state of self.new_update. This base class method of @run_controller resets the self.new_update flag

Parameters:

force (bool) – Whether to force an update to occur or not

update_initial_joints(initial_joints)#

Updates the internal attribute self.initial_joints. This is useful for updating changes in controller-specific behavior, such as with OSC where self.initial_joints is used for determine nullspace actions

This function can also be extended by subclassed controllers for additional controller-specific updates

Parameters:

initial_joints (Iterable) – Array of joint position values to update the initial joints

clip_torques(torques)#

Clips the torques to be within the actuator limits

Parameters:

torques (Iterable) – Torques to clip

Returns:

Clipped torques

Return type:

np.array

reset_goal()#

Resets the goal – usually by setting to the goal to all zeros, but in some cases may be different (e.g.: OSC)

static nums2array(nums, dim)#

Convert input @nums into numpy array of length @dim. If @nums is a single number, broadcasts it to the corresponding dimension size @dim before converting into a numpy array

Parameters:
  • nums (numeric or Iterable) – Either single value or array of numbers

  • dim (int) – Size of array to broadcast input to env.sim.data.actuator_force

Returns:

Array filled with values specified in @nums

Return type:

np.array

property torque_compensation#

Gravity compensation for this robot arm

Returns:

torques

Return type:

np.array

property actuator_limits#

Torque limits for this controller

Returns:

  • (np.array) minimum actuator torques

  • (np.array) maximum actuator torques

Return type:

2-tuple

property control_limits#

Limits over this controller’s action space, which defaults to input min/max

Returns:

  • (np.array) minimum action values

  • (np.array) maximum action values

Return type:

2-tuple

property name#

Name of this controller

Returns:

controller name

Return type:

str

Mobile Base Joint Velocity Controller (mobile base)#

class robosuite.controllers.parts.mobile_base.joint_vel.MobileBaseJointVelocityController(sim, joint_indexes, actuator_range, input_max=1, input_min=-1, output_max=1, output_min=-1, kp=50, damping_ratio=1, impedance_mode='fixed', kp_limits=(0, 300), damping_ratio_limits=(0, 100), policy_freq=20, qpos_limits=None, interpolator=None, **kwargs)#

Controller for controlling robot arm via impedance control. Allows position control of the robot’s joints.

NOTE: Control input actions assumed to be taken relative to the current joint positions. A given action to this controller is assumed to be of the form: (dpos_j0, dpos_j1, … , dpos_jn-1) for an n-joint robot

Parameters:
  • sim (MjSim) – Simulator instance this controller will pull robot state updates from

  • joint_indexes (dict) –

    Each key contains sim reference indexes to relevant robot joint information, namely:

    ’joints’:

    list of indexes to relevant robot joints

    ’qpos’:

    list of indexes to relevant robot joint positions

    ’qvel’:

    list of indexes to relevant robot joint velocities

  • actuator_range (2-tuple of array of float) – 2-Tuple (low, high) representing the robot joint actuator range

  • input_max (float or Iterable of float) – Maximum above which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • input_min (float or Iterable of float) – Minimum below which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_max (float or Iterable of float) – Maximum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_min (float or Iterable of float) – Minimum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • kp (float or Iterable of float) – positional gain for determining desired torques based upon the joint pos error. Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)

  • damping_ratio (float or Iterable of float) – used in conjunction with kp to determine the velocity gain for determining desired torques based upon the joint pos errors. Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)

  • impedance_mode (str) – Impedance mode with which to run this controller. Options are {“fixed”, “variable”, “variable_kp”}. If “fixed”, the controller will have fixed kp and damping_ratio values as specified by the @kp and @damping_ratio arguments. If “variable”, both kp and damping_ratio will now be part of the controller action space, resulting in a total action space of num_joints * 3. If “variable_kp”, only kp will become variable, with damping_ratio fixed at 1 (critically damped). The resulting action space will then be num_joints * 2.

  • kp_limits (2-list of float or 2-list of Iterable of floats) – Only applicable if @impedance_mode is set to either “variable” or “variable_kp”. This sets the corresponding min / max ranges of the controller action space for the varying kp values. Can be either be a 2-list (same min / max for all kp action dims), or a 2-list of list (specific min / max for each kp dim)

  • damping_ratio_limits (2-list of float or 2-list of Iterable of floats) – Only applicable if @impedance_mode is set to “variable”. This sets the corresponding min / max ranges of the controller action space for the varying damping_ratio values. Can be either be a 2-list (same min / max for all damping_ratio action dims), or a 2-list of list (specific min / max for each damping_ratio dim)

  • policy_freq (int) – Frequency at which actions from the robot policy are fed into this controller

  • qpos_limits (2-list of float or 2-list of Iterable of floats) – Limits (rad) below and above which the magnitude of a calculated goal joint position will be clipped. Can be either be a 2-list (same min/max value for all joint dims), or a 2-list of list (specific min/max values for each dim)

  • interpolator (Interpolator) – Interpolator object to be used for interpolating from the current joint position to the goal joint position during each timestep between inputted actions

  • **kwargs – Does nothing; placeholder to “sink” any additional arguments so that instantiating this controller via an argument dict that has additional extraneous arguments won’t raise an error

Raises:

AssertionError – [Invalid impedance mode]

set_goal(action, set_qpos=None)#

Sets goal based on input @action. If self.impedance_mode is not “fixed”, then the input will be parsed into the delta values to update the goal position / pose and the kp and/or damping_ratio values to be immediately updated internally before executing the proceeding control loop.

Note that @action expected to be in the following format, based on impedance mode!

Mode ‘fixed’:

[joint pos command]

Mode ‘variable’:

[damping_ratio values, kp values, joint pos command]

Mode ‘variable_kp’:

[kp values, joint pos command]

Parameters:
  • action (Iterable) – Desired relative joint position goal state

  • set_qpos (Iterable) – If set, overrides @action and sets the desired absolute joint position goal state

Raises:

AssertionError – [Invalid action dimension size]

run_controller()#

Calculates the torques required to reach the desired setpoint

Returns:

Command torques

Return type:

np.array

reset_goal()#

Resets joint position goal to be current position

property control_limits#

Returns the limits over this controller’s action space, overrides the superclass property Returns the following (generalized for both high and low limits), based on the impedance mode:

Mode ‘fixed’:

[joint pos command]

Mode ‘variable’:

[damping_ratio values, kp values, joint pos command]

Mode ‘variable_kp’:

[kp values, joint pos command]

Returns:

  • (np.array) minimum action values

  • (np.array) maximum action values

Return type:

2-tuple

property name#

Name of this controller

Returns:

controller name

Return type:

str

Gripper Controller (base class)#

class robosuite.controllers.parts.gripper.gripper_controller.GripperController(sim, joint_indexes, actuator_range, part_name=None, naming_prefix=None)#

General controller interface.

Requires reference to mujoco sim object, relevant joint_indexes to that robot, and whether an initial_joint is used for nullspace torques or not

Parameters:
  • sim (MjSim) – Simulator instance this controller will pull robot state updates from

  • eef_name (str) – Name of controlled robot arm’s end effector (from robot XML)

  • joint_indexes (dict) –

    Each key contains sim reference indexes to relevant robot joint information, namely:

    ’joints’:

    list of indexes to relevant robot joints

    ’qpos’:

    list of indexes to relevant robot joint positions

    ’qvel’:

    list of indexes to relevant robot joint velocities

  • actuator_range (2-tuple of array of float) – 2-Tuple (low, high) representing the robot joint actuator range

abstract run_controller()#

Abstract method that should be implemented in all subclass controllers, and should convert a given action into torques (pre gravity compensation) to be executed on the robot. Additionally, resets the self.new_update flag so that the next self.update call will occur

scale_action(action)#

Clips @action to be within self.input_min and self.input_max, and then re-scale the values to be within the range self.output_min and self.output_max

Parameters:

action (Iterable) – Actions to scale

Returns:

Re-scaled action

Return type:

np.array

update(force=False)#

Updates the state of the robot arm, including end effector pose / orientation / velocity, joint pos/vel, jacobian, and mass matrix. By default, since this is a non-negligible computation, multiple redundant calls will be ignored via the self.new_update attribute flag. However, if the @force flag is set, the update will occur regardless of that state of self.new_update. This base class method of @run_controller resets the self.new_update flag

Parameters:

force (bool) – Whether to force an update to occur or not

update_initial_joints(initial_joints)#

Updates the internal attribute self.initial_joints. This is useful for updating changes in controller-specific behavior, such as with OSC where self.initial_joints is used for determine nullspace actions

This function can also be extended by subclassed controllers for additional controller-specific updates

Parameters:

initial_joints (Iterable) – Array of joint position values to update the initial joints

clip_torques(torques)#

Clips the torques to be within the actuator limits

Parameters:

torques (Iterable) – Torques to clip

Returns:

Clipped torques

Return type:

np.array

reset_goal()#

Resets the goal – usually by setting to the goal to all zeros, but in some cases may be different (e.g.: OSC)

static nums2array(nums, dim)#

Convert input @nums into numpy array of length @dim. If @nums is a single number, broadcasts it to the corresponding dimension size @dim before converting into a numpy array

Parameters:
  • nums (numeric or Iterable) – Either single value or array of numbers

  • dim (int) – Size of array to broadcast input to env.sim.data.actuator_force

Returns:

Array filled with values specified in @nums

Return type:

np.array

property torque_compensation#

Gravity compensation for this robot arm

Returns:

torques

Return type:

np.array

property actuator_limits#

Torque limits for this controller

Returns:

  • (np.array) minimum actuator torques

  • (np.array) maximum actuator torques

Return type:

2-tuple

property control_limits#

Limits over this controller’s action space, which defaults to input min/max

Returns:

  • (np.array) minimum action values

  • (np.array) maximum action values

Return type:

2-tuple

property name#

Name of this controller

Returns:

controller name

Return type:

str

Simple Grip Controller (gripper)#

class robosuite.controllers.parts.gripper.simple_grip.SimpleGripController(sim, joint_indexes, actuator_range, input_max=1, input_min=-1, output_max=1, output_min=-1, policy_freq=20, qpos_limits=None, interpolator=None, use_action_scaling=True, **kwargs)#

Controller for controlling robot arm via impedance control. Allows position control of the robot’s joints.

NOTE: Control input actions assumed to be taken relative to the current joint positions. A given action to this controller is assumed to be of the form: (dpos_j0, dpos_j1, … , dpos_jn-1) for an n-joint robot

Parameters:
  • sim (MjSim) – Simulator instance this controller will pull robot state updates from

  • eef_name (str) – Name of controlled robot arm’s end effector (from robot XML)

  • joint_indexes (dict) –

    Each key contains sim reference indexes to relevant robot joint information, namely:

    ’joints’:

    list of indexes to relevant robot joints

    ’qpos’:

    list of indexes to relevant robot joint positions

    ’qvel’:

    list of indexes to relevant robot joint velocities

  • actuator_range (2-tuple of array of float) – 2-Tuple (low, high) representing the robot joint actuator range

  • input_max (float or Iterable of float) – Maximum above which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • input_min (float or Iterable of float) – Minimum below which an inputted action will be clipped. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_max (float or Iterable of float) – Maximum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • output_min (float or Iterable of float) – Minimum which defines upper end of scaling range when scaling an input action. Can be either be a scalar (same value for all action dimensions), or a list (specific values for each dimension). If the latter, dimension should be the same as the control dimension for this controller

  • policy_freq (int) – Frequency at which actions from the robot policy are fed into this controller

  • qpos_limits (2-list of float or 2-list of Iterable of floats) – Limits (rad) below and above which the magnitude of a calculated goal joint position will be clipped. Can be either be a 2-list (same min/max value for all joint dims), or a 2-list of list (specific min/max values for each dim)

  • interpolator (Interpolator) – Interpolator object to be used for interpolating from the current joint position to the goal joint position during each timestep between inputted actions

  • **kwargs – Does nothing; placeholder to “sink” any additional arguments so that instantiating this controller via an argument dict that has additional extraneous arguments won’t raise an error

Raises:

AssertionError – [Invalid impedance mode]

set_goal(action, set_qpos=None)#

Sets goal based on input @action. If self.impedance_mode is not “fixed”, then the input will be parsed into the delta values to update the goal position / pose and the kp and/or damping_ratio values to be immediately updated internally before executing the proceeding control loop.

Note that @action expected to be in the following format, based on impedance mode!

Mode ‘fixed’:

[joint pos command]

Mode ‘variable’:

[damping_ratio values, kp values, joint pos command]

Mode ‘variable_kp’:

[kp values, joint pos command]

Parameters:
  • action (Iterable) – Desired relative joint position goal state

  • set_qpos (Iterable) – If set, overrides @action and sets the desired absolute joint position goal state

Raises:

AssertionError – [Invalid action dimension size]

run_controller()#

Calculates the torques required to reach the desired setpoint

Returns:

Command torques

Return type:

np.array

reset_goal()#

Resets joint position goal to be current position

property control_limits#

Returns the limits over this controller’s action space, overrides the superclass property Returns the following (generalized for both high and low limits), based on the impedance mode: :returns: - (np.array) minimum action values

  • (np.array) maximum action values

Return type:

2-tuple

property name#

Name of this controller

Returns:

controller name

Return type:

str