Translation2d
- class wpimath.Translation2d(*args, **kwargs)
Bases:
pybind11_objectRepresents a translation in 2D 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 and left is positive Y.
Overloaded function.
__init__(self: wpimath._wpimath.Translation2d) -> None
Constructs a Translation2d with X and Y components equal to zero.
__init__(self: wpimath._wpimath.Translation2d, x: wpimath.units.meters, y: wpimath.units.meters) -> None
Constructs a Translation2d with the X and Y components equal to the provided values.
- Parameters:
x – The x component of the translation.
y – The y component of the translation.
__init__(self: wpimath._wpimath.Translation2d, distance: wpimath.units.meters, angle: wpimath._wpimath.Rotation2d) -> None
Constructs a Translation2d 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.Translation2d, vector: typing.Annotated[numpy.typing.ArrayLike, numpy.float64, “[2, 1]”]) -> None
Constructs a Translation2d from a 2D translation vector. The values are assumed to be in meters.
- Parameters:
vector – The translation vector.
- 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.
- angle() wpimath._wpimath.Rotation2d
Returns the angle this translation forms with the positive X axis.
- Returns:
The angle of the translation
- cross(other: wpimath._wpimath.Translation2d) wpimath.units.square_meters
Computes the cross product between this translation and another translation in 2D space.
The 2D cross product between two translations is defined as 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.Translation2d) wpimath.units.meters
Calculates the distance between two translations in 2D space.
The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²).
- Parameters:
other – The translation to compute the distance to.
- Returns:
The distance between the two translations.
- distanceFeet(arg0: wpimath._wpimath.Translation2d) wpimath.units.feet
- dot(other: wpimath._wpimath.Translation2d) wpimath.units.square_meters
Computes the dot product between this translation and another translation in 2D space.
The dot product between two translations is defined as x₁x₂+y₁y₂.
- Parameters:
other – The translation to compute the dot product with.
- Returns:
The dot product between the two translations.
- static fromFeet(*args, **kwargs)
Overloaded function.
fromFeet(x: wpimath.units.feet, y: wpimath.units.feet) -> wpimath._wpimath.Translation2d
fromFeet(distance: wpimath.units.feet, angle: wpimath._wpimath.Rotation2d) -> wpimath._wpimath.Translation2d
- nearest(translations: List[wpimath._wpimath.Translation2d]) wpimath._wpimath.Translation2d
Returns the nearest Translation2d from a collection of translations
- Parameters:
translations – The collection of translations.
- Returns:
The nearest Translation2d 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.Translation2d, rot: wpimath._wpimath.Rotation2d) wpimath._wpimath.Translation2d
Rotates this translation around another translation in 2D space.
[x_new] [rot.cos, -rot.sin][x - other.x] [other.x] [y_new] = [rot.sin, rot.cos][y - other.y] + [other.y]
- 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.Rotation2d) wpimath._wpimath.Translation2d
Applies a rotation to the translation in 2D space.
This multiplies the translation vector by a counterclockwise rotation matrix of the given angle.
[x_new] [other.cos, -other.sin][x] [y_new] = [other.sin, other.cos][y]
For example, rotating a Translation2d of <2, 0> by 90 degrees will return a Translation2d of <0, 2>.
- Parameters:
other – The rotation to rotate the translation by.
- Returns:
The new rotated translation.
- squaredDistance(other: wpimath._wpimath.Translation2d) wpimath.units.square_meters
Calculates the square of the distance between two translations in 2D space. This is equivalent to squaring the result of Distance(Translation2d), but avoids computing a square root.
The square of the distance between translations is defined as (x₂−x₁)²+(y₂−y₁)².
- Parameters:
other – The translation to compute the squared distance to.
- Returns:
The square of the 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.
- toVector() Annotated[numpy.typing.NDArray[numpy.float64], '[2, 1]']
Returns a 2D translation vector representation of this translation.
- Returns:
A 2D translation vector representation of this translation.
- property x
- property x_feet
- property y
- property y_feet