Transform3d

class wpimath.Transform3d(*args, **kwargs)

Bases: pybind11_object

Represents a transformation for a Pose3d in the pose’s frame. Translation is applied before rotation. (The translation is applied in the pose’s original frame, not the transformed frame.)

Overloaded function.

  1. __init__(self: wpimath._wpimath.Transform3d, initial: wpimath._wpimath.Pose3d, final: wpimath._wpimath.Pose3d) -> None

Constructs the transform that maps the initial pose to the final pose.

Parameters:
  • initial – The initial pose for the transformation.

  • final – The final pose for the transformation.

  1. __init__(self: wpimath._wpimath.Transform3d, translation: wpimath._wpimath.Translation3d, rotation: wpimath._wpimath.Rotation3d) -> None

Constructs a transform with the given translation and rotation components.

Parameters:
  • translation – Translational component of the transform.

  • rotation – Rotational component of the transform.

  1. __init__(self: wpimath._wpimath.Transform3d, x: wpimath.units.meters, y: wpimath.units.meters, z: wpimath.units.meters, rotation: wpimath._wpimath.Rotation3d) -> None

Constructs a transform with x, y, and z translations instead of a separate Translation3d.

Parameters:
  • x – The x component of the translational component of the transform.

  • y – The y component of the translational component of the transform.

  • z – The z component of the translational component of the transform.

  • rotation – The rotational component of the transform.

  1. __init__(self: wpimath._wpimath.Transform3d) -> None

Constructs the identity transform – maps an initial pose to itself.

  1. __init__(self: wpimath._wpimath.Transform3d, transform: wpimath._wpimath.Transform2d) -> None

Constructs a 3D transform from a 2D transform in the X-Y plane. **

Parameters:

transform – The 2D transform. @see Rotation3d(Rotation2d) @see Translation3d(Translation2d)

WPIStruct = <capsule object "WPyStruct">
X() wpimath.units.meters

Returns the X component of the transformation’s translation.

Returns:

The x component of the transformation’s translation.

Y() wpimath.units.meters

Returns the Y component of the transformation’s translation.

Returns:

The y component of the transformation’s translation.

Z() wpimath.units.meters

Returns the Z component of the transformation’s translation.

Returns:

The z component of the transformation’s translation.

static fromMatrix(matrix: Annotated[numpy.typing.ArrayLike, numpy.float64, '[4, 4]']) wpimath._wpimath.Transform3d

Constructs a transform with the specified affine transformation matrix.

Parameters:

matrix – The affine transformation matrix. @throws std::domain_error if the affine transformation matrix is invalid.

inverse() wpimath._wpimath.Transform3d

Invert the transformation. This is useful for undoing a transformation.

Returns:

The inverted transformation.

log() wpimath._wpimath.Twist3d

Returns a Twist3d of the current transform (pose delta). If b is the output of a.Log(), then b.Exp() would yield a.

Returns:

The twist that maps the current transform.

rotation() wpimath._wpimath.Rotation3d

Returns the rotational component of the transformation.

Returns:

Reference to the rotational component of the transform.

toMatrix() Annotated[numpy.typing.NDArray[numpy.float64], '[4, 4]']

Returns an affine transformation matrix representation of this transformation.

translation() wpimath._wpimath.Translation3d

Returns the translation component of the transformation.

Returns:

Reference to the translational component of the transform.

property x
property x_feet
property y
property y_feet
property z
property z_feet