adam.parametric.model
=====================

.. py:module:: adam.parametric.model


Submodules
----------

.. toctree::
   :maxdepth: 1

   /autoapi/adam/parametric/model/parametric_factories/index


Classes
-------

.. autoapisummary::

   adam.parametric.model.ParametricJoint
   adam.parametric.model.ParametricLink
   adam.parametric.model.URDFParametricModelFactory


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

.. py:class:: ParametricJoint(joint: urdf_parser_py.urdf.Joint, math: adam.core.spatial_math.SpatialMath, parent_link: adam.parametric.model.parametric_factories.parametric_link.ParametricLink, idx: Union[int, None] = None)

   Bases: :py:obj:`adam.model.Joint`


   Parametric Joint class


   .. py:attribute:: math


   .. py:attribute:: name


   .. py:attribute:: parent


   .. py:attribute:: parent_parametric


   .. py:attribute:: child


   .. py:attribute:: type


   .. py:attribute:: axis
      :value: None



   .. py:attribute:: limit


   .. py:attribute:: idx
      :value: None


      Abstract base class for all joints.


   .. py:attribute:: joint


   .. py:attribute:: offset


   .. py:attribute:: origin


   .. py:method:: _set_axis(axis: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param axis: axis
      :type axis: npt.ArrayLike

      :returns: set the axis
      :rtype: npt.ArrayLike



   .. py:method:: _set_origin(origin: adam.model.Pose) -> adam.model.Pose

      :param origin: origin
      :type origin: Pose

      :returns: set the origin
      :rtype: Pose



   .. py:method:: _set_limits(limit: adam.model.Limits) -> adam.model.Limits

      :param limit: limit
      :type limit: Limits

      :returns: set the limits
      :rtype: Limits



   .. py:method:: modify(parent_joint_offset: numpy.typing.ArrayLike)

      :param parent_joint_offset: offset of the parent joint
      :type parent_joint_offset: npt.ArrayLike

      :returns: the origin of the joint, parametric with respect to the parent link dimensions
      :rtype: npt.ArrayLike



   .. py:method:: homogeneous(q: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param q: joint value
      :type q: npt.ArrayLike

      :returns: the homogenous transform of a joint, given q
      :rtype: npt.ArrayLike



   .. py:method:: spatial_transform(q: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param q: joint motion
      :type q: npt.ArrayLike

      :returns: spatial transform of the joint given q
      :rtype: npt.ArrayLike



   .. py:method:: motion_subspace() -> numpy.typing.ArrayLike

      :param joint: Joint
      :type joint: Joint

      :returns: motion subspace of the joint
      :rtype: npt.ArrayLike



.. py:class:: ParametricLink(link: urdf_parser_py.urdf.Link, math: adam.core.spatial_math.SpatialMath, length_multiplier, densities)

   Bases: :py:obj:`adam.model.Link`


   Parametric Link class


   .. py:attribute:: math


   .. py:attribute:: name


   .. py:attribute:: length_multiplier


   .. py:attribute:: densities


   .. py:attribute:: original_visual


   .. py:attribute:: visuals


   .. py:attribute:: original_density


   .. py:attribute:: link_offset


   .. py:attribute:: mass


   .. py:attribute:: inertial


   .. py:method:: get_principal_length()

      Method computing the principal link length, i.e. the dimension in which the kinematic chain grows



   .. py:method:: get_principal_length_parametric()

      Method computing the principal link length parametric, i.e. the dimension in which the kinematic chain grows



   .. py:method:: compute_offset()

      :returns: link offset
      :rtype: npt.ArrayLike



   .. py:method:: compute_joint_offset(joint_i, parent_offset)

      :returns: the child joint offset
      :rtype: npt.ArrayLike



   .. py:method:: get_geometry(visual_obj)
      :staticmethod:


      :returns: the geometry of the link and the related urdf object
      :rtype: (Geometry, urdf geometry)



   .. py:method:: compute_volume(length_multiplier)

      :returns: the volume and the dimension parametric
      :rtype: (npt.ArrayLike, npt.ArrayLike)



   .. py:method:: compute_mass()

      Function that computes the mass starting from the densities, and the link volume
      :returns: the link mass
      :rtype: (npt.ArrayLike)



   .. py:method:: modify_origin()

      :returns: the link origin parametrized
      :rtype: (npt.ArrayLike)



   .. py:method:: compute_inertia_parametric()

      :returns: inertia (ixx, iyy and izz) with the formula that corresponds to the geometry
      :rtype: Inertia Parametric

      Formulas retrieved from https://en.wikipedia.org/wiki/List_of_moments_of_inertia



   .. py:method:: spatial_inertia() -> numpy.typing.ArrayLike

      :returns:

                the 6x6 inertia matrix expressed at the
                               origin of the link (with rotation)
      :rtype: npt.ArrayLike



   .. py:method:: homogeneous() -> numpy.typing.ArrayLike

      :returns: the homogeneous transform of the link
      :rtype: npt.ArrayLike



   .. py:method:: update_visuals()


.. py:class:: URDFParametricModelFactory(path: str, math: adam.core.spatial_math.SpatialMath, links_name_list: list, length_multiplier, densities)

   Bases: :py:obj:`adam.model.ModelFactory`


   This factory generates robot elements from urdf_parser_py parametrized w.r.t. link lengths and densities

   :param ModelFactory: the Model factory


   .. py:attribute:: math


   .. py:attribute:: links_name_list


   .. py:attribute:: urdf_desc


   .. py:attribute:: name


   .. py:attribute:: length_multiplier


   .. py:attribute:: densities


   .. py:method:: get_joints() -> list[adam.model.Joint]

      :returns: build the list of the joints
      :rtype: list[Joint]



   .. py:method:: get_links() -> list[adam.model.Link]

      :returns: build the list of the links
      :rtype: list[Link]



   .. py:method:: get_frames() -> list[adam.model.StdLink]

      :returns: build the list of the links
      :rtype: list[Link]



   .. py:method:: build_joint(joint: urdf_parser_py.urdf.Joint) -> adam.model.Joint

      :param joint: the urdf_parser_py joint
      :type joint: Joint

      :returns: our joint representation
      :rtype: StdJoint/ParametricJoint



   .. py:method:: build_link(link: urdf_parser_py.urdf.Link) -> adam.model.Link

      :param link: the urdf_parser_py link
      :type link: Link

      :returns: our link representation
      :rtype: StdLink/ParametricLink



   .. py:method:: get_element_by_name(link_name)

      :param link_name: the link name
      :type link_name: Link

      :returns: the urdf parser link object associated to the link name
      :rtype: Link



