robosuite.controllers.parts.generic package#
Submodules#
robosuite.controllers.parts.generic.joint_pos module#
- 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)#
Bases:
Controller
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]
- 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.generic.joint_tor module#
- 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)#
Bases:
Controller
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
- property name#
Name of this controller
- Returns:
controller name
- Return type:
str
- reset_goal()#
Resets joint torque goal to be all zeros (pre-compensation)
- run_controller()#
Calculates the torques required to reach the desired setpoint
- Returns:
Command torques
- Return type:
np.array
- set_goal(torques)#
Sets goal based on input @torques.
- Parameters:
torques (Iterable) – Desired joint torques
- Raises:
AssertionError – [Invalid action dimension size]
robosuite.controllers.parts.generic.joint_vel module#
- 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)#
Bases:
Controller
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
- property name#
Name of this controller
- Returns:
controller name
- Return type:
str
- reset_goal()#
Resets joint velocity goal to be all zeros
- run_controller()#
Calculates the torques required to reach the desired setpoint
- Returns:
Command torques
- Return type:
np.array
- set_goal(velocities)#
Sets goal based on input @velocities.
- Parameters:
velocities (Iterable) – Desired joint velocities
- Raises:
AssertionError – [Invalid action dimension size]