Translation2d
- class wpimath.geometry.Translation2d(*args, **kwargs)
Bases:
pybind11_object
Represents 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.geometry._geometry.Translation2d) -> None
Constructs a Translation2d with X and Y components equal to zero.
__init__(self: wpimath.geometry._geometry.Translation2d, x: meters, y: 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.geometry._geometry.Translation2d, distance: meters, angle: wpimath.geometry._geometry.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.
- X() meters
Returns the X component of the translation.
- Returns:
The X component of the translation.
- Y() meters
Returns the Y component of the translation.
- Returns:
The Y component of the translation.
- angle() wpimath.geometry._geometry.Rotation2d
Returns the angle this translation forms with the positive X axis.
- Returns:
The angle of the translation
- distance(other: wpimath.geometry._geometry.Translation2d) 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.geometry._geometry.Translation2d) feet
- static fromFeet(x: feet, y: feet) wpimath.geometry._geometry.Translation2d
- nearest(translations: List[wpimath.geometry._geometry.Translation2d]) wpimath.geometry._geometry.Translation2d
Returns the nearest Translation2d from a collection of translations
- Parameters:
translations – The collection of translations.
- Returns:
The nearest Translation2d from the collection.
- norm() meters
Returns the norm, or distance from the origin to the translation.
- Returns:
The norm of the translation.
- normFeet() feet
- rotateBy(other: wpimath.geometry._geometry.Rotation2d) wpimath.geometry._geometry.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.
- property x
- property x_feet
- property y
- property y_feet