Translation3d
- class wpimath.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._wpimath.Translation3d) -> None
Constructs a Translation3d with X, Y, and Z components equal to zero.
__init__(self: wpimath._wpimath.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._wpimath.Translation3d, distance: wpimath.units.meters, angle: wpimath._wpimath.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._wpimath.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._wpimath.Translation3d, translation: wpimath._wpimath.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 X 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.
- cross(other: wpimath._wpimath.Translation3d) Annotated[numpy.typing.NDArray[wpimath.units.square_meters], '[3, 1]']
Computes the cross product between this translation and another translation in 3D space. The resulting translation will be perpendicular to both translations.
The 3D cross product between two translations is defined as <y₁z₂-y₂z₁, z₁x₂-z₂x₁, x₁y₂-x₂y₁>.
- Parameters:
other – The translation to compute the cross product with.
- Returns:
The cross product between the two translations.
- distance(other: wpimath._wpimath.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._wpimath.Translation3d) wpimath.units.feet
- dot(other: wpimath._wpimath.Translation3d) wpimath.units.square_meters
Computes the dot product between this translation and another translation in 3D space.
The dot product between two translations is defined as x₁x₂+y₁y₂+z₁z₂.
- Parameters:
other – The translation to compute the dot product with.
- Returns:
The dot product between the two translations.
- static fromFeet(x: wpimath.units.feet, y: wpimath.units.feet, z: wpimath.units.feet) wpimath._wpimath.Translation3d
- nearest(translations: List[wpimath._wpimath.Translation3d]) wpimath._wpimath.Translation3d
Returns the nearest Translation3d from a collection of translations
- Parameters:
translations – The collection of translations.
- Returns:
The nearest Translation3d from the collection.
- 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._wpimath.Translation3d, rot: wpimath._wpimath.Rotation3d) wpimath._wpimath.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._wpimath.Rotation3d) wpimath._wpimath.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.
- squaredDistance(other: wpimath._wpimath.Translation3d) wpimath.units.square_meters
Calculates the squared distance between two translations in 3D space. This is equivalent to squaring the result of Distance(Translation3d), but avoids computing a square root.
The squared distance between translations is defined as (x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)².
- Parameters:
other – The translation to compute the squared distance to.
- Returns:
The squared distance between the two translations.
- squaredNorm() wpimath.units.square_meters
Returns the squared norm, or squared distance from the origin to the translation. This is equivalent to squaring the result of Norm(), but avoids computing a square root.
- Returns:
The squared norm of the translation.
- toTranslation2d() wpimath._wpimath.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