adam.casadi.casadi_like
=======================

.. py:module:: adam.casadi.casadi_like


Classes
-------

.. autoapisummary::

   adam.casadi.casadi_like.CasadiLike
   adam.casadi.casadi_like.CasadiLikeFactory
   adam.casadi.casadi_like.SpatialMath


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

.. py:class:: CasadiLike

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


   Wrapper class for CasADi SX/DM with ArrayLike ops.


   .. py:attribute:: array
      :type:  Union[casadi.SX, casadi.DM]


   .. py:method:: __matmul__(other: CasadiLike) -> CasadiLike


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


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


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


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


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


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


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


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


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


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


   .. py:property:: shape
      :type: tuple[int, Ellipsis]



   .. py:property:: ndim
      :type: int



   .. py:property:: T
      :type: CasadiLike


      Transpose of the array

      :type: Returns


.. py:class:: CasadiLikeFactory(xp: Union[casadi.SX, casadi.DM, None] = None)

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


   ArrayLikeFactory for CasADi. Drops batch dims (>2) since CasADi is 2-D only.


   .. py:attribute:: _xp


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

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

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



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

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

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



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

      Convert input to a CasadiLike array.

      This method handles various input types and converts them to CasadiLike objects
      using appropriate CasADi operations for concatenation and array construction.

      :param x: Input to convert. Can be:
      :param - Empty list: Returns empty CasadiLike array
      :param - List of CasADi objects: Horizontally concatenated
      :type - List of CasADi objects: cs.SX, cs.DM
      :param - List of lists/tuples: Creates 2D array with vertical and horizontal concatenation
      :param - Numbers or lists of numbers: Direct conversion to CasadiLike

      :returns: A CasadiLike object wrapping the converted input.
      :rtype: CasadiLike

      .. rubric:: Examples

      - Empty list [] -> CasadiLike with empty array
      - [sx1, sx2] -> CasadiLike with horizontally concatenated SX objects
      - [[1, 2], [3, 4]] -> CasadiLike with 2x2 matrix
      - 5 or [1, 2, 3] -> CasadiLike with direct conversion



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

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

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



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

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

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



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

      :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:: SpatialMath(spec=None)

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


   CasADi backend for SpatialMath. Keeps the same high-level API.


   .. py:method:: sin(x: CasadiLike) -> CasadiLike
      :staticmethod:


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

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



   .. py:method:: cos(x: CasadiLike) -> CasadiLike
      :staticmethod:


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

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



   .. py:method:: skew(x: Union[CasadiLike, numpy.typing.ArrayLike]) -> CasadiLike
      :staticmethod:



   .. py:method:: outer(x: CasadiLike, y: CasadiLike) -> CasadiLike
      :staticmethod:



   .. py:method:: vertcat(*x: CasadiLike) -> CasadiLike
      :staticmethod:


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

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



   .. py:method:: horzcat(*x: CasadiLike) -> CasadiLike
      :staticmethod:


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

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



   .. py:method:: stack(x: Sequence[CasadiLike], axis: int = 0) -> CasadiLike
      :staticmethod:


      :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: Sequence[CasadiLike], axis: int = 0) -> CasadiLike
      :staticmethod:


      Concatenate a sequence of CasadiLike objects along a specified axis.

      This function provides flexible concatenation behavior with special handling
      for common use cases in CasADi operations.

      :param x: Sequence of CasadiLike objects to concatenate
      :type x: Sequence[CasadiLike]
      :param axis: Axis along which to concatenate. Defaults to 0.
                   - 0 or -2: Vertical concatenation (stack rows)
                   - 1 or -1: Horizontal concatenation (stack columns)
      :type axis: int, optional

      :returns: The concatenated result
      :rtype: CasadiLike

      :raises NotImplementedError: If axis is not in {-2, -1, 0, 1}

      Special Cases:
          - When axis=-1 and exactly 2 column vectors are provided, they are
          vertically stacked to create a longer column vector
          - For horizontal concatenation (axis=1 or -1), if arrays don't have
          matching row dimensions, the function attempts to reshape them:
          * 1D arrays are reshaped to column vectors
          * Row vectors (1xn) are transposed to column vectors
          * Other shapes are kept as-is and stacked vertically

      .. note::

         The function uses CasADi's vertcat and horzcat functions internally
         for the actual concatenation operations.



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



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

      :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: CasadiLike, dims: tuple) -> CasadiLike

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

      :returns: transposed array
      :rtype: npt.ArrayLike



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


      Expand dimensions of a CasADi array.

      :param x: Input array (CasadiLike)
      :param axis: Position where new axis is to be inserted

      :returns: Array with expanded dimensions
      :rtype: CasadiLike



   .. py:method:: inv(x: CasadiLike) -> CasadiLike
      :staticmethod:


      Matrix inversion for CasADi.

      :param x: Matrix to invert (CasadiLike)

      :returns: Inverse of x
      :rtype: CasadiLike



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


      Solve linear system Ax = B for x using CasADi.

      :param A: Coefficient matrix (CasadiLike)
      :param B: Right-hand side vector or matrix (CasadiLike)

      :returns: Solution x
      :rtype: CasadiLike



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


      Matrix-matrix multiplication for CasADi.

      :param A: First matrix (CasadiLike)
      :param B: Second matrix (CasadiLike)

      :returns: Result of A @ B
      :rtype: CasadiLike



   .. py:method:: mxv(m: CasadiLike, v: CasadiLike) -> CasadiLike
      :staticmethod:


      Matrix-vector multiplication for CasADi.

      :param m: Matrix (CasadiLike)
      :param v: Vector (CasadiLike)

      :returns: Returns a *column* vector (n,1).
      :rtype: CasadiLike



   .. py:method:: vxs(v: CasadiLike, c: CasadiLike) -> CasadiLike
      :staticmethod:


      Vector times scalar multiplication for CasADi.

      :param v: Vector (CasadiLike)
      :param c: Scalar (CasadiLike)

      :returns: Result of vector times scalar
      :rtype: CasadiLike



