adam.pytorch
============

.. py:module:: adam.pytorch


Submodules
----------

.. toctree::
   :maxdepth: 1

   /autoapi/adam/pytorch/computations/index
   /autoapi/adam/pytorch/torch_like/index


Classes
-------

.. autoapisummary::

   adam.pytorch.KinDynComputations
   adam.pytorch.KinDynComputationsBatch
   adam.pytorch.TorchLike


Package Contents
----------------

.. py:class:: KinDynComputations(urdfstring: str, joints_name_list: list = None, device: torch.device = torch.device('cuda') if torch.cuda.is_available() else torch.device('cpu'), dtype: torch.dtype = torch.float32, root_link: str = None, gravity: torch.Tensor = torch.tensor([0, 0, -9.80665, 0, 0, 0]))

   Bases: :py:obj:`adam.model.kindyn_mixin.KinDynFactoryMixin`


   This is a small class that retrieves robot quantities using Pytorch for Floating Base systems.


   .. py:attribute:: rbdalgos


   .. py:attribute:: NDoF


   .. py:attribute:: g


   .. py:method:: set_frame_velocity_representation(representation: adam.core.constants.Representations) -> None

      Sets the representation of the velocity of the frames

      :param representation: The representation of the velocity
      :type representation: Representations



   .. py:method:: mass_matrix(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the Mass Matrix functions computed the CRBA

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: Mass Matrix
      :rtype: M (torch.tensor)



   .. py:method:: centroidal_momentum_matrix(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the Centroidal Momentum Matrix functions computed the CRBA

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: Centroidal Momentum matrix
      :rtype: Jcc (torch.tensor)



   .. py:method:: forward_kinematics(frame, base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Computes the forward kinematics relative to the specified frame

      :param frame: The frame to which the fk will be computed
      :type frame: str
      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The fk represented as Homogenous transformation matrix
      :rtype: H (torch.tensor)



   .. py:method:: jacobian(frame: str, base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the Jacobian relative to the specified frame

      :param frame: The frame to which the jacobian will be computed
      :type frame: str
      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The Jacobian relative to the frame
      :rtype: J_tot (torch.tensor)



   .. py:method:: relative_jacobian(frame, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the Jacobian between the root link and a specified frame frames

      :param frame: The tip of the chain
      :type frame: str
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The Jacobian between the root and the frame
      :rtype: J (torch.tensor)



   .. py:method:: jacobian_dot(frame: str, base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor) -> torch.Tensor

      Returns the Jacobian derivative relative to the specified frame

      :param frame: The frame to which the jacobian will be computed
      :type frame: str
      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.Tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.Tensor
      :param base_velocity: The base velocity
      :type base_velocity: torch.Tensor
      :param joint_velocities: The joint velocities
      :type joint_velocities: torch.Tensor

      :returns: The Jacobian derivative relative to the frame
      :rtype: Jdot (torch.Tensor)



   .. py:method:: CoM_position(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the CoM position

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The CoM position
      :rtype: CoM (torch.tensor)



   .. py:method:: CoM_jacobian(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the CoM Jacobian

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The CoM Jacobian
      :rtype: Jcom (torch.tensor)



   .. py:method:: bias_force(base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor) -> torch.Tensor

      Returns the bias force of the floating-base dynamics equation,
      using a reduced RNEA (no acceleration and external forces)

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor
      :param base_velocity: The base velocity
      :type base_velocity: torch.tensor
      :param joint_velocities: The joints velocity
      :type joint_velocities: torch.tensor

      :returns: the bias force
      :rtype: h (torch.tensor)



   .. py:method:: coriolis_term(base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor) -> torch.Tensor

      Returns the coriolis term of the floating-base dynamics equation,
      using a reduced RNEA (no acceleration and external forces)

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor
      :param base_velocity: The base velocity
      :type base_velocity: torch.tensor
      :param joint_velocities: The joints velocity
      :type joint_velocities: torch.tensor

      :returns: the Coriolis term
      :rtype: C (torch.tensor)



   .. py:method:: gravity_term(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the gravity term of the floating-base dynamics equation,
      using a reduced RNEA (no acceleration and external forces)

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints positions
      :type joint_positions: torch.tensor

      :returns: the gravity term
      :rtype: G (torch.tensor)



   .. py:method:: aba(base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor, joint_torques: torch.Tensor, external_wrenches: dict[str, torch.Tensor] | None = None) -> torch.Tensor

      Featherstone Articulated-Body Algorithm (floating base, O(n)).

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.Tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.Tensor
      :param base_velocity: The base velocity
      :type base_velocity: torch.Tensor
      :param joint_velocities: The joint velocities
      :type joint_velocities: torch.Tensor
      :param joint_torques: The joint torques
      :type joint_torques: torch.Tensor
      :param external_wrenches: External wrenches applied to the robot. Defaults to None.
      :type external_wrenches: dict[str, torch.Tensor], optional

      :returns: The base acceleration and the joint accelerations
      :rtype: torch.Tensor



   .. py:method:: get_total_mass() -> float

      Returns the total mass of the robot

      :returns: The total mass
      :rtype: mass



.. py:class:: KinDynComputationsBatch(urdfstring: str, joints_name_list: list = None, device: torch.device = torch.device('cuda') if torch.cuda.is_available() else torch.device('cpu'), dtype: torch.dtype = torch.float32, root_link: str = None, gravity: torch.Tensor = torch.tensor([0, 0, -9.80665, 0, 0, 0]))

   Bases: :py:obj:`adam.model.kindyn_mixin.KinDynFactoryMixin`


   This is a small class that retrieves robot quantities using Pytorch for Floating Base systems.


   .. py:attribute:: rbdalgos


   .. py:attribute:: NDoF


   .. py:attribute:: g


   .. py:method:: set_frame_velocity_representation(representation: adam.core.constants.Representations) -> None

      Sets the representation of the velocity of the frames

      :param representation: The representation of the velocity
      :type representation: Representations



   .. py:method:: mass_matrix(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the Mass Matrix functions computed the CRBA

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: Mass Matrix
      :rtype: M (torch.tensor)



   .. py:method:: centroidal_momentum_matrix(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the Centroidal Momentum Matrix functions computed the CRBA

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: Centroidal Momentum matrix
      :rtype: Jcc (torch.tensor)



   .. py:method:: forward_kinematics(frame, base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Computes the forward kinematics relative to the specified frame

      :param frame: The frame to which the fk will be computed
      :type frame: str
      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The fk represented as Homogenous transformation matrix
      :rtype: H (torch.tensor)



   .. py:method:: jacobian(frame: str, base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the Jacobian relative to the specified frame

      :param frame: The frame to which the jacobian will be computed
      :type frame: str
      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The Jacobian relative to the frame
      :rtype: J_tot (torch.tensor)



   .. py:method:: relative_jacobian(frame, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the Jacobian between the root link and a specified frame frames

      :param frame: The tip of the chain
      :type frame: str
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The Jacobian between the root and the frame
      :rtype: J (torch.tensor)



   .. py:method:: jacobian_dot(frame: str, base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor) -> torch.Tensor

      Returns the Jacobian derivative relative to the specified frame

      :param frame: The frame to which the jacobian will be computed
      :type frame: str
      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.Tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.Tensor
      :param base_velocity: The base velocity
      :type base_velocity: torch.Tensor
      :param joint_velocities: The joint velocities
      :type joint_velocities: torch.Tensor

      :returns: The Jacobian derivative relative to the frame
      :rtype: Jdot (torch.Tensor)



   .. py:method:: CoM_position(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the CoM position

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The CoM position
      :rtype: CoM (torch.tensor)



   .. py:method:: CoM_jacobian(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the CoM Jacobian

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor

      :returns: The CoM Jacobian
      :rtype: Jcom (torch.tensor)



   .. py:method:: bias_force(base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor) -> torch.Tensor

      Returns the bias force of the floating-base dynamics equation,
      using a reduced RNEA (no acceleration and external forces)

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor
      :param base_velocity: The base velocity
      :type base_velocity: torch.tensor
      :param joint_velocities: The joints velocity
      :type joint_velocities: torch.tensor

      :returns: the bias force
      :rtype: h (torch.tensor)



   .. py:method:: coriolis_term(base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor) -> torch.Tensor

      Returns the coriolis term of the floating-base dynamics equation,
      using a reduced RNEA (no acceleration and external forces)

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.tensor
      :param base_velocity: The base velocity
      :type base_velocity: torch.tensor
      :param joint_velocities: The joints velocity
      :type joint_velocities: torch.tensor

      :returns: the Coriolis term
      :rtype: C (torch.tensor)



   .. py:method:: gravity_term(base_transform: torch.Tensor, joint_positions: torch.Tensor) -> torch.Tensor

      Returns the gravity term of the floating-base dynamics equation,
      using a reduced RNEA (no acceleration and external forces)

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.tensor
      :param joint_positions: The joints positions
      :type joint_positions: torch.tensor

      :returns: the gravity term
      :rtype: G (torch.tensor)



   .. py:method:: aba(base_transform: torch.Tensor, joint_positions: torch.Tensor, base_velocity: torch.Tensor, joint_velocities: torch.Tensor, joint_torques: torch.Tensor, external_wrenches: dict[str, torch.Tensor] | None = None) -> torch.Tensor

      Featherstone Articulated-Body Algorithm (floating base, O(n)).

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: torch.Tensor
      :param joint_positions: The joints position
      :type joint_positions: torch.Tensor
      :param base_velocity: The base velocity
      :type base_velocity: torch.Tensor
      :param joint_velocities: The joint velocities
      :type joint_velocities: torch.Tensor
      :param joint_torques: The joint torques
      :type joint_torques: torch.Tensor
      :param external_wrenches: External wrenches applied to the robot. Defaults to None.
      :type external_wrenches: dict[str, torch.Tensor], optional

      :returns: The base acceleration and the joint accelerations
      :rtype: torch.Tensor



   .. py:method:: get_total_mass() -> float

      Returns the total mass of the robot

      :returns: The total mass
      :rtype: mass



.. py:class:: TorchLike

   Bases: :py:obj:`adam.core.array_api_math.ArrayAPILike`


   Class wrapping pyTorch types


   .. py:attribute:: array
      :type:  torch.Tensor


