pyrobopath.toolpath.path.transform.Transform#

class pyrobopath.toolpath.path.transform.Transform(trans: List[float] | Tuple[float, float, float] | ndarray[Tuple[Literal[3]], dtype[floating]] | None = None, orient: List[float] | Tuple[float, float, float, float] | ndarray[Tuple[Literal[4]], dtype[floating]] | quaternion | None = None)[source]#

Bases: object

A transformation class that implements spatial transformations on members of the group SE3 (Special Euclidean)

This class internally represents a 3D pose (or transformation) as a translation (3D numpy array) and a rotation (numpy-quaternion).

It provides class methods that facilitate constructing transformation with common SE3 parameterizations (i.e. axis rotations, quaternions, homogeneous transformations, Euler angles., translations)

Parameters:
  • trans (ArrayLike3) – The translational component (default: [0, 0, 0])

  • orient (Quat) – The rotational component as {w, x, y, z} (default: [1, 0, 0, 0])

Methods

Quaternion

Construct a new SE(3) transformation instance from Quaternion

Rx

Construct a new SE(3) transformation from X-axis rotation

Ry

Construct a new SE(3) transformation from Y-axis rotation

Rz

Construct a new SE(3) transformation from Z-axis rotation

Trans

Construct a new SE(3) instance from a pure translation

almost_equal

copy

interp

Interpolate between SE(3) instances

inv

Find the inverse transformation of the SE(3) instance

Attributes

N

Dimension of the object's group (superclass property)

R

Rotational component of SE(3)

matrix

The homogeneous transformation matrix

quat

Get the rotational component of the tranformation as a quaternion

t

Translation component of SE(3)

property N: int#

Dimension of the object’s group (superclass property)

Returns:

dimension

Return type:

int

This corresponds to the dimension of the space, 2D or 3D, to which these rotations or rigid-body motions apply.

classmethod Quaternion(w: float, x: float, y: float, z: float) Transform[source]#

Construct a new SE(3) transformation instance from Quaternion

q = [w, x, y, z]

Parameters:
  • w (float) – the real component

  • x (float) – the x component of the imaginary vector

  • y (float) – the y component of the imaginary vector

  • z (float) – the z component of the imaginary vector

Returns:

SE(3) rotation

Return type:

Pose instance

property R: ndarray[Tuple[Literal[3], Literal[3]], dtype[floating]]#

Rotational component of SE(3)

Returns:

A readonly matrix view of the SO(3) rotation

Return type:

R3x3

classmethod Rx(theta: float) Transform[source]#

Construct a new SE(3) transformation from X-axis rotation

Parameters:

θ (float or array_like) – rotation angle about the X-axis

Returns:

SE(3) rotation

Return type:

SE3 instance

classmethod Ry(theta: float) Transform[source]#

Construct a new SE(3) transformation from Y-axis rotation

Parameters:

θ (float or array_like) – rotation angle about the Y-axis

Returns:

SE(3) rotation

Return type:

SE3 instance

classmethod Rz(theta: float) Transform[source]#

Construct a new SE(3) transformation from Z-axis rotation

Parameters:

θ (float or array_like) – rotation angle about the Z-axis

Returns:

SE(3) rotation

Return type:

SE3 instance

classmethod Trans(x: float | List[float] | Tuple[float, float, float] | ndarray[Tuple[Literal[3]], dtype[floating]], y: float | None = None, z: float | None = None) Transform[source]#

Construct a new SE(3) instance from a pure translation

Parameters:
  • x (float or ArrayLike3) – the x value of the translation (if float) or a 3 vector position (if ArrayLike3)

  • y (float) – the y value of the translation

  • z (float) – the z value of the translation

Returns:

SE(3) translation

Return type:

SE3

interp(other: Transform, s: float) Transform[source]#

Interpolate between SE(3) instances

Parameters:
  • other (SE3) – the ending orientation at s = 1.0

  • s (float) – the interpolation variable s in [0, 1]

Returns:

the SE(3) instances interpolated at value s

Return type:

SE(3)

inv() Transform[source]#

Find the inverse transformation of the SE(3) instance

Returns:

SE(3) inverse

Return type:

SE3

property matrix: ndarray[Tuple[Literal[4], Literal[4]], dtype[floating]]#

The homogeneous transformation matrix

Returns:

An array view of the 4x4 homogeneous transformation

Return type:

R4x4

property quat: quaternion#

Get the rotational component of the tranformation as a quaternion

Returns:

The rotation of the transformation as a quaternion

Return type:

Quat

property t: ndarray[Tuple[Literal[3]], dtype[floating]]#

Translation component of SE(3)

Returns:

An array view of the R3 translation

Return type:

R3