adam.parametric.numpy
=====================

.. py:module:: adam.parametric.numpy


Submodules
----------

.. toctree::
   :maxdepth: 1

   /autoapi/adam/parametric/numpy/computations_parametric/index


Classes
-------

.. autoapisummary::

   adam.parametric.numpy.KinDynComputationsParametric


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

.. py:class:: KinDynComputationsParametric(urdfstring: str, joints_name_list: list, links_name_list: list, root_link: str = None, gravity: numpy.array = np.array([0, 0, -9.80665, 0, 0, 0]))

   This is a small class that retrieves robot quantities using NumPy for Floating Base systems.
   This is parametric w.r.t the link length and densities.


   .. py:attribute:: links_name_list


   .. py:attribute:: math


   .. py:attribute:: g


   .. py:attribute:: urdfstring


   .. py:attribute:: joints_name_list


   .. py:attribute:: representation


   .. 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: numpy.ndarray, joint_positions: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      Returns the Mass Matrix functions computed the CRBA

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: np.ndarray
      :param joint_positions: The joints position
      :type joint_positions: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: Mass Matrix
      :rtype: M (np.ndarray)



   .. py:method:: centroidal_momentum_matrix(base_transform: numpy.ndarray, s: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      Returns the Centroidal Momentum Matrix functions computed the CRBA

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: np.ndarray
      :param joint_positions: The joint positions
      :type joint_positions: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: Centroidal Momentum matrix
      :rtype: Jcc (np.ndarray)



   .. py:method:: forward_kinematics(frame: str, base_transform: numpy.ndarray, joint_positions: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      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: np.ndarray
      :param joint_positions: The joints position
      :type joint_positions: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: The fk represented as Homogenous transformation matrix
      :rtype: T_fk (np.ndarray)



   .. py:method:: jacobian(frame: str, base_transform: numpy.ndarray, joint_positions: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      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: np.ndarray
      :param joint_positions: The joints position
      :type joint_positions: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: The Jacobian relative to the frame
      :rtype: J_tot (np.ndarray)



   .. py:method:: relative_jacobian(frame: str, joint_positions: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      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: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: The Jacobian between the root and the frame
      :rtype: J (np.ndarray)



   .. py:method:: jacobian_dot(frame: str, base_transform: numpy.ndarray, joint_positions: numpy.ndarray, base_velocity: numpy.ndarray, joint_velocities: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      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: np.ndarray
      :param joint_positions: The joints position
      :type joint_positions: np.ndarray
      :param base_velocity: The base velocity
      :type base_velocity: np.ndarray
      :param joint_velocities: The joint velocities
      :type joint_velocities: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: The Jacobian derivative relative to the frame
      :rtype: Jdot (np.ndarray)



   .. py:method:: CoM_position(base_transform: numpy.ndarray, joint_positions: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      Returns the CoM position

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: np.ndarray
      :param joint_positions: The joints position
      :type joint_positions: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: The CoM position
      :rtype: CoM (np.ndarray)



   .. py:method:: bias_force(base_transform: numpy.ndarray, joint_positions: numpy.ndarray, base_velocity: numpy.ndarray, joint_velocities: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      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: np.ndarray
      :param joint_positions: The joints position
      :type joint_positions: np.ndarray
      :param base_velocity: The base velocity
      :type base_velocity: np.ndarray
      :param joint_velocities: The joint velocities
      :type joint_velocities: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: the bias force
      :rtype: h (np.ndarray)



   .. py:method:: coriolis_term(base_transform: numpy.ndarray, joint_positions: numpy.ndarray, base_velocity: numpy.ndarray, joint_velocities: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      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: np.ndarray
      :param joint_positions: The joints position
      :type joint_positions: np.ndarray
      :param base_velocity: The base velocity
      :type base_velocity: np.ndarray
      :param joint_velocities: The joint velocities
      :type joint_velocities: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: the Coriolis term
      :rtype: C (np.ndarray)



   .. py:method:: gravity_term(base_transform: numpy.ndarray, joint_positions: numpy.ndarray, length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> numpy.ndarray

      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: np.ndarray
      :param joint_positions: The joints position
      :type joint_positions: np.ndarray
      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: the gravity term
      :rtype: G (np.ndarray)



   .. py:method:: get_total_mass(length_multiplier: numpy.ndarray, densities: numpy.ndarray) -> float

      Returns the total mass of the robot

      :param length_multiplier: The length multiplier of the parametrized links
      :type length_multiplier: np.ndarray
      :param densities: The densities of the parametrized links
      :type densities: np.ndarray

      :returns: The total mass
      :rtype: mass



   .. py:method:: get_original_densities() -> list[float]

      Returns the original densities of the parametric links

      :returns: The original densities of the parametric links
      :rtype: densities



