torchcontrol.modules package

Module contents

Contains a set of reusable, interchangeable modules to conveniently combine to create policies.

Submodules

torchcontrol.modules.feedback module

class torchcontrol.modules.feedback.CartesianSpacePD(Kp: Tensor, Kd: Tensor)

Bases: CartesianSpacePDFast

PD feedback control in SE3 pose space

Logically identical as CartesianSpacePDFast but with torchcontrol.transform.TransformationObj inputs. Slower implementation due to object creation and member access.

forward(pose_current: TransformationObj, twist_current: Tensor, pose_desired: TransformationObj, twist_desired: Tensor)
Parameters:
  • pose_current – Current ee pose

  • twist_current – Current ee twist of shape (6,)

  • pose_desired – Desired ee pose

  • twist_desired – Desired ee twist of shape (6,)

Returns:

Output wrench of shape (6,)

class torchcontrol.modules.feedback.CartesianSpacePDFast(Kp: Tensor, Kd: Tensor)

Bases: ControlModule

PD feedback control in SE3 pose space

Module parameters:
  • Kp: P gain matrix of shape (6, 6)

  • Kd: D gain matrix of shape (6, 6)

forward(pos_current: Tensor, quat_current: Tensor, twist_current: Tensor, pos_desired: Tensor, quat_desired: Tensor, twist_desired: Tensor)
Parameters:
  • pos_current – Current position of shape (3,)

  • quat_current – Current quaternion of shape (4,)

  • twist_current – Current twist of shape (6,)

  • pos_desired – Desired position of shape (3,)

  • quat_desired – Desired quaternion of shape (4,)

  • twist_desired – Desired twist of shape (6,)

Returns:

Output wrench of shape (6,)

class torchcontrol.modules.feedback.HybridJointSpacePD(Kq: Tensor, Kqd: Tensor, Kx: Tensor, Kxd: Tensor)

Bases: ControlModule

PD feedback control in joint space Uses both constant joint gains and adaptive operational space gains

nA is the action dimension and N is the number of degrees of freedom

Module parameters:
  • Kq: P gain matrix of shape (nA, N)

  • Kqd: D gain matrix of shape (nA, N)

  • Kx: P gain matrix of shape (6, 6)

  • Kxd: D gain matrix of shape (6, 6)

forward(joint_pos_current: Tensor, joint_vel_current: Tensor, joint_pos_desired: Tensor, joint_vel_desired: Tensor, jacobian: Tensor) Tensor

nA is the action dimension and N is the number of degrees of freedom

Parameters:
  • joint_pos_current – Current joint position of shape (N,)

  • joint_vel_current – Current joint velocity of shape (N,)

  • joint_pos_desired – Desired joint position of shape (N,)

  • joint_vel_desired – Desired joint velocity of shape (N,)

  • jacobian – End-effector jacobian of shape (N, 6)

Returns:

Output action of shape (nA,)

class torchcontrol.modules.feedback.JointSpacePD(Kp: Tensor, Kd: Tensor)

Bases: ControlModule

PD feedback control in joint space

nA is the action dimension and N is the number of degrees of freedom

Module parameters:
  • Kp: P gain matrix of shape (nA, N)

  • Kd: D gain matrix of shape (nA, N)

forward(joint_pos_current: Tensor, joint_vel_current: Tensor, joint_pos_desired: Tensor, joint_vel_desired: Tensor) Tensor
Parameters:
  • joint_pos_current – Current joint position of shape (N,)

  • joint_vel_current – Current joint velocity of shape (N,)

  • joint_pos_desired – Desired joint position of shape (N,)

  • joint_vel_desired – Desired joint velocity of shape (N,)

Returns:

Output action of shape (nA,)

class torchcontrol.modules.feedback.LinearFeedback(K: Tensor)

Bases: ControlModule

Linear feedback control: \(u = Kx\)

nA is the action dimension and nS is the state dimension

Module parameters:
  • K: Gain matrix of shape (nA, nS)

forward(x_current: Tensor, x_desired: Tensor) Tensor
Parameters:
  • x_current – Current state of shape (nS,)

  • x_desired – Desired state of shape (nS,)

Returns:

Output action of shape (nA,)

torchcontrol.modules.feedforward module

class torchcontrol.modules.feedforward.Coriolis(robot_model)

Bases: ControlModule

Computes the Coriolis force

forward(q_current: Tensor, qd_current: Tensor) Tensor
Parameters:
  • q_current – Current generalized coordinates

  • qd_current – Current generalized velocities

Returns:

Coriolis forces

class torchcontrol.modules.feedforward.InverseDynamics(robot_model, ignore_gravity: bool = True)

Bases: ControlModule

Computes inverse dynamics

forward(q_current: Tensor, qd_current: Tensor, qdd_desired: Tensor) Tensor
Parameters:
  • q_current – Current generalized coordinates

  • qd_current – Current generalized velocities

  • qdd_desired – Desired generalized accelerations

Returns:

Required generalized forces

use_grav_comp: bool

torchcontrol.modules.planning module