adam.core.rbd_algorithms
========================

.. py:module:: adam.core.rbd_algorithms


Classes
-------

.. autoapisummary::

   adam.core.rbd_algorithms.RBDAlgorithms


Module Contents
---------------

.. py:class:: RBDAlgorithms(model: adam.model.Model, math: adam.core.spatial_math.SpatialMath)

   This is a small class that implements Rigid body algorithms retrieving robot quantities, for Floating Base systems - as humanoid robots.


   .. py:attribute:: model


   .. py:attribute:: NDoF


   .. py:attribute:: root_link


   .. py:attribute:: math


   .. py:attribute:: frame_velocity_representation


   .. py:attribute:: _root_spatial_transform


   .. py:attribute:: _root_motion_subspace


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

      Sets the frame velocity representation

      :param representation: The representation of the frame velocity
      :type representation: str



   .. py:method:: crba(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike)

      Batched Composite Rigid Body Algorithm (CRBA) + Orin's Centroidal Momentum Matrix.

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

      :returns: The mass matrix and the centroidal momentum matrix
      :rtype: M, Jcm (npt.ArrayLike, npt.ArrayLike)



   .. py:method:: forward_kinematics(frame, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      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: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike

      :returns: The fk represented as Homogenous transformation matrix
      :rtype: I_H_L (npt.ArrayLike)



   .. py:method:: joints_jacobian(frame: str, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      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: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike

      :returns: The Joints Jacobian relative to the frame
      :rtype: J (npt.ArrayLike)



   .. py:method:: jacobian(frame: str, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the Jacobian for `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: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike

      :returns: The Jacobian for the specified frame
      :rtype: npt.ArrayLike



   .. py:method:: relative_jacobian(frame: str, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the Jacobian between the root link and a specified `frame`.

      :param frame: The tip of the chain
      :type frame: str
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike

      :returns: The 6 x NDoF Jacobian between the root and the `frame`
      :rtype: J (npt.ArrayLike)



   .. py:method:: jacobian_dot(frame: str, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike, base_velocity: numpy.typing.ArrayLike, joint_velocities: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the Jacobian time derivative for `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: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike
      :param base_velocity: The spatial velocity of the base
      :type base_velocity: npt.ArrayLike
      :param joint_velocities: The joints velocities
      :type joint_velocities: npt.ArrayLike

      :returns: The Jacobian derivative relative to the frame
      :rtype: J_dot (npt.ArrayLike)



   .. py:method:: CoM_position(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the CoM position

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

      :returns: The CoM position
      :rtype: com (npt.ArrayLike)



   .. py:method:: CoM_jacobian(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the center of mass (CoM) Jacobian using the centroidal momentum matrix.

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

      :returns: The CoM Jacobian
      :rtype: J_com (npt.ArrayLike)



   .. py:method:: get_total_mass()

      Returns the total mass of the robot

      :returns: The total mass
      :rtype: mass



   .. py:method:: rnea(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike, base_velocity: numpy.typing.ArrayLike, joint_velocities: numpy.typing.ArrayLike, g: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Batched Recursive Newton-Euler (reduced: no joint/base accelerations, no external forces).

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike
      :param base_velocity: The base spatial velocity
      :type base_velocity: npt.ArrayLike
      :param joint_velocities: The joints velocities
      :type joint_velocities: npt.ArrayLike
      :param g: The gravity vector
      :type g: npt.ArrayLike

      :returns: The vector of generalized forces
      :rtype: tau (npt.ArrayLike)



   .. py:method:: aba(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike, base_velocity: numpy.typing.ArrayLike, joint_velocities: numpy.typing.ArrayLike, joint_torques: numpy.typing.ArrayLike, g: numpy.typing.ArrayLike, external_wrenches: dict[str, numpy.typing.ArrayLike] | None = None) -> numpy.typing.ArrayLike

      Featherstone Articulated Body Algorithm for floating-base forward dynamics.

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike
      :param base_velocity: The spatial velocity of the base
      :type base_velocity: npt.ArrayLike
      :param joint_velocities: The joints velocities
      :type joint_velocities: npt.ArrayLike
      :param joint_torques: The joints torques/forces
      :type joint_torques: npt.ArrayLike
      :param g: The gravity vector
      :type g: npt.ArrayLike | None, optional
      :param external_wrenches: A dictionary of external wrenches applied to specific links. Keys are link names, and values are 6D wrench vectors. Defaults to None.
      :type external_wrenches: dict[str, npt.ArrayLike] | None, optional

      :returns: The spatial acceleration of the base and joints accelerations
      :rtype: accelerations (npt.ArrayLike)



   .. py:method:: _convert_to_arraylike(*args)

      Convert inputs to ArrayLike if they are not already.
      :param \*args: Input arguments to be converted.

      :returns: Converted arguments as ArrayLike.



   .. py:method:: _prepare_tree_cache() -> None

      Pre-compute static tree data so the dynamic algorithms avoid repeated Python work.



