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.

Base Controller

class perls2.controllers.base_controller.Controller

General controller interface.

abstract run_controller(action)

Go from actions to torques

scale_action(action)

Scale the action based on max and min of action

Joint Impedance Controller

class perls2.controllers.joint_imp.JointImpController(robot_model, input_max=1, input_min=-1, output_max=1.0, output_min=-1.0, kp=50, kv=None, damping=1, control_freq=20, qpos_limits=None, interpolator_qpos=None)

Controller for joint impedance

set_goal(delta, set_qpos=None, **kwargs)

Set goal for controller. :param delta: (7f) list of deltas from current joint positions :type delta: list :param set_qpos: (7f) goal positions for the joints. :type set_qpos: list :param kwargs: additional keyword arguments. :type kwargs: dict

Returns

None

Examples::

$ self.controller.set_goal(delta=[0.1, 0.1, 0, 0, 0, 0], set_pos=None, set_ori=None)

$self.controller.set_goal(delta=None, set_pose=[0.4, 0.2, 0.4], set_ori=[0, 0, 0, 1])

run_controller()

Calculate torques to acheive goal state from current state.

Parameters

None

Returns

7f list of torques to command.

Return type

torques (list)

Joint Velocity Controller

class perls2.controllers.joint_vel.JointVelController(robot_model, input_max=1, input_min=-1, output_max=1, output_min=-1, kv=4.0, control_freq=20, interpolator=None)

Controller for joint velocity

set_goal(velocities, **kwargs)

Set goal joint velocities

Parameters
  • velocities (list) – 7f list of joint velocities to command to the robot.

  • kwargs (dict) – additional keyword arguments.

Returns

None

run_controller()

Run controller to calculate torques.

Returns

7f list of torques to command.

Return type

torques (list)

Joint Torque Controller

class perls2.controllers.joint_torque.JointTorqueController(robot_model, input_max=1, input_min=-1, output_max=1.0, output_min=-1.0, control_freq=20, interpolator=None)

Controller for joint torque

robot_model

model of robot containing state and parameters.

Type

Model

input_max

Maximum above which an inputted action will be clipped.

Type

float or list of floats

input_min

Minimum below which an inputted action will be clipped.

Type

float or list of floats

output_max

Maximum which defines upper end of scaling range when scaling an input action.

Type

float or list of float

output_min

Minimum which defines lower end of scaling range when scaling an input action.

Type

float or list of float

interpolator

Interpolator object to be used for interpolating between consecutive goals..

Type

LinearInterpolator

goal_torque

goal torques for controller.

Type

list of float

current_torque

current torque being outputted.

Type

list of float

joint_dim

number of joints in the arm (usually 7.)

Type

int

torques

7f list of torques.

Type

list

set_goal(torques, **kwargs)

Set goal torques.

Parameters
  • torques (list) – 7f list of torques to command to the robot.

  • kwargs (dict) – additional keyword arguments.

Returns

None

run_controller()

Run controller to calculate torques.

Returns

7f list of torques to command.

Return type

torques (list)

EEImpedance Controller

class perls2.controllers.ee_imp.EEImpController(robot_model, input_max=1, input_min=-1, output_max=1.0, output_min=-1.0, kp=50, kv=None, damping=1, control_freq=20, position_limits=None, orientation_limits=None, interpolator_pos=None, interpolator_ori=None, uncouple_pos_ori=False, **kwargs)

Class definition for End-effector Impedance Controller.

End effector impedance uses PD control to reach desired end-effector position and orientation.

input_max

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

Type

float or list of float

input_min

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

Type

float or list of float

output_max

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

Type

float or list of float

output_min

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

Type

float or list of float

kp

positional gain for determining desired torques based upon the pos / ori errors. Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)

Type

float or list of float

kv

velocity gain for determining desired torques based on vel / ang vel errors. Can be either a scalar (same value for all action dims) or list (specific values for each dim). If kv is defined, damping is ignored.

Type

float or list of float

damping

used in conjunction with kp to determine the velocity gain for determining desired torques based upon the pos / ori errors. If kv is defined, damping is ignored.

Type

float or list of float

policy_freq

Frequency at which actions from the robot policy are fed into this controller

Type

int

position_limits

Limits (m) below and above which the magnitude of a calculated goal eef position will be clipped. Can be either be a 2-list (same min/max value for all cartesian dims), or a 2-list of list (specific min/max values for each dim)

Type

2-list of float or 2-list of list of floats

orientation_limits

[Lower_bounds, upper_bounds]. Limits (rad) below and above which the magnitude of a calculated goal eef orientation 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/mx values for each dim)

Type

2-list of float or 2-list of list of floats

interpolator_pos

Interpolator object to be used for interpolating from the current position to the goal position during each timestep between inputted actions

Type

Interpolator

interpolator_ori

