torchcontrol.models package

Submodules

torchcontrol.models.torchscript_pinocchio module

class torchcontrol.models.torchscript_pinocchio.RobotModelPinocchio(urdf_filename: str, ee_link_name: Optional[str] = None)

Bases: Module

A robot model able to compute kinematics & dynamics of a robot given an urdf.

Implemented as a torch.nn.Module wrapped around a C++ custom class that leverages Pinocchio - a C++ rigid body dynamics library.

Parameters:
  • urdf_filename (str) – path to the urdf file.

  • ee_link_name (str, optional) – name of the end-effector link. Defaults to None. Having a value of either None or “” would require you to specify link_name when using methods which require a link frame; otherwise, the end-effector link will be used by default.

compute_jacobian(joint_positions: Tensor, link_name: str = '') Tensor

Computes the Jacobian relative to the link frame.

Parameters:
  • joint_positions – A given set of joint angles.

  • link_name (str, optional) – name of the link desired. Defaults to the end-effector link, if it was set during initialization.

Returns:

The Jacobian relative to the link frame.

Return type:

torch.Tensor, torch.Tensor

forward_kinematics(joint_positions: Tensor, link_name: str = '') Tuple[Tensor, Tensor]

Computes link position and orientation from a given joint position.

Parameters:
  • joint_positions – A given set of joint angles.

  • link_name (str, optional) – name of the link desired. Defaults to the end-effector link, if it was set during initialization.

Returns:

Link position, link orientation as quaternion

Return type:

Tuple[torch.Tensor, torch.Tensor]

get_joint_angle_limits() Tensor
get_joint_velocity_limits() Tensor
inverse_dynamics(joint_positions: Tensor, joint_velocities: Tensor, joint_accelerations: Tensor) Tensor

Computes the desired torques to achieve a certain joint acceleration from given joint positions and velocities.

Returns:

desired torques

Return type:

torch.Tensor

inverse_kinematics(link_pos: Tensor, link_quat: Tensor, link_name: str = '', rest_pose: Optional[Tensor] = None, eps: float = 0.0001, max_iters: int = 1000, dt: float = 0.1, damping: float = 1e-06) Tensor

Computes joint positions that achieve a given end-effector pose. Uses CLIK algorithm from https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/master/doxygen-html/md_doc_b-examples_i-inverse-kinematics.html

Parameters:
  • link_pos (torch.Tensor) – desired link position

  • link_quat (torch.Tensor) – desired link orientation

  • link_name (str, optional) – name of the link desired. Defaults to the end-effector link, if it was set during initialization.

  • rest_pose (torch.Tensor) – (optional) initial solution for IK

  • eps (float) – (optional) maximum allowed error

  • max_iters (int) – (optional) maximum number of iterations

  • dt (float) – (optional) time step for integration

  • damping – (optional) damping factor for numerical stability

Returns:

joint positions

Return type:

torch.Tensor

Sets the ee_link_name, ee_link_idx using pinocchio::ModelTpl::getBodyId.

training: bool

Module contents