Class Translation2d

java.lang.Object
edu.wpi.first.wpilibj.geometry.Translation2d

public class Translation2d
extends 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 placed on the origin, facing toward the X direction, moving forward increases the X, whereas moving to the left increases the Y.

  • Constructor Summary

    Constructors 
    Constructor Description
    Translation2d()
    Constructs a Translation2d with X and Y components equal to zero.
    Translation2d​(double x, double y)
    Constructs a Translation2d with the X and Y components equal to the provided values.
    Translation2d​(double distance, Rotation2d angle)
    Constructs a Translation2d with the provided distance and angle.
  • Method Summary

    Modifier and Type Method Description
    Translation2d div​(double scalar)
    Divides the translation by a scalar and returns the new translation.
    boolean equals​(Object obj)
    Checks equality between this Translation2d and another object.
    double getDistance​(Translation2d other)
    Calculates the distance between two translations in 2d space.
    double getNorm()
    Returns the norm, or distance from the origin to the translation.
    double getX()
    Returns the X component of the translation.
    double getY()
    Returns the Y component of the translation.
    int hashCode()  
    Translation2d minus​(Translation2d other)
    Subtracts the other translation from the other translation and returns the difference.
    Translation2d plus​(Translation2d other)
    Adds two translations in 2d space and returns the sum.
    Translation2d rotateBy​(Rotation2d other)
    Applies a rotation to the translation in 2d space.
    Translation2d times​(double scalar)
    Multiplies the translation by a scalar and returns the new translation.
    String toString()  
    Translation2d unaryMinus()
    Returns the inverse of the current translation.

    Methods inherited from class java.lang.Object

    clone, finalize, getClass, notify, notifyAll, wait, wait, wait
  • Constructor Details

    • Translation2d

      public Translation2d()
      Constructs a Translation2d with X and Y components equal to zero.
    • Translation2d

      public Translation2d​(double x, double y)
      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.
    • Translation2d

      public Translation2d​(double distance, Rotation2d angle)
      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.
  • Method Details

    • getDistance

      public double getDistance​(Translation2d other)
      Calculates the distance between two translations in 2d space.

      This function uses the pythagorean theorem to calculate the distance. distance = sqrt((x2 - x1)^2 + (y2 - y1)^2)

      Parameters:
      other - The translation to compute the distance to.
      Returns:
      The distance between the two translations.
    • getX

      public double getX()
      Returns the X component of the translation.
      Returns:
      The x component of the translation.
    • getY

      public double getY()
      Returns the Y component of the translation.
      Returns:
      The y component of the translation.
    • getNorm

      public double getNorm()
      Returns the norm, or distance from the origin to the translation.
      Returns:
      The norm of the translation.
    • rotateBy

      public Translation2d rotateBy​(Rotation2d other)
      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.
    • plus

      public Translation2d plus​(Translation2d other)
      Adds two translations in 2d space and returns the sum. This is similar to vector addition.

      For example, Translation2d{1.0, 2.5} + Translation2d{2.0, 5.5} = Translation2d{3.0, 8.0}

      Parameters:
      other - The translation to add.
      Returns:
      The sum of the translations.
    • minus

      public Translation2d minus​(Translation2d other)
      Subtracts the other translation from the other translation and returns the difference.

      For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} = Translation2d{4.0, 2.0}

      Parameters:
      other - The translation to subtract.
      Returns:
      The difference between the two translations.
    • unaryMinus

      public Translation2d unaryMinus()
      Returns the inverse of the current translation. This is equivalent to rotating by 180 degrees, flipping the point over both axes, or simply negating both components of the translation.
      Returns:
      The inverse of the current translation.
    • times

      public Translation2d times​(double scalar)
      Multiplies the translation by a scalar and returns the new translation.

      For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}

      Parameters:
      scalar - The scalar to multiply by.
      Returns:
      The scaled translation.
    • div

      public Translation2d div​(double scalar)
      Divides the translation by a scalar and returns the new translation.

      For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}

      Parameters:
      scalar - The scalar to multiply by.
      Returns:
      The reference to the new mutated object.
    • toString

      public String toString()
      Overrides:
      toString in class Object
    • equals

      public boolean equals​(Object obj)
      Checks equality between this Translation2d and another object.
      Overrides:
      equals in class Object
      Parameters:
      obj - The other object.
      Returns:
      Whether the two objects are equal or not.
    • hashCode

      public int hashCode()
      Overrides:
      hashCode in class Object