Translation3d
- class wpimath.geometry.Translation3d(*args, **kwargs)
Bases:
pybind11_objectRepresents a translation in 3D space. This object can be used to represent a point or a vector.
This assumes that you are using conventional mathematical axes. When the robot is at the origin facing in the positive X direction, forward is positive X, left is positive Y, and up is positive Z.
Overloaded function.
__init__(self: wpimath.geometry._geometry.Translation3d) -> None
Constructs a Translation3d with X, Y, and Z components equal to zero.
__init__(self: wpimath.geometry._geometry.Translation3d, x: wpimath.units.meters, y: wpimath.units.meters, z: wpimath.units.meters) -> None
Constructs a Translation3d with the X, Y, and Z components equal to the provided values.
- Parameters:
x – The x component of the translation.
y – The y component of the translation.
z – The z component of the translation.
__init__(self: wpimath.geometry._geometry.Translation3d, distance: wpimath.units.meters, angle: wpimath.geometry._geometry.Rotation3d) -> None
Constructs a Translation3d with the provided distance and angle. This is essentially converting from polar coordinates to Cartesian coordinates.
- Parameters:
distance – The distance from the origin to the end of the translation.
angle – The angle between the x-axis and the translation vector.
__init__(self: wpimath.geometry._geometry.Translation3d, vector: typing.Annotated[numpy.typing.ArrayLike, numpy.float64, “[3, 1]”]) -> None
Constructs a Translation3d from a 3D translation vector. The values are assumed to be in meters.
- Parameters:
vector – The translation vector.
__init__(self: wpimath.geometry._geometry.Translation3d, translation: wpimath.geometry._geometry.Translation2d) -> None
Constructs a 3D translation from a 2D translation in the X-Y plane.
- Parameters:
translation – The 2D translation. @see Pose3d(Pose2d) @see Transform3d(Transform2d)
- WPIStruct = <capsule object "WPyStruct">
- X() wpimath.units.meters
Returns the X component of the translation.
- Returns:
The Z component of the translation.
- Y() wpimath.units.meters
Returns the Y component of the translation.
- Returns:
The Y component of the translation.
- Z() wpimath.units.meters
Returns the Z component of the translation.
- Returns:
The Z component of the translation.
- distance(other: wpimath.geometry._geometry.Translation3d) wpimath.units.meters
Calculates the distance between two translations in 3D space.
The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)²).
- Parameters:
other – The translation to compute the distance to.
- Returns:
The distance between the two translations.
- distanceFeet(arg0: wpimath.geometry._geometry.Translation3d) wpimath.units.feet
- static fromFeet(x: wpimath.units.feet, y: wpimath.units.feet, z: wpimath.units.feet) wpimath.geometry._geometry.Translation3d
- norm() wpimath.units.meters
Returns the norm, or distance from the origin to the translation.
- Returns:
The norm of the translation.
- normFeet() wpimath.units.feet
- rotateAround(other: wpimath.geometry._geometry.Translation3d, rot: wpimath.geometry._geometry.Rotation3d) wpimath.geometry._geometry.Translation3d
Rotates this translation around another translation in 3D space.
- Parameters:
other – The other translation to rotate around.
rot – The rotation to rotate the translation by.
- Returns:
The new rotated translation.
- rotateBy(other: wpimath.geometry._geometry.Rotation3d) wpimath.geometry._geometry.Translation3d
Applies a rotation to the translation in 3D space.
For example, rotating a Translation3d of <2, 0, 0> by 90 degrees around the Z axis will return a Translation3d of <0, 2, 0>.
- Parameters:
other – The rotation to rotate the translation by.
- Returns:
The new rotated translation.
- toTranslation2d() wpimath.geometry._geometry.Translation2d
Returns a Translation2d representing this Translation3d projected into the X-Y plane.
- toVector() Annotated[numpy.typing.NDArray[numpy.float64], '[3, 1]']
Returns a 3D translation vector representation of this translation.
- Returns:
A 3D translation vector representation of this translation.
- property x
- property x_feet
- property y
- property y_feet
- property z
- property z_feet