adam.core

Contents

adam.core#

Submodules#

Classes#

Representations

Enum where members are also (and must be) ints

RBDAlgorithms

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

SpatialMath

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

ArrayAPISpatialMath

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

ArrayAPIFactory

Generic factory. Give it (a) a Like class and (b) an xp namespace

ArrayAPILike

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

Package Contents#

class adam.core.Representations[source]#

Bases: enum.IntEnum

Enum where members are also (and must be) ints

BODY_FIXED_REPRESENTATION#
MIXED_REPRESENTATION#
INERTIAL_FIXED_REPRESENTATION#
class adam.core.RBDAlgorithms(model: adam.model.Model, math: adam.core.spatial_math.SpatialMath)[source]#

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

model#
NDoF#
math#
frame_velocity_representation#
_root_spatial_transform#
_root_motion_subspace#
set_frame_velocity_representation(representation: adam.core.constants.Representations)[source]#

Sets the frame velocity representation

Parameters:

representation (str) – The representation of the frame velocity

crba(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike)[source]#

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

Parameters:
  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The mass matrix and the centroidal momentum matrix

Return type:

M, Jcm (npt.ArrayLike, npt.ArrayLike)

forward_kinematics(frame, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#

Computes the forward kinematics relative to the specified frame.

Parameters:
  • frame (str) – The frame to which the fk will be computed

  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The fk represented as Homogenous transformation matrix

Return type:

I_H_L (npt.ArrayLike)

joints_jacobian(frame: str, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#

Returns the Jacobian relative to the specified frame.

Parameters:
  • frame (str) – The frame to which the jacobian will be computed

  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The Joints Jacobian relative to the frame

Return type:

J (npt.ArrayLike)

jacobian(frame: str, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#

Returns the Jacobian for frame.

Parameters:
  • frame (str) – The frame to which the jacobian will be computed

  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The Jacobian for the specified frame

Return type:

npt.ArrayLike

relative_jacobian(frame: str, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#

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

Parameters:
  • frame (str) – The tip of the chain

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The 6 x NDoF Jacobian between the root and the frame

Return type:

J (npt.ArrayLike)

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[source]#

Returns the Jacobian time derivative for frame.

Parameters:
  • frame (str) – The frame to which the jacobian will be computed

  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

  • base_velocity (npt.ArrayLike) – The spatial velocity of the base

  • joint_velocities (npt.ArrayLike) – The joints velocities

Returns:

The Jacobian derivative relative to the frame

Return type:

J_dot (npt.ArrayLike)

CoM_position(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#

Returns the CoM position

Parameters:
  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The CoM position

Return type:

com (npt.ArrayLike)

CoM_jacobian(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#

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

Parameters:
  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The CoM Jacobian

Return type:

J_com (npt.ArrayLike)

get_total_mass()[source]#

Returns the total mass of the robot

Returns:

The total mass

Return type:

mass

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[source]#

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

Parameters:
  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

  • base_velocity (npt.ArrayLike) – The base spatial velocity

  • joint_velocities (npt.ArrayLike) – The joints velocities

  • g (npt.ArrayLike) – The gravity vector

Returns:

The vector of generalized forces

Return type:

tau (npt.ArrayLike)

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[source]#

Featherstone Articulated Body Algorithm for floating-base forward dynamics.

Parameters:
  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

  • base_velocity (npt.ArrayLike) – The spatial velocity of the base

  • joint_velocities (npt.ArrayLike) – The joints velocities

  • joint_torques (npt.ArrayLike) – The joints torques/forces

  • g (npt.ArrayLike | None, optional) – The gravity vector

  • external_wrenches (dict[str, npt.ArrayLike] | None, optional) – A dictionary of external wrenches applied to specific links. Keys are link names, and values are 6D wrench vectors. Defaults to None.

Returns:

The spatial acceleration of the base and joints accelerations

Return type:

accelerations (npt.ArrayLike)

_convert_to_arraylike(*args)[source]#

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

Returns:

Converted arguments as ArrayLike.

_prepare_tree_cache() None[source]#

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

class adam.core.SpatialMath(factory: ArrayLikeFactory)[source]#

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

Parameters:

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

_factory#
property factory: ArrayLikeFactory#
abstractmethod vertcat(x: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

x (npt.ArrayLike) – elements

Returns:

vertical concatenation of elements x

Return type:

npt.ArrayLike

abstractmethod horzcat(x: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

x (npt.ArrayLike) – elements

Returns:

horizontal concatenation of elements x

Return type:

npt.ArrayLike

abstractmethod concatenate(x: numpy.typing.ArrayLike, axis: int) numpy.typing.ArrayLike[source]#
Parameters:
  • x (npt.ArrayLike) – elements

  • axis (int) – axis along which to concatenate

Returns:

concatenation of elements x along axis

Return type:

npt.ArrayLike

abstractmethod stack(x: numpy.typing.ArrayLike, axis: int) numpy.typing.ArrayLike[source]#
Parameters:
  • x (npt.ArrayLike) – elements

  • axis (int) – axis along which to stack

Returns:

stacked elements x along axis

Return type:

npt.ArrayLike

abstractmethod tile(x: numpy.typing.ArrayLike, reps: tuple) numpy.typing.ArrayLike[source]#
Parameters:
  • x (npt.ArrayLike) – input array

  • reps (tuple) – repetition factors for each dimension

Returns:

tiled array

Return type:

npt.ArrayLike

abstractmethod transpose(x: numpy.typing.ArrayLike, dims: tuple) numpy.typing.ArrayLike[source]#
Parameters:
  • x (npt.ArrayLike) – input array

  • dims (tuple) – permutation of dimensions

Returns:

transposed array

Return type:

npt.ArrayLike

abstractmethod inv(x: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

x (npt.ArrayLike) – input array

Returns:

inverse of the array

Return type:

npt.ArrayLike

abstractmethod mtimes(x: numpy.typing.ArrayLike, y: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
abstractmethod sin(x: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

x (npt.ArrayLike) – angle value

Returns:

sin value of x

Return type:

npt.ArrayLike

abstractmethod cos(x: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

x (npt.ArrayLike) – angle value

Returns:

cos value of angle x

Return type:

npt.ArrayLike

abstractmethod skew(x)[source]#
R_from_axis_angle(axis, q)[source]#

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

sxm(s: numpy.typing.ArrayLike, m: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#

Computes scalar multiplication with a matrix

Parameters:
  • s (npt.ArrayLike) – scalar value

  • m (npt.ArrayLike) – matrix to be multiplied

Returns:

result of the multiplication

Return type:

npt.ArrayLike

Rx(q: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

q (npt.ArrayLike) – angle value

Returns:

rotation matrix around x axis

Return type:

npt.ArrayLike

Ry(q: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

q (npt.ArrayLike) – angle value

Returns:

rotation matrix around y axis

Return type:

npt.ArrayLike

Rz(q: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

q (npt.ArrayLike) – angle value

Returns:

rotation matrix around z axis

Return type:

npt.ArrayLike

H_revolute_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike, axis: numpy.typing.ArrayLike, q: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • xyz (npt.ArrayLike) – joint origin in the urdf

  • rpy (npt.ArrayLike) – joint orientation in the urdf

  • axis (npt.ArrayLike) – joint axis in the urdf

  • q (npt.ArrayLike) – joint angle value

Returns:

Homogeneous transform

Return type:

npt.ArrayLike

homogeneous(R, p)[source]#
H_prismatic_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike, axis: numpy.typing.ArrayLike, q: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • xyz (npt.ArrayLike) – joint origin in the urdf

  • rpy (npt.ArrayLike) – joint orientation in the urdf

  • axis (npt.ArrayLike) – joint axis in the urdf

  • q (npt.ArrayLike) – joint angle value

Returns:

Homogeneous transform

Return type:

npt.ArrayLike

H_from_Pos_RPY(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • xyz (npt.ArrayLike) – translation vector

  • rpy (npt.ArrayLike) – rotation as rpy angles

Returns:

Homegeneous transform

Return type:

npt.ArrayLike

R_from_RPY(rpy: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

rpy (npt.ArrayLike) – rotation as rpy angles

Returns:

Rotation matrix

Return type:

npt.ArrayLike

X_revolute_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike, axis: numpy.typing.ArrayLike, q: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • xyz (npt.ArrayLike) – joint origin in the urdf

  • rpy (npt.ArrayLike) – joint orientation in the urdf

  • axis (npt.ArrayLike) – joint axis in the urdf

  • q (npt.ArrayLike) – joint angle value

Returns:

Spatial transform of a revolute joint given its rotation angle

Return type:

npt.ArrayLike

X_prismatic_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike, axis: numpy.typing.ArrayLike, q: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • xyz (npt.ArrayLike) – joint origin in the urdf

  • rpy (npt.ArrayLike) – joint orientation in the urdf

  • axis (npt.ArrayLike) – joint axis in the urdf

  • q (npt.ArrayLike) – joint angle value

Returns:

Spatial transform of a prismatic joint given its increment

Return type:

npt.ArrayLike

X_fixed_joint(xyz: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • xyz (npt.ArrayLike) – joint origin in the urdf

  • rpy (npt.ArrayLike) – joint orientation in the urdf

Returns:

Spatial transform of a fixed joint

Return type:

npt.ArrayLike

_X_from_H(T)[source]#
spatial_transform(R: numpy.typing.ArrayLike, p: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • R (npt.ArrayLike) – Rotation matrix

  • p (npt.ArrayLike) – translation vector

Returns:

spatial transform

Return type:

npt.ArrayLike

spatial_inertia(inertia_matrix: numpy.typing.ArrayLike, mass: numpy.typing.ArrayLike, c: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • inertia_matrix (npt.ArrayLike) – inertia values from urdf

  • mass (npt.ArrayLike) – mass value from urdf

  • c (npt.ArrayLike) – origin of the link from urdf

  • rpy (npt.ArrayLike) – orientation of the link from the urdf

Returns:

the 6x6 inertia matrix expressed at the origin of the link (with rotation)

Return type:

npt.ArrayLike

spatial_inertia_with_parameters(inertia_matrix, mass, c, rpy)[source]#
Parameters:
  • I (npt.ArrayLike) – inertia values parametric

  • mass (npt.ArrayLike) – mass value parametric

  • c (npt.ArrayLike) – origin of the link parametric

  • rpy (npt.ArrayLike) – orientation of the link from urdf

Returns:

the 6x6 inertia matrix parametric expressed at the origin of the link (with rotation)

Return type:

npt.ArrayLike

spatial_skew(v: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

v (npt.ArrayLike) – 6D vector

Returns:

spatial skew matrix

Return type:

npt.ArrayLike

spatial_skew_star(v: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

v (npt.ArrayLike) – 6D vector

Returns:

negative spatial skew matrix traspose

Return type:

npt.ArrayLike

adjoint(H: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

H (npt.ArrayLike) – Homogeneous transform

Returns:

adjoint matrix

Return type:

npt.ArrayLike

adjoint_derivative(H: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • H (npt.ArrayLike) – Homogeneous transform

  • v (npt.ArrayLike) – 6D twist

Returns:

adjoint matrix derivative

Return type:

npt.ArrayLike

mxv(m: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • m (npt.ArrayLike) – Matrix

  • v (npt.ArrayLike) – Vector

Returns:

Result of matrix-vector multiplication

Return type:

npt.ArrayLike

vxs(v: numpy.typing.ArrayLike, s: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • v (npt.ArrayLike) – Vector

  • s (npt.ArrayLike) – Scalar

Returns:

Result of vector cross product with scalar multiplication

Return type:

npt.ArrayLike

adjoint_inverse(H: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

H (npt.ArrayLike) – Homogeneous transform

Returns:

adjoint matrix

Return type:

npt.ArrayLike

adjoint_inverse_derivative(H: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • H (npt.ArrayLike) – Homogeneous transform

  • v (npt.ArrayLike) – 6D twist

Returns:

adjoint matrix derivative

Return type:

npt.ArrayLike

adjoint_mixed(H: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

H (npt.ArrayLike) – Homogeneous transform

Returns:

adjoint matrix

Return type:

npt.ArrayLike

adjoint_mixed_inverse(H: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

H (npt.ArrayLike) – Homogeneous transform

Returns:

adjoint matrix

Return type:

npt.ArrayLike

adjoint_mixed_derivative(H: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • H (npt.ArrayLike) – Homogeneous transform

  • v (npt.ArrayLike) – 6D twist

Returns:

adjoint matrix derivative

Return type:

npt.ArrayLike

adjoint_mixed_inverse_derivative(H: numpy.typing.ArrayLike, v: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • H (npt.ArrayLike) – Homogeneous transform

  • v (npt.ArrayLike) – 6D twist

Returns:

adjoint matrix derivative

Return type:

npt.ArrayLike

homogeneous_inverse(H: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

H (npt.ArrayLike) – Homogeneous transform

Returns:

inverse of the homogeneous transform

Return type:

npt.ArrayLike

zeros(*x: int) numpy.typing.ArrayLike[source]#
Parameters:

x (int) – dimension

Returns:

zero matrix of dimension x

Return type:

npt.ArrayLike

eye(x: int) numpy.typing.ArrayLike[source]#
Parameters:

x (int) – dimension

Returns:

identity matrix of dimension x

Return type:

npt.ArrayLike

asarray(x: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

x (npt.ArrayLike) – array

Returns:

array

Return type:

npt.ArrayLike

zeros_like(x: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

x (npt.ArrayLike) – array

Returns:

zero array with the same shape as x

Return type:

npt.ArrayLike

ones_like(x: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

x (npt.ArrayLike) – array

Returns:

one array with the same shape as x

Return type:

npt.ArrayLike

class adam.core.ArrayAPISpatialMath(factory, xp_getter: Callable[Ellipsis, Any] = xp_getter)[source]#

Bases: 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.

_xp_getter#
_xp(*xs: Any)[source]#
sin(x)[source]#
Parameters:

x (npt.ArrayLike) – angle value

Returns:

sin value of x

Return type:

npt.ArrayLike

cos(x)[source]#
Parameters:

x (npt.ArrayLike) – angle value

Returns:

cos value of angle x

Return type:

npt.ArrayLike

skew(x)[source]#
outer(x, y)[source]#
vertcat(*x)[source]#
Parameters:

x (npt.ArrayLike) – elements

Returns:

vertical concatenation of elements x

Return type:

npt.ArrayLike

horzcat(*x)[source]#
Parameters:

x (npt.ArrayLike) – elements

Returns:

horizontal concatenation of elements x

Return type:

npt.ArrayLike

stack(x, axis=0)[source]#
Parameters:
  • x (npt.ArrayLike) – elements

  • axis (int) – axis along which to stack

Returns:

stacked elements x along axis

Return type:

npt.ArrayLike

concatenate(x, axis=0)[source]#
Parameters:
  • x (npt.ArrayLike) – elements

  • axis (int) – axis along which to concatenate

Returns:

concatenation of elements x along axis

Return type:

npt.ArrayLike

swapaxes(x: ArrayAPILike, axis1: int, axis2: int) ArrayAPILike[source]#
expand_dims(x: ArrayAPILike, axis: int) ArrayAPILike[source]#
transpose(x: ArrayAPILike, dims: tuple) ArrayAPILike[source]#
Parameters:
  • x (npt.ArrayLike) – input array

  • dims (tuple) – permutation of dimensions

Returns:

transposed array

Return type:

npt.ArrayLike

inv(x: ArrayAPILike) ArrayAPILike[source]#
Parameters:

x (npt.ArrayLike) – input array

Returns:

inverse of the array

Return type:

npt.ArrayLike

mtimes(A: ArrayAPILike, B: ArrayAPILike) ArrayAPILike[source]#
solve(A: ArrayAPILike, B: ArrayAPILike) ArrayAPILike[source]#
class adam.core.ArrayAPIFactory(like_cls, xp, *, dtype=None, device=None)[source]#

Bases: 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).

_like#
_xp#
_dtype = None#
_device = None#
zeros(*shape) ArrayAPILike[source]#
Parameters:

x (npt.ArrayLike) – matrix dimension

Returns:

zero matrix of dimension x

Return type:

npt.ArrayLike

eye(*shape) ArrayAPILike[source]#
Parameters:

x (npt.ArrayLike) – matrix dimension

Returns:

identity matrix of dimension x

Return type:

npt.ArrayLike

asarray(x) ArrayAPILike[source]#
Parameters:

x (npt.ArrayLike) – array

Returns:

array

Return type:

npt.ArrayLike

zeros_like(x: ArrayAPILike) ArrayAPILike[source]#
Parameters:

x (npt.ArrayLike) – array

Returns:

one array with the same shape as x

Return type:

npt.ArrayLike

ones_like(x: ArrayAPILike) ArrayAPILike[source]#
Parameters:

x (npt.ArrayLike) – array

Returns:

one array with the same shape as x

Return type:

npt.ArrayLike

tile(x: ArrayAPILike, reps: tuple) ArrayAPILike[source]#
Parameters:
  • x (npt.ArrayLike) – input array

  • reps (tuple) – repetition factors for each dimension

Returns:

tiled array

Return type:

npt.ArrayLike

class adam.core.ArrayAPILike[source]#

Bases: adam.core.spatial_math.ArrayLike

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

array: Any#
__getitem__(idx) ArrayAPILike[source]#
property shape#
reshape(*args)[source]#
property T: ArrayAPILike#

Transpose of the array

Type:

Returns

__matmul__(other)[source]#
__rmatmul__(other) ArrayAPILike[source]#
__mul__(other) ArrayAPILike[source]#
__rmul__(other) ArrayAPILike[source]#
__truediv__(other) ArrayAPILike[source]#
__add__(other) ArrayAPILike[source]#
__radd__(other) ArrayAPILike[source]#
__sub__(other) ArrayAPILike[source]#
__rsub__(other) ArrayAPILike[source]#
__neg__() ArrayAPILike[source]#
property ndim#