Pose3d

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

Bases: pybind11_object

Represents a 3D pose containing translational and rotational elements.

Overloaded function.

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

Constructs a pose at the origin facing toward the positive X axis.

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

Constructs a pose with the specified translation and rotation.

Parameters:
  • translation – The translational component of the pose.

  • rotation – The rotational component of the pose.

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

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

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

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

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

  • rotation – The rotational component of the pose.

  1. __init__(self: wpimath._wpimath.Pose3d, pose: wpimath._wpimath.Pose2d) -> None

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

Parameters:

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

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

Returns the X component of the pose’s translation.

Returns:

The x component of the pose’s translation.

Y() wpimath.units.meters

Returns the Y component of the pose’s translation.

Returns:

The y component of the pose’s translation.

Z() wpimath.units.meters

Returns the Z component of the pose’s translation.

Returns:

The z component of the pose’s translation.

static fromFeet(x: wpimath.units.feet, y: wpimath.units.feet, z: wpimath.units.feet, r: wpimath._wpimath.Rotation3d) wpimath._wpimath.Pose3d
static fromMatrix(matrix: Annotated[numpy.typing.ArrayLike, numpy.float64, '[4, 4]']) wpimath._wpimath.Pose3d

Constructs a pose with the specified affine transformation matrix.

Parameters:

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

nearest(poses: List[wpimath._wpimath.Pose3d]) wpimath._wpimath.Pose3d

Returns the nearest Pose3d from a collection of poses.

If two or more poses in the collection have the same distance from this pose, return the one with the closest rotation component.

Parameters:

poses – The collection of poses.

Returns:

The nearest Pose3d from the collection.

relativeTo(other: wpimath._wpimath.Pose3d) wpimath._wpimath.Pose3d

Returns the current pose relative to the given pose.

This function can often be used for trajectory tracking or pose stabilization algorithms to get the error between the reference and the current pose.

Parameters:

other – The pose that is the origin of the new coordinate frame that the current pose will be converted into.

Returns:

The current pose relative to the new origin pose.

rotateAround(point: wpimath._wpimath.Translation3d, rot: wpimath._wpimath.Rotation3d) wpimath._wpimath.Pose3d

Rotates the current pose around a point in 3D space.

Parameters:
  • point – The point in 3D space to rotate around.

  • rot – The rotation to rotate the pose by.

Returns:

The new rotated pose.

rotateBy(other: wpimath._wpimath.Rotation3d) wpimath._wpimath.Pose3d

Rotates the pose around the origin and returns the new pose.

Parameters:

other – The rotation to transform the pose by, which is applied extrinsically (from the global frame).

Returns:

The rotated pose.

rotation() wpimath._wpimath.Rotation3d

Returns the underlying rotation.

Returns:

Reference to the rotational component of the pose.

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

Returns an affine transformation matrix representation of this pose.

toPose2d() wpimath._wpimath.Pose2d

Returns a Pose2d representing this Pose3d projected into the X-Y plane.

transformBy(other: wpimath._wpimath.Transform3d) wpimath._wpimath.Pose3d

Transforms the pose by the given transformation and returns the new transformed pose. The transform is applied relative to the pose’s frame. Note that this differs from Pose3d::RotateBy(const Rotation3d&), which is applied relative to the global frame and around the origin.

Parameters:

other – The transform to transform the pose by.

Returns:

The transformed pose.

translation() wpimath._wpimath.Translation3d

Returns the underlying translation.

Returns:

Reference to the translational component of the pose.

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