adam.core
=========

.. py:module:: adam.core


Submodules
----------

.. toctree::
   :maxdepth: 1

   /autoapi/adam/core/array_api_math/index
   /autoapi/adam/core/constants/index
   /autoapi/adam/core/rbd_algorithms/index
   /autoapi/adam/core/spatial_math/index


Classes
-------

.. autoapisummary::

   adam.core.Representations
   adam.core.RBDAlgorithms
   adam.core.SpatialMath
   adam.core.ArrayAPISpatialMath
   adam.core.ArrayAPIFactory
   adam.core.ArrayAPILike


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

.. py:class:: Representations

   Bases: :py:obj:`enum.IntEnum`


   Enum where members are also (and must be) ints


   .. py:attribute:: BODY_FIXED_REPRESENTATION


   .. py:attribute:: MIXED_REPRESENTATION


   .. py:attribute:: INERTIAL_FIXED_REPRESENTATION


.. py:class:: RBDAlgorithms(model: adam.model.Model, math: adam.core.spatial_math.SpatialMath)

   This is a small class that implements Rigid body algorithms retrieving robot quantities, for Floating Base systems - as humanoid robots.


   .. py:attribute:: model


   .. py:attribute:: NDoF


   .. py:attribute:: root_link


   .. py:attribute:: math


   .. py:attribute:: frame_velocity_representation


   .. py:attribute:: _root_spatial_transform


   .. py:attribute:: _root_motion_subspace


   .. py:method:: set_frame_velocity_representation(representation: adam.core.constants.Representations)

      Sets the frame velocity representation

      :param representation: The representation of the frame velocity
      :type representation: str



   .. py:method:: crba(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike)

      Batched Composite Rigid Body Algorithm (CRBA) + Orin's Centroidal Momentum Matrix.

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

      :returns: The mass matrix and the centroidal momentum matrix
      :rtype: M, Jcm (npt.ArrayLike, npt.ArrayLike)



   .. py:method:: forward_kinematics(frame, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

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

      :returns: The fk represented as Homogenous transformation matrix
      :rtype: I_H_L (npt.ArrayLike)



   .. py:method:: joints_jacobian(frame: str, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

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

      :returns: The Joints Jacobian relative to the frame
      :rtype: J (npt.ArrayLike)



   .. py:method:: jacobian(frame: str, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the Jacobian for `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: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike

      :returns: The Jacobian for the specified frame
      :rtype: npt.ArrayLike



   .. py:method:: relative_jacobian(frame: str, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the Jacobian between the root link and a specified `frame`.

      :param frame: The tip of the chain
      :type frame: str
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike

      :returns: The 6 x NDoF Jacobian between the root and the `frame`
      :rtype: J (npt.ArrayLike)



   .. py:method:: jacobian_dot(frame: str, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike, base_velocity: numpy.typing.ArrayLike, joint_velocities: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the Jacobian time derivative for `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: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike
      :param base_velocity: The spatial velocity of the base
      :type base_velocity: npt.ArrayLike
      :param joint_velocities: The joints velocities
      :type joint_velocities: npt.ArrayLike

      :returns: The Jacobian derivative relative to the frame
      :rtype: J_dot (npt.ArrayLike)



   .. py:method:: CoM_position(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the CoM position

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

      :returns: The CoM position
      :rtype: com (npt.ArrayLike)



   .. py:method:: CoM_jacobian(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Returns the center of mass (CoM) Jacobian using the centroidal momentum matrix.

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

      :returns: The CoM Jacobian
      :rtype: J_com (npt.ArrayLike)



   .. py:method:: get_total_mass()

      Returns the total mass of the robot

      :returns: The total mass
      :rtype: mass



   .. py:method:: rnea(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike, base_velocity: numpy.typing.ArrayLike, joint_velocities: numpy.typing.ArrayLike, g: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Batched Recursive Newton-Euler (reduced: no joint/base accelerations, no external forces).

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike
      :param base_velocity: The base spatial velocity
      :type base_velocity: npt.ArrayLike
      :param joint_velocities: The joints velocities
      :type joint_velocities: npt.ArrayLike
      :param g: The gravity vector
      :type g: npt.ArrayLike

      :returns: The vector of generalized forces
      :rtype: tau (npt.ArrayLike)



   .. py:method:: aba(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike, base_velocity: numpy.typing.ArrayLike, joint_velocities: numpy.typing.ArrayLike, joint_torques: numpy.typing.ArrayLike, g: numpy.typing.ArrayLike, external_wrenches: dict[str, numpy.typing.ArrayLike] | None = None) -> numpy.typing.ArrayLike

      Featherstone Articulated Body Algorithm for floating-base forward dynamics.

      :param base_transform: The homogenous transform from base to world frame
      :type base_transform: npt.ArrayLike
      :param joint_positions: The joints position
      :type joint_positions: npt.ArrayLike
      :param base_velocity: The spatial velocity of the base
      :type base_velocity: npt.ArrayLike
      :param joint_velocities: The joints velocities
      :type joint_velocities: npt.ArrayLike
      :param joint_torques: The joints torques/forces
      :type joint_torques: npt.ArrayLike
      :param g: The gravity vector
      :type g: npt.ArrayLike | None, optional
      :param external_wrenches: A dictionary of external wrenches applied to specific links. Keys are link names, and values are 6D wrench vectors. Defaults to None.
      :type external_wrenches: dict[str, npt.ArrayLike] | None, optional

      :returns: The spatial acceleration of the base and joints accelerations
      :rtype: accelerations (npt.ArrayLike)



   .. py:method:: _convert_to_arraylike(*args)

      Convert inputs to ArrayLike if they are not already.
      :param \*args: Input arguments to be converted.

      :returns: Converted arguments as ArrayLike.



   .. py:method:: _prepare_tree_cache() -> None

      Pre-compute static tree data so the dynamic algorithms avoid repeated Python work.



.. py:class:: SpatialMath(factory: ArrayLikeFactory)

   Class implementing the main geometric functions used for computing rigid-body algorithm

   :param ArrayLike: abstract class describing a generic Array wrapper. It needs to be implemented for every data type


   .. py:attribute:: _factory


   .. py:property:: factory
      :type: ArrayLikeFactory



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


      :param x: elements
      :type x: npt.ArrayLike

      :returns: vertical concatenation of elements x
      :rtype: npt.ArrayLike



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


      :param x: elements
      :type x: npt.ArrayLike

      :returns: horizontal concatenation of elements x
      :rtype: npt.ArrayLike



   .. py:method:: concatenate(x: numpy.typing.ArrayLike, axis: int) -> numpy.typing.ArrayLike
      :abstractmethod:


      :param x: elements
      :type x: npt.ArrayLike
      :param axis: axis along which to concatenate
      :type axis: int

      :returns: concatenation of elements x along axis
      :rtype: npt.ArrayLike



   .. py:method:: stack(x: numpy.typing.ArrayLike, axis: int) -> numpy.typing.ArrayLike
      :abstractmethod:


      :param x: elements
      :type x: npt.ArrayLike
      :param axis: axis along which to stack
      :type axis: int

      :returns: stacked elements x along axis
      :rtype: npt.ArrayLike



   .. py:method:: tile(x: numpy.typing.ArrayLike, reps: tuple) -> numpy.typing.ArrayLike
      :abstractmethod:


      :param x: input array
      :type x: npt.ArrayLike
      :param reps: repetition factors for each dimension
      :type reps: tuple

      :returns: tiled array
      :rtype: npt.ArrayLike



   .. py:method:: transpose(x: numpy.typing.ArrayLike, dims: tuple) -> numpy.typing.ArrayLike
      :abstractmethod:


      :param x: input array
      :type x: npt.ArrayLike
      :param dims: permutation of dimensions
      :type dims: tuple

      :returns: transposed array
      :rtype: npt.ArrayLike



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


      :param x: input array
      :type x: npt.ArrayLike

      :returns: inverse of the array
      :rtype: npt.ArrayLike



   .. py:method:: mtimes(x: numpy.typing.ArrayLike, y: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike
      :abstractmethod:



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


      :param x: angle value
      :type x: npt.ArrayLike

      :returns: sin value of x
      :rtype: npt.ArrayLike



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


      :param x: angle value
      :type x: npt.ArrayLike

      :returns: cos value of angle x
      :rtype: npt.ArrayLike



   .. py:method:: skew(x)
      :abstractmethod:



   .. py:method:: R_from_axis_angle(axis, q)

      axis: (...,3) - normalized axis vector, batched if q is batched
      q   : (...,)  - rotation angle, batched or scalar
      returns: (...,3,3) - rotation matrix



   .. py:method:: sxm(s: numpy.typing.ArrayLike, m: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      Computes scalar multiplication with a matrix

      :param s: scalar value
      :type s: npt.ArrayLike
      :param m: matrix to be multiplied
      :type m: npt.ArrayLike

      :returns: result of the multiplication
      :rtype: npt.ArrayLike



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

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

      :returns: rotation matrix around x axis
      :rtype: npt.ArrayLike



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

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

      :returns: rotation matrix around y axis
      :rtype: npt.ArrayLike



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

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

      :returns: rotation matrix around z axis
      :rtype: npt.ArrayLike



   .. py:method:: H_revolute_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike, axis: numpy.typing.ArrayLike, q: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param xyz: joint origin in the urdf
      :type xyz: npt.ArrayLike
      :param rpy: joint orientation in the urdf
      :type rpy: npt.ArrayLike
      :param axis: joint axis in the urdf
      :type axis: npt.ArrayLike
      :param q: joint angle value
      :type q: npt.ArrayLike

      :returns: Homogeneous transform
      :rtype: npt.ArrayLike



   .. py:method:: homogeneous(R, p)


   .. py:method:: H_prismatic_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike, axis: numpy.typing.ArrayLike, q: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param xyz: joint origin in the urdf
      :type xyz: npt.ArrayLike
      :param rpy: joint orientation in the urdf
      :type rpy: npt.ArrayLike
      :param axis: joint axis in the urdf
      :type axis: npt.ArrayLike
      :param q: joint angle value
      :type q: npt.ArrayLike

      :returns: Homogeneous transform
      :rtype: npt.ArrayLike



   .. py:method:: H_from_Pos_RPY(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param xyz: translation vector
      :type xyz: npt.ArrayLike
      :param rpy: rotation as rpy angles
      :type rpy: npt.ArrayLike

      :returns: Homegeneous transform
      :rtype: npt.ArrayLike



   .. py:method:: R_from_RPY(rpy: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param rpy: rotation as rpy angles
      :type rpy: npt.ArrayLike

      :returns: Rotation matrix
      :rtype: npt.ArrayLike



   .. py:method:: X_revolute_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike, axis: numpy.typing.ArrayLike, q: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param xyz: joint origin in the urdf
      :type xyz: npt.ArrayLike
      :param rpy: joint orientation in the urdf
      :type rpy: npt.ArrayLike
      :param axis: joint axis in the urdf
      :type axis: npt.ArrayLike
      :param q: joint angle value
      :type q: npt.ArrayLike

      :returns: Spatial transform of a revolute joint given its rotation angle
      :rtype: npt.ArrayLike



   .. py:method:: X_prismatic_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike, axis: numpy.typing.ArrayLike, q: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param xyz: joint origin in the urdf
      :type xyz: npt.ArrayLike
      :param rpy: joint orientation in the urdf
      :type rpy: npt.ArrayLike
      :param axis: joint axis in the urdf
      :type axis: npt.ArrayLike
      :param q: joint angle value
      :type q: npt.ArrayLike

      :returns: Spatial transform of a prismatic joint given its increment
      :rtype: npt.ArrayLike



   .. py:method:: X_fixed_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param xyz: joint origin in the urdf
      :type xyz: npt.ArrayLike
      :param rpy: joint orientation in the urdf
      :type rpy: npt.ArrayLike

      :returns: Spatial transform of a fixed joint
      :rtype: npt.ArrayLike



   .. py:method:: _X_from_H(T)


   .. py:method:: spatial_transform(R: numpy.typing.ArrayLike, p: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param R: Rotation matrix
      :type R: npt.ArrayLike
      :param p: translation vector
      :type p: npt.ArrayLike

      :returns: spatial transform
      :rtype: npt.ArrayLike



   .. py:method:: spatial_inertia(inertia_matrix: numpy.typing.ArrayLike, mass: numpy.typing.ArrayLike, c: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param inertia_matrix: inertia values from urdf
      :type inertia_matrix: npt.ArrayLike
      :param mass: mass value from urdf
      :type mass: npt.ArrayLike
      :param c: origin of the link from urdf
      :type c: npt.ArrayLike
      :param rpy: orientation of the link from the urdf
      :type rpy: npt.ArrayLike

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



   .. py:method:: spatial_inertia_with_parameters(inertia_matrix, mass, c, rpy)

      :param I: inertia values parametric
      :type I: npt.ArrayLike
      :param mass: mass value parametric
      :type mass: npt.ArrayLike
      :param c: origin of the link parametric
      :type c: npt.ArrayLike
      :param rpy: orientation of the link from urdf
      :type rpy: npt.ArrayLike

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



   .. py:method:: spatial_skew(v: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param v: 6D vector
      :type v: npt.ArrayLike

      :returns: spatial skew matrix
      :rtype: npt.ArrayLike



   .. py:method:: spatial_skew_star(v: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param v: 6D vector
      :type v: npt.ArrayLike

      :returns: negative spatial skew matrix traspose
      :rtype: npt.ArrayLike



   .. py:method:: adjoint(H: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param H: Homogeneous transform
      :type H: npt.ArrayLike

      :returns: adjoint matrix
      :rtype: npt.ArrayLike



   .. py:method:: adjoint_derivative(H: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param H: Homogeneous transform
      :type H: npt.ArrayLike
      :param v: 6D twist
      :type v: npt.ArrayLike

      :returns: adjoint matrix derivative
      :rtype: npt.ArrayLike



   .. py:method:: mxv(m: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param m: Matrix
      :type m: npt.ArrayLike
      :param v: Vector
      :type v: npt.ArrayLike

      :returns: Result of matrix-vector multiplication
      :rtype: npt.ArrayLike



   .. py:method:: vxs(v: numpy.typing.ArrayLike, s: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param v: Vector
      :type v: npt.ArrayLike
      :param s: Scalar
      :type s: npt.ArrayLike

      :returns: Result of vector cross product with scalar multiplication
      :rtype: npt.ArrayLike



   .. py:method:: adjoint_inverse(H: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param H: Homogeneous transform
      :type H: npt.ArrayLike

      :returns: adjoint matrix
      :rtype: npt.ArrayLike



   .. py:method:: adjoint_inverse_derivative(H: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param H: Homogeneous transform
      :type H: npt.ArrayLike
      :param v: 6D twist
      :type v: npt.ArrayLike

      :returns: adjoint matrix derivative
      :rtype: npt.ArrayLike



   .. py:method:: adjoint_mixed(H: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param H: Homogeneous transform
      :type H: npt.ArrayLike

      :returns: adjoint matrix
      :rtype: npt.ArrayLike



   .. py:method:: adjoint_mixed_inverse(H: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param H: Homogeneous transform
      :type H: npt.ArrayLike

      :returns: adjoint matrix
      :rtype: npt.ArrayLike



   .. py:method:: adjoint_mixed_derivative(H: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param H: Homogeneous transform
      :type H: npt.ArrayLike
      :param v: 6D twist
      :type v: npt.ArrayLike

      :returns: adjoint matrix derivative
      :rtype: npt.ArrayLike



   .. py:method:: adjoint_mixed_inverse_derivative(H: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param H: Homogeneous transform
      :type H: npt.ArrayLike
      :param v: 6D twist
      :type v: npt.ArrayLike

      :returns: adjoint matrix derivative
      :rtype: npt.ArrayLike



   .. py:method:: homogeneous_inverse(H: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param H: Homogeneous transform
      :type H: npt.ArrayLike

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



   .. py:method:: zeros(*x: int) -> numpy.typing.ArrayLike

      :param x: dimension
      :type x: int

      :returns: zero matrix of dimension x
      :rtype: npt.ArrayLike



   .. py:method:: eye(x: int) -> numpy.typing.ArrayLike

      :param x: dimension
      :type x: int

      :returns: identity matrix of dimension x
      :rtype: npt.ArrayLike



   .. py:method:: asarray(x: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param x: array
      :type x: npt.ArrayLike

      :returns: array
      :rtype: npt.ArrayLike



   .. py:method:: zeros_like(x: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param x: array
      :type x: npt.ArrayLike

      :returns: zero array with the same shape as x
      :rtype: npt.ArrayLike



   .. py:method:: ones_like(x: numpy.typing.ArrayLike) -> numpy.typing.ArrayLike

      :param x: array
      :type x: npt.ArrayLike

      :returns: one array with the same shape as x
      :rtype: npt.ArrayLike



.. py:class:: ArrayAPISpatialMath(factory, xp_getter: Callable[Ellipsis, Any] = xp_getter)

   Bases: :py:obj:`adam.core.spatial_math.SpatialMath`


   A drop-in SpatialMath that implements sin/cos/outer/concat/skew with the Array API.

   Works for NumPy, PyTorch, and JAX; CasADi should keep its own subclass.


   .. py:attribute:: _xp_getter


   .. py:method:: _xp(*xs: Any)


   .. py:method:: sin(x)

      :param x: angle value
      :type x: npt.ArrayLike

      :returns: sin value of x
      :rtype: npt.ArrayLike



   .. py:method:: cos(x)

      :param x: angle value
      :type x: npt.ArrayLike

      :returns: cos value of angle x
      :rtype: npt.ArrayLike



   .. py:method:: skew(x)


   .. py:method:: outer(x, y)


   .. py:method:: vertcat(*x)

      :param x: elements
      :type x: npt.ArrayLike

      :returns: vertical concatenation of elements x
      :rtype: npt.ArrayLike



   .. py:method:: horzcat(*x)

      :param x: elements
      :type x: npt.ArrayLike

      :returns: horizontal concatenation of elements x
      :rtype: npt.ArrayLike



   .. py:method:: stack(x, axis=0)

      :param x: elements
      :type x: npt.ArrayLike
      :param axis: axis along which to stack
      :type axis: int

      :returns: stacked elements x along axis
      :rtype: npt.ArrayLike



   .. py:method:: concatenate(x, axis=0)

      :param x: elements
      :type x: npt.ArrayLike
      :param axis: axis along which to concatenate
      :type axis: int

      :returns: concatenation of elements x along axis
      :rtype: npt.ArrayLike



   .. py:method:: swapaxes(x: ArrayAPILike, axis1: int, axis2: int) -> ArrayAPILike


   .. py:method:: expand_dims(x: ArrayAPILike, axis: int) -> ArrayAPILike


   .. py:method:: transpose(x: ArrayAPILike, dims: tuple) -> ArrayAPILike

      :param x: input array
      :type x: npt.ArrayLike
      :param dims: permutation of dimensions
      :type dims: tuple

      :returns: transposed array
      :rtype: npt.ArrayLike



   .. py:method:: inv(x: ArrayAPILike) -> ArrayAPILike

      :param x: input array
      :type x: npt.ArrayLike

      :returns: inverse of the array
      :rtype: npt.ArrayLike



   .. py:method:: mtimes(A: ArrayAPILike, B: ArrayAPILike) -> ArrayAPILike


   .. py:method:: solve(A: ArrayAPILike, B: ArrayAPILike) -> ArrayAPILike


.. py:class:: ArrayAPIFactory(like_cls, xp, *, dtype=None, device=None)

   Bases: :py:obj:`adam.core.spatial_math.ArrayLikeFactory`


   Generic factory. Give it (a) a Like class and (b) an xp namespace
   (array_api_compat.* if available; otherwise the library module).


   .. py:attribute:: _like


   .. py:attribute:: _xp


   .. py:attribute:: _dtype
      :value: None



   .. py:attribute:: _device
      :value: None



   .. py:method:: zeros(*shape) -> ArrayAPILike

      :param x: matrix dimension
      :type x: npt.ArrayLike

      :returns: zero matrix of dimension x
      :rtype: npt.ArrayLike



   .. py:method:: eye(*shape) -> ArrayAPILike

      :param x: matrix dimension
      :type x: npt.ArrayLike

      :returns: identity matrix of dimension x
      :rtype: npt.ArrayLike



   .. py:method:: asarray(x) -> ArrayAPILike

      :param x: array
      :type x: npt.ArrayLike

      :returns: array
      :rtype: npt.ArrayLike



   .. py:method:: zeros_like(x: ArrayAPILike) -> ArrayAPILike

      :param x: array
      :type x: npt.ArrayLike

      :returns: one array with the same shape as x
      :rtype: npt.ArrayLike



   .. py:method:: ones_like(x: ArrayAPILike) -> ArrayAPILike

      :param x: array
      :type x: npt.ArrayLike

      :returns: one array with the same shape as x
      :rtype: npt.ArrayLike



   .. py:method:: tile(x: ArrayAPILike, reps: tuple) -> ArrayAPILike

      :param x: input array
      :type x: npt.ArrayLike
      :param reps: repetition factors for each dimension
      :type reps: tuple

      :returns: tiled array
      :rtype: npt.ArrayLike



.. py:class:: ArrayAPILike

   Bases: :py:obj:`adam.core.spatial_math.ArrayLike`


   Generic Array-API-style wrapper used by NumPy/JAX/Torch backends.


   .. py:attribute:: array
      :type:  Any


   .. py:method:: __getitem__(idx) -> ArrayAPILike


   .. py:property:: shape


   .. py:method:: reshape(*args)


   .. py:property:: T
      :type: ArrayAPILike


      Transpose of the array

      :type: Returns


   .. py:method:: __matmul__(other)


   .. py:method:: __rmatmul__(other) -> ArrayAPILike


   .. py:method:: __mul__(other) -> ArrayAPILike


   .. py:method:: __rmul__(other) -> ArrayAPILike


   .. py:method:: __truediv__(other) -> ArrayAPILike


   .. py:method:: __add__(other) -> ArrayAPILike


   .. py:method:: __radd__(other) -> ArrayAPILike


   .. py:method:: __sub__(other) -> ArrayAPILike


   .. py:method:: __rsub__(other) -> ArrayAPILike


   .. py:method:: __neg__() -> ArrayAPILike


   .. py:property:: ndim


