adam.core.spatial_math#

Classes#

ArrayLike

Abstract class for a generic Array wrapper. Every method should be implemented for every data type.

ArrayLikeFactory

Abstract class for a generic Array wrapper. Every method should be implemented for every data type.

SpatialMath

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

Module Contents#

class adam.core.spatial_math.ArrayLike[source]#

Bases: abc.ABC

Abstract class for a generic Array wrapper. Every method should be implemented for every data type.

abstractmethod __add__(other)[source]#
abstractmethod __radd__(other)[source]#
abstractmethod __sub__(other)[source]#
abstractmethod __rsub__(other)[source]#
abstractmethod __mul__(other)[source]#
abstractmethod __rmul__(other)[source]#
abstractmethod __matmul__(other)[source]#
abstractmethod __rmatmul__(other)[source]#
abstractmethod __neg__()[source]#
abstractmethod __getitem__(item)[source]#
abstractmethod __setitem__(key, value)[source]#
abstractmethod __truediv__(other)[source]#
abstract property T[source]#

Transpose of the array

Type:

Returns

class adam.core.spatial_math.ArrayLikeFactory[source]#

Bases: abc.ABC

Abstract class for a generic Array wrapper. Every method should be implemented for every data type.

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

x (npt.ArrayLike) – matrix dimension

Returns:

zero matrix of dimension x

Return type:

npt.ArrayLike

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

x (npt.ArrayLike) – matrix dimension

Returns:

identity matrix of dimension x

Return type:

npt.ArrayLike

class adam.core.spatial_math.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[source]#
property factory: ArrayLikeFactory[source]#
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 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: numpy.typing.ArrayLike, q: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • axis (npt.ArrayLike) – axis vector

  • q (npt.ArrayLike) – angle value

Returns:

rotation matrix from axis-angle representation

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

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

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(I: numpy.typing.ArrayLike, mass: numpy.typing.ArrayLike, c: numpy.typing.ArrayLike, rpy: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:
  • I (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_inertial_with_parameters(I, 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

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