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

.. py:module:: adam.model


Submodules
----------

.. toctree::
   :maxdepth: 1

   /autoapi/adam/model/abc_factories/index
   /autoapi/adam/model/conversions/index
   /autoapi/adam/model/factory/index
   /autoapi/adam/model/kindyn_mixin/index
   /autoapi/adam/model/mj_factory/index
   /autoapi/adam/model/model/index
   /autoapi/adam/model/std_factories/index
   /autoapi/adam/model/tree/index


Classes
-------

.. autoapisummary::

   adam.model.Inertia
   adam.model.Inertial
   adam.model.Joint
   adam.model.Limits
   adam.model.Link
   adam.model.ModelFactory
   adam.model.Pose
   adam.model.Model
   adam.model.StdJoint
   adam.model.StdLink
   adam.model.MujocoModelFactory
   adam.model.URDFModelFactory
   adam.model.Node
   adam.model.Tree


Functions
---------

.. autoapisummary::

   adam.model.build_model_factory


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

.. py:class:: Inertia

   .. py:attribute:: matrix
      :type:  numpy.typing.ArrayLike


   .. py:attribute:: ixx
      :type:  numpy.typing.DTypeLike


   .. py:attribute:: ixy
      :type:  numpy.typing.DTypeLike


   .. py:attribute:: ixz
      :type:  numpy.typing.DTypeLike


   .. py:attribute:: iyy
      :type:  numpy.typing.DTypeLike


   .. py:attribute:: iyz
      :type:  numpy.typing.DTypeLike


   .. py:attribute:: izz
      :type:  numpy.typing.DTypeLike


   .. py:method:: build(ixx: numpy.typing.DTypeLike, ixy: numpy.typing.DTypeLike, ixz: numpy.typing.DTypeLike, iyy: numpy.typing.DTypeLike, iyz: numpy.typing.DTypeLike, izz: numpy.typing.DTypeLike, math: adam.core.spatial_math.SpatialMath) -> Inertia
      :staticmethod:



   .. py:method:: zero(math: adam.core.spatial_math.SpatialMath) -> Inertia
      :staticmethod:



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


.. py:class:: Inertial

   Inertial description


   .. py:attribute:: mass
      :type:  numpy.typing.DTypeLike


   .. py:attribute:: inertia
      :type:  Inertia


   .. py:attribute:: origin
      :type:  Pose


   .. py:method:: zero(math: adam.core.spatial_math.SpatialMath) -> Inertial
      :staticmethod:


      Returns an Inertial object with zero mass and inertia



   .. py:method:: set_mass(mass: numpy.typing.ArrayLike) -> Inertial

      Set the mass of the inertial object



   .. py:method:: set_inertia(inertia: Inertia) -> Inertial

      Set the inertia of the inertial object



   .. py:method:: set_origin(origin: Pose) -> Inertial

      Set the origin of the inertial object



.. py:class:: Joint

   Bases: :py:obj:`abc.ABC`


   Base Joint class. You need to fill at least these fields


   .. py:attribute:: math
      :type:  adam.core.spatial_math.SpatialMath


   .. py:attribute:: name
      :type:  str


   .. py:attribute:: parent
      :type:  str


   .. py:attribute:: child
      :type:  str


   .. py:attribute:: type
      :type:  str


   .. py:attribute:: axis
      :type:  numpy.typing.ArrayLike


   .. py:attribute:: origin
      :type:  Pose


   .. py:attribute:: limit
      :type:  Limits


   .. py:attribute:: idx
      :type:  int

      Abstract base class for all joints.


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


      :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
      :abstractmethod:


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



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


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

      :returns: homogeneous transform given the joint value
      :rtype: npt.ArrayLike



.. py:class:: Limits

   Limits class


   .. py:attribute:: lower
      :type:  numpy.typing.ArrayLike


   .. py:attribute:: upper
      :type:  numpy.typing.ArrayLike


   .. py:attribute:: effort
      :type:  numpy.typing.ArrayLike


   .. py:attribute:: velocity
      :type:  numpy.typing.ArrayLike


.. py:class:: Link

   Bases: :py:obj:`abc.ABC`


   Base Link class. You need to fill at least these fields


   .. py:attribute:: math
      :type:  adam.core.spatial_math.SpatialMath


   .. py:attribute:: name
      :type:  str


   .. py:attribute:: visuals
      :type:  list


   .. py:attribute:: inertial
      :type:  Inertial


   .. py:attribute:: collisions
      :type:  list


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


      :returns:

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



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


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



.. py:class:: ModelFactory

   Bases: :py:obj:`abc.ABC`


   The abstract class of the model factory.

   The model factory is responsible for creating the model.

   You need to implement all the methods in your concrete implementation


   .. py:attribute:: math
      :type:  adam.core.spatial_math.SpatialMath


   .. py:attribute:: name
      :type:  str


   .. py:method:: build_link() -> Link
      :abstractmethod:


      build the single link
      :returns: Link



   .. py:method:: build_joint() -> Joint
      :abstractmethod:


      build the single joint

      :returns: Joint



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


      :returns: the list of the link
      :rtype: list[Link]



   .. py:method:: get_frames() -> list[Link]
      :abstractmethod:


      :returns: the list of the frames
      :rtype: list[Link]



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


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



.. py:class:: Pose

   Pose class


   .. py:attribute:: xyz
      :type:  numpy.typing.ArrayLike


   .. py:attribute:: rpy
      :type:  numpy.typing.ArrayLike


   .. py:method:: build(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike, math: adam.core.spatial_math.SpatialMath) -> Pose
      :staticmethod:



   .. py:method:: zero(math: adam.core.spatial_math.SpatialMath) -> Pose
      :staticmethod:



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


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


.. py:function:: build_model_factory(description: Any, math) -> adam.model.abc_factories.ModelFactory

   Return a ModelFactory from a URDF string/path or a MuJoCo model.


.. py:class:: Model

   Model class. It describes the robot using links and frames and their connectivity


   .. py:attribute:: name
      :type:  str


   .. py:attribute:: links
      :type:  dict[str, adam.model.abc_factories.Link]


   .. py:attribute:: frames
      :type:  dict[str, adam.model.abc_factories.Link]


   .. py:attribute:: joints
      :type:  dict[str, adam.model.abc_factories.Joint]


   .. py:attribute:: tree
      :type:  adam.model.tree.Tree


   .. py:attribute:: NDoF
      :type:  int


   .. py:attribute:: actuated_joints
      :type:  list[str]


   .. py:property:: N
      :type: int


      Returns:
      int: the number of links in the model


   .. py:method:: build(factory: adam.model.abc_factories.ModelFactory, joints_name_list: list[str] = None) -> Model
      :staticmethod:


      generates the model starting from the list of joints and the links-joints factory

      :param factory: the factory that generates the links and the joints, starting from a description (eg. urdf)
      :type factory: ModelFactory
      :param joints_name_list: the list of the actuated joints
      :type joints_name_list: list[str]

      :returns: the model describing the robot
      :rtype: Model



   .. py:method:: get_joints_chain(root: str, target: str) -> list[adam.model.abc_factories.Joint]

      generate the joints chains from a link to a link

      :param root: the starting link
      :type root: str
      :param target: the target link
      :type target: str

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



   .. py:method:: get_total_mass() -> float

      total mass of the robot

      :returns: the total mass of the robot
      :rtype: float



   .. py:method:: print_table()

      print the table that describes the connectivity between the elements.
      You need rich to use it



.. py:class:: StdJoint(joint: urdf_parser_py.urdf.Joint, math: adam.core.spatial_math.SpatialMath, idx: Union[int, None] = None)

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


   Standard Joint class


   .. py:attribute:: math


   .. py:attribute:: name


   .. py:attribute:: parent


   .. py:attribute:: child


   .. py:attribute:: type


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



   .. py:attribute:: origin


   .. py:attribute:: limit


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


      Abstract base class for all joints.


   .. 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:: 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:: StdLink(link: urdf_parser_py.urdf.Link, math: adam.core.spatial_math.SpatialMath)

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


   Standard Link class


   .. py:attribute:: math


   .. py:attribute:: name


   .. py:attribute:: visuals


   .. py:attribute:: inertial


   .. py:attribute:: collisions


   .. py:method:: _set_inertia(link: urdf_parser_py.urdf.Link) -> numpy.typing.ArrayLike

      :param inertia: inertia
      :type inertia: npt.ArrayLike

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



   .. 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:class:: MujocoModelFactory(mj_model: mujoco.MjModel, math: adam.core.spatial_math.SpatialMath)

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


   Factory that builds a model starting from a mujoco.MjModel.


   .. py:attribute:: math


   .. py:attribute:: mujoco


   .. py:attribute:: mj_model


   .. py:attribute:: name


   .. py:attribute:: _links
      :value: []



   .. py:attribute:: _child_map


   .. py:attribute:: _joints
      :value: []



   .. py:method:: _import_mujoco()


   .. py:method:: _model_exists(mj_model)


   .. py:method:: _body_name(body_id: int) -> str


   .. py:method:: _joint_name(joint_id: int) -> str


   .. py:method:: _link_inertial(body_id: int) -> MujocoInertial


   .. py:method:: _build_links() -> list[adam.model.std_factories.std_link.StdLink]


   .. py:method:: _build_child_map() -> dict[str, list[str]]


   .. py:method:: _joint_origin(body_id: int, joint_id: Optional[int]) -> MujocoOrigin


   .. py:method:: _build_limits(joint_id: int, joint_type: str) -> Optional[adam.model.abc_factories.Limits]


   .. py:method:: _joint_type(mj_type: int) -> str


   .. py:method:: _build_joint(body_id: int, joint_id: Optional[int], parent_name: str, joint_type: str) -> adam.model.std_factories.std_joint.StdJoint


   .. py:method:: _build_joints() -> list[adam.model.std_factories.std_joint.StdJoint]


   .. py:method:: build_joint(joint) -> adam.model.std_factories.std_joint.StdJoint
      :abstractmethod:


      build the single joint

      :returns: Joint



   .. py:method:: build_link(link) -> adam.model.std_factories.std_link.StdLink
      :abstractmethod:


      build the single link
      :returns: Link



   .. py:method:: get_joints() -> list[adam.model.std_factories.std_joint.StdJoint]

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



   .. py:method:: _has_non_fixed_joint(link_name: str) -> bool


   .. py:method:: get_links() -> list[adam.model.std_factories.std_link.StdLink]

      :returns: the list of the link
      :rtype: list[Link]



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

      :returns: the list of the frames
      :rtype: list[Link]



.. py:class:: URDFModelFactory(path: str, math: adam.core.spatial_math.SpatialMath)

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


   This factory generates robot elements from urdf_parser_py

   :param ModelFactory: the Model factory


   .. py:attribute:: math


   .. py:attribute:: urdf_desc


   .. py:attribute:: name


   .. py:method:: get_joints() -> list[adam.model.std_factories.std_joint.StdJoint]

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



   .. py:method:: get_links() -> list[adam.model.std_factories.std_link.StdLink]

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

      A link is considered a "real" link if
      - it has an inertial
      - it has children
      - if it has no children and no inertial, it is at lest connected to the parent with a non fixed joint



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

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

      A link is considered a "fake" link (frame) if
      - it has no inertial
      - it does not have children
      - it is connected to the parent with a fixed joint



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

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

      :returns: our joint representation
      :rtype: StdJoint



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

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

      :returns: our link representation
      :rtype: StdLink



.. py:class:: Node

   The node class


   .. py:attribute:: name
      :type:  str


   .. py:attribute:: link
      :type:  adam.model.abc_factories.Link


   .. py:attribute:: arcs
      :type:  list[adam.model.abc_factories.Joint]


   .. py:attribute:: children
      :type:  list[Node]


   .. py:attribute:: parent
      :type:  Union[adam.model.abc_factories.Link, None]
      :value: None



   .. py:attribute:: parent_arc
      :type:  Union[adam.model.abc_factories.Joint, None]
      :value: None



   .. py:method:: __hash__() -> int


   .. py:method:: get_elements() -> tuple[adam.model.abc_factories.Link, adam.model.abc_factories.Joint, adam.model.abc_factories.Link]

      returns the node with its parent arc and parent link

      :returns: the node, the parent_arc, the parent_link
      :rtype: tuple[Link, Joint, Link]



.. py:class:: Tree

   Bases: :py:obj:`Iterable`


   The directed tree class


   .. py:attribute:: graph
      :type:  dict[str, Node]


   .. py:attribute:: root
      :type:  str


   .. py:method:: __post_init__()


   .. py:method:: build_tree(links: list[adam.model.abc_factories.Link], joints: list[adam.model.abc_factories.Joint]) -> Tree
      :staticmethod:


      builds the tree from the connectivity of the elements

      :param links:
      :type links: list[Link]
      :param joints:
      :type joints: list[Joint]

      :returns: the directed tree
      :rtype: Tree



   .. py:method:: print(root)

      prints the tree

      :param root: the root of the tree
      :type root: str



   .. py:method:: get_ordered_nodes_list(start: str) -> list[str]

      get the ordered list of the nodes, given the connectivity

      :param start: the start node
      :type start: str

      :returns: the ordered list
      :rtype: list[str]



   .. py:method:: get_children(node: Node, list: Tree.get_children.list)
      :classmethod:


      Recursive method that finds children of child of child
      :param node: the analized node
      :type node: Node
      :param list: the list of the children that needs to be filled
      :type list: list



   .. py:method:: get_idx_from_name(name: str) -> int

      :param name: node name
      :type name: str

      :returns: the index of the node in the ordered list
      :rtype: int



   .. py:method:: get_name_from_idx(idx: int) -> str

      :param idx: the index in the ordered list
      :type idx: int

      :returns: the corresponding node name
      :rtype: str



   .. py:method:: get_node_from_name(name: str) -> Node

      :param name: the node name
      :type name: str

      :returns: the node istance
      :rtype: Node



   .. py:method:: __iter__() -> Iterator[Node]

      This method allows to iterate on the model
      :returns: the node istance
      :rtype: Node

      :Yields: *Iterator[Node]* -- the list of the nodes



   .. py:method:: __reversed__() -> Iterator[Node]

      :returns: Node

      :Yields: *Iterator[Node]* -- the reversed nodes list



   .. py:method:: __getitem__(key) -> Node

      get the item at key in the model

      :param key: _description_
      :type key: Union[int, Slice]

      :returns: _description_
      :rtype: Node



   .. py:method:: __len__() -> int

      :returns: the length of the model
      :rtype: int