Interpolator object to be used for interpolating from the current orientation to the goal orientation during each timestep between inputted actions

Type

Interpolator

control_ori

Whether inputted actions will control both pos and ori or exclusively pos

Type

bool

uncouple_pos_ori

Whether to decouple torques meant to control pos and torques meant to control ori

Type

bool

**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(delta, set_pos=None, set_ori=None, **kwargs)

Set goal for controller.

Parameters
  • delta (list) – (6f) list of deltas from current position [dx, dy, dz, ax, ay, az]. Deltas expressed as position and axis-angle in orientation.

  • set_pos (list) – (3f) fixed position goal. [x, y, z] in world frame. Only used if delta is None.

  • set_ori (list) – (4f) fixed orientation goal as quaternion in world frame. Only used if delta is None.

  • kwargs (dict) – additional keyword arguments.

Returns

None

Examples::

$ self.controller.set_goal(delta=[0.1, 0.1, 0, 0, 0, 0], set_pos=None, set_ori=None)

$ self.controller.set_goal(delta=None, set_pose=[0.4, 0.2, 0.4], set_ori=[0, 0, 0, 1])

run_controller()

Calculate torques to acheive goal.

See controllers documentation for more information on EEImpedance

control. Set goal must be called before running controller.

Parameters

None

Returns

7f list of torques to command.

Return type

torques (list)

Run impedance controllers.

EEPosture Controller

class perls2.controllers.ee_posture.EEPostureController(robot_model, input_max=1, input_min=-1, output_max=1.0, output_min=-1.0, kp=50, kv=None, damping=1, posture_gain=0, posture=[0, -1.18, 0.0, 2.18, 0.0, 0.57, 3.3161], policy_freq=20, control_freq=500, position_limits=None, orientation_limits=None, interpolator_pos=None, interpolator_ori=None, uncouple_pos_ori=False, **kwargs)

Class definition for End-effector Impedance Controller.

End effector impedance uses PD control to reach desired end-effector position and orientation, torques are projected to nullspace to maintain posture.

input_max

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

Type

float or list of float

input_min

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

Type

float or list of float

output_max

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

Type

float or list of float

output_min

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

Type

float or list of float

kp

positional gain for determining desired torques based upon the pos / ori errors. Can be either be a scalar (same value for all action dims), or a list (specific values for each dim)

Type

float or list of float

kv

velocity gain for determining desired torques based on vel / ang vel errors. Can be either a scalar (same value for all action dims) or list (specific values for each dim). If kv is defined, damping is ignored.

Type

float or list of float

damping

used in conjunction with kp to determine the velocity gain for determining desired torques based upon the pos / ori errors. If kv is defined, damping is ignored.

Type

float or list of float

posture_gain

gains for determining torques to maintiain desired joint posture.

Type

list

posture

7f joint positions for desired nullspace posture to maintain.

Type

list

control_freq

frequency at which controller sends to robot.

Type

float

position_limits

Limits (m) below and above which the magnitude of a calculated goal eef position will be clipped. Can be either be a 2-list (same min/max value for all cartesian dims), or a 2-list of list (specific min/max values for each dim)

Type

2-list of float or 2-list of list of floats

orientation_limits

[Lower_bounds, upper_bounds]. Limits (rad) below and above which the magnitude of a calculated goal eef orientation 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/mx values for each dim)

Type

2-list of float or 2-list of list of floats

interpolator_pos

Interpolator object to be used for interpolating from the current position to the goal position during each timestep between inputted actions

Type

Interpolator

interpolator_ori

Interpolator object to be used for interpolating from the current orientation to the goal orientation during each timestep between inputted actions

Type

Interpolator

control_ori

Whether inputted actions will control both pos and ori or exclusively pos

Type

bool

uncouple_pos_ori

Whether to decouple torques meant to control pos and torques meant to control ori

Type

bool

**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(delta, set_pos=None, set_ori=None, **kwargs)

Set goal for controller.

Parameters
  • delta (list) – (6f) list of deltas from current position [dx, dy, dz, ax, ay, az]. Deltas expressed as position and axis-angle in orientation.

  • set_pos (list) – (3f) fixed position goal. [x, y, z] in world frame. Only used if delta is None.

  • set_ori (list) – (4f) fixed orientation goal as quaternion in world frame. Only used if delta is None.

  • kwargs (dict) – additional keyword arguments.

Returns

None

Examples::

$ self.controller.set_goal(delta=[0.1, 0.1, 0, 0, 0, 0], set_pos=None, set_ori=None)

$ self.controller.set_goal(delta=None, set_pose=[0.4, 0.2, 0.4], set_ori=[0, 0, 0, 1])

run_controller()

Run controller to calculate torques to acheive desired pose.

Args: None :returns: 7f list of torques to command. :rtype: torques (list)

Runs impedance controllers and adds nullspace constrained posture compensation.