robosuite.controllers.parts.mobile_base package#

Submodules#

robosuite.controllers.parts.mobile_base.joint_vel module#

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

Bases: MobileBaseController

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]

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

reset_goal()#

Resets joint position goal to be current position

run_controller()#

Calculates the torques required to reach the desired setpoint

Returns:

Command torques

Return type:

np.array

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]

robosuite.controllers.parts.mobile_base.mobile_base_controller module#

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

Bases: object

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

property actuator_limits#

Torque limits for this controller

Returns:

  • (np.array) minimum actuator torques

  • (np.array) maximum actuator torques

Return type:

2-tuple

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

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

get_base_pose()#
property name#

Name of this controller

Returns:

controller name

Return type:

str

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

reset()#
reset_goal()#

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

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

property torque_compensation#

Gravity compensation for this robot arm

Returns:

torques

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

Module contents#