adam.casadi.computations
========================

.. py:module:: adam.casadi.computations


Classes
-------

.. autoapisummary::

   adam.casadi.computations.KinDynComputations


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

.. py:class:: KinDynComputations(urdfstring: str, joints_name_list: list = None, 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'), cse=True))

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


   Class that retrieves robot quantities using CasADi for Floating Base systems.


   .. 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: H (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:: CoM_jacobian_fun() -> casadi.Function

      Returns the CoM Jacobian

      :returns: The CoM Jacobian
      :rtype: J_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() -> float

      Returns the total mass of the robot

      :returns: The total mass
      :rtype: mass



   .. py:method:: mass_matrix(base_transform: casadi.SX, joint_positions: casadi.SX)

      Returns the Mass Matrix functions computed the CRBA

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

      :returns: Mass Matrix
      :rtype: M (cs.SX)



   .. py:method:: centroidal_momentum_matrix(base_transform: casadi.SX, joint_positions: casadi.SX)

      Returns the Centroidal Momentum Matrix functions computed the CRBA

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

      :returns: Centroidal Momentum matrix
      :rtype: Jcc (cs.SX)



   .. py:method:: relative_jacobian(frame: str, joint_positions: casadi.SX)

      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: cs.SX

      :returns: The Jacobian between the root and the frame
      :rtype: J (cs.SX)



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

      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: cs.SX
      :param joint_positions: The joints position
      :type joint_positions: cs.SX
      :param base_velocity: The base velocity
      :type base_velocity: cs.SX
      :param joint_velocities: The joint velocities
      :type joint_velocities: cs.SX

      :returns: The Jacobian derivative relative to the frame
      :rtype: Jdot (cs.SX)



   .. py:method:: forward_kinematics(frame: str, base_transform: casadi.SX, joint_positions: casadi.SX)

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

      :returns: The fk represented as Homogenous transformation matrix
      :rtype: H (cs.SX)



   .. py:method:: jacobian(frame: str, base_transform, joint_positions)

      Returns the Jacobian relative to the specified frame

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: cs.SX
      :param s: The joints position
      :type s: cs.SX
      :param frame: The frame to which the jacobian will be computed
      :type frame: str

      :returns: The Jacobian relative to the frame
      :rtype: J_tot (cs.SX)



   .. py:method:: bias_force(base_transform: casadi.SX, joint_positions: casadi.SX, base_velocity: casadi.SX, joint_velocities: casadi.SX) -> casadi.SX

      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: cs.SX
      :param joint_positions: The joints position
      :type joint_positions: cs.SX
      :param base_velocity: The base velocity
      :type base_velocity: cs.SX
      :param joint_velocities: The joints velocity
      :type joint_velocities: cs.SX

      :returns: the bias force
      :rtype: h (cs.SX)



   .. py:method:: coriolis_term(base_transform: casadi.SX, joint_positions: casadi.SX, base_velocity: casadi.SX, joint_velocities: casadi.SX) -> casadi.SX

      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: cs.SX
      :param joint_positions: The joints position
      :type joint_positions: cs.SX
      :param base_velocity: The base velocity
      :type base_velocity: cs.SX
      :param joint_velocities: The joints velocity
      :type joint_velocities: cs.SX

      :returns: the Coriolis term
      :rtype: C (cs.SX)



   .. py:method:: gravity_term(base_transform: casadi.SX, joint_positions: casadi.SX) -> casadi.SX

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

      :returns: the gravity term
      :rtype: G (cs.SX)



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

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

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

      :returns: The base acceleration and the joint accelerations
      :rtype: cs.SX



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

      Returns the Articulated Body Algorithm function for forward dynamics

      :returns: The joint accelerations and base acceleration
      :rtype: qdd (casADi function)



   .. py:method:: CoM_position(base_transform: casadi.SX, joint_positions: casadi.SX) -> casadi.SX

      Returns the CoM position

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

      :returns: The CoM position
      :rtype: CoM (cs.SX)



   .. py:method:: CoM_jacobian(base_transform: casadi.SX, joint_positions: casadi.SX) -> casadi.SX

      Returns the CoM Jacobian

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

      :returns: The CoM Jacobian
      :rtype: J_com (cs.SX)



