adam.parametric.casadi
======================

.. py:module:: adam.parametric.casadi


Submodules
----------

.. toctree::
   :maxdepth: 1

   /autoapi/adam/parametric/casadi/computations_parametric/index


Classes
-------

.. autoapisummary::

   adam.parametric.casadi.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, 0.0, -9.80665, 0.0, 0.0, 0.0]), f_opts: dict = dict(jit=False, jit_options=dict(flags='-Ofast')))

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


   .. py:attribute:: densities


   .. py:attribute:: length_multiplier


   .. py:attribute:: links_name_list


   .. py:attribute:: rbdalgos


   .. py:attribute:: NDoF


   .. py:attribute:: g


   .. py:attribute:: f_opts


   .. 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_fun() -> casadi.Function

      Returns the Mass Matrix functions computed the CRBA

      :returns: Mass Matrix
      :rtype: M (casADi function)



   .. py:method:: centroidal_momentum_matrix_fun() -> casadi.Function

      Returns the Centroidal Momentum Matrix functions computed the CRBA

      :returns: Centroidal Momentum matrix
      :rtype: Jcc (casADi function)



   .. py:method:: forward_kinematics_fun(frame: str) -> casadi.Function

      Computes the forward kinematics relative to the specified frame

      :param frame: The frame to which the fk will be computed
      :type frame: str

      :returns: The fk represented as Homogenous transformation matrix
      :rtype: T_fk (casADi function)



   .. py:method:: jacobian_fun(frame: str) -> casadi.Function

      Returns the Jacobian relative to the specified frame

      :param frame: The frame to which the jacobian will be computed
      :type frame: str

      :returns: The Jacobian relative to the frame
      :rtype: J_tot (casADi function)



   .. py:method:: relative_jacobian_fun(frame: str) -> casadi.Function

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

      :param frame: The tip of the chain
      :type frame: str

      :returns: The Jacobian between the root and the frame
      :rtype: J (casADi function)



   .. py:method:: jacobian_dot_fun(frame: str) -> casadi.Function

      Returns the Jacobian derivative relative to the specified frame

      :param frame: The frame to which the jacobian will be computed
      :type frame: str

      :returns: The Jacobian derivative relative to the frame
      :rtype: J_dot (casADi function)



   .. py:method:: CoM_position_fun() -> casadi.Function

      Returns the CoM position

      :returns: The CoM position
      :rtype: com (casADi function)



   .. py:method:: bias_force_fun() -> casadi.Function

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

      :returns: the bias force
      :rtype: h (casADi function)



   .. py:method:: coriolis_term_fun() -> casadi.Function

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

      :returns: the Coriolis term
      :rtype: C (casADi function)



   .. py:method:: gravity_term_fun() -> casadi.Function

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

      :returns: the gravity term
      :rtype: G (casADi function)



   .. py:method:: get_total_mass() -> casadi.Function

      Returns the total mass of the robot

      :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



