Pose2d
- class wpimath.Pose2d(*args, **kwargs)
Bases:
pybind11_objectRepresents a 2D pose containing translational and rotational elements.
Overloaded function.
__init__(self: wpimath._wpimath.Pose2d) -> None
Constructs a pose at the origin facing toward the positive X axis.
__init__(self: wpimath._wpimath.Pose2d, translation: wpimath._wpimath.Translation2d, rotation: wpimath._wpimath.Rotation2d) -> 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.
__init__(self: wpimath._wpimath.Pose2d, x: wpimath.units.meters, y: wpimath.units.meters, rotation: wpimath._wpimath.Rotation2d) -> None
Constructs a pose with x and y translations instead of a separate Translation2d.
- Parameters:
x – The x component of the translational component of the pose.
y – The y component of the translational component of the pose.
rotation – The rotational component of the pose.
__init__(self: wpimath._wpimath.Pose2d, x: wpimath.units.meters, y: wpimath.units.meters, angle: wpimath.units.radians) -> None
- 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.
- static fromFeet(*args, **kwargs)
Overloaded function.
fromFeet(x: wpimath.units.feet, y: wpimath.units.feet, r: wpimath._wpimath.Rotation2d) -> wpimath._wpimath.Pose2d
fromFeet(x: wpimath.units.feet, y: wpimath.units.feet, angle: wpimath.units.radians) -> wpimath._wpimath.Pose2d
- static fromMatrix(matrix: Annotated[numpy.typing.ArrayLike, numpy.float64, '[3, 3]']) wpimath._wpimath.Pose2d
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.Pose2d]) wpimath._wpimath.Pose2d
Returns the nearest Pose2d 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 Pose2d from the collection.
- relativeTo(other: wpimath._wpimath.Pose2d) wpimath._wpimath.Pose2d
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.Translation2d, rot: wpimath._wpimath.Rotation2d) wpimath._wpimath.Pose2d
Rotates the current pose around a point in 2D space.
- Parameters:
point – The point in 2D space to rotate around.
rot – The rotation to rotate the pose by.
- Returns:
The new rotated pose.
- rotateBy(other: wpimath._wpimath.Rotation2d) wpimath._wpimath.Pose2d
Rotates the pose around the origin and returns the new pose.
- Parameters:
other – The rotation to transform the pose by.
- Returns:
The rotated pose.
- rotation() wpimath._wpimath.Rotation2d
Returns the underlying rotation.
- Returns:
Reference to the rotational component of the pose.
- toMatrix() Annotated[numpy.typing.NDArray[numpy.float64], '[3, 3]']
Returns an affine transformation matrix representation of this pose.
- transformBy(other: wpimath._wpimath.Transform2d) wpimath._wpimath.Pose2d
Transforms the pose by the given transformation and returns the new pose. See + operator for the matrix multiplication performed.
- Parameters:
other – The transform to transform the pose by.
- Returns:
The transformed pose.
- translation() wpimath._wpimath.Translation2d
Returns the underlying translation.
- Returns:
Reference to the translational component of the pose.
- property x
- property x_feet
- property y
- property y_feet