Class Translation3d

java.lang.Object
edu.wpi.first.math.geometry.Translation3d
All Implemented Interfaces:
Interpolatable<Translation3d>

public class Translation3d
extends Object
implements Interpolatable<Translation3d>
Represents 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.

  • Constructor Details

    • Translation3d

      public Translation3d()
      Constructs a Translation3d with X, Y, and Z components equal to zero.
    • Translation3d

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

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

    • getDistance

      public double getDistance​(Translation3d other)
      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.
    • 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.
    • getZ

      public double getZ()
      Returns the Z component of the translation.
      Returns:
      The Z 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 Translation3d rotateBy​(Rotation3d other)
      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

      Returns a Translation2d representing this Translation3d projected into the X-Y plane.
      Returns:
      A Translation2d representing this Translation3d projected into the X-Y plane.
    • plus

      public Translation3d plus​(Translation3d other)
      Returns the sum of two translations in 3D space.

      For example, Translation3d(1.0, 2.5, 3.5) + Translation3d(2.0, 5.5, 7.5) = Translation3d{3.0, 8.0, 11.0).

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

      public Translation3d minus​(Translation3d other)
      Returns the difference between two translations.

      For example, Translation3d(5.0, 4.0, 3.0) - Translation3d(1.0, 2.0, 3.0) = Translation3d(4.0, 2.0, 0.0).

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

      Returns the inverse of the current translation. This is equivalent to negating all components of the translation.
      Returns:
      The inverse of the current translation.
    • times

      public Translation3d times​(double scalar)
      Returns the translation multiplied by a scalar.

      For example, Translation3d(2.0, 2.5, 4.5) * 2 = Translation3d(4.0, 5.0, 9.0).

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

      public Translation3d div​(double scalar)
      Returns the translation divided by a scalar.

      For example, Translation3d(2.0, 2.5, 4.5) / 2 = Translation3d(1.0, 1.25, 2.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 Translation3d 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
    • interpolate

      public Translation3d interpolate​(Translation3d endValue, double t)
      Description copied from interface: Interpolatable
      Return the interpolated value. This object is assumed to be the starting position, or lower bound.
      Specified by:
      interpolate in interface Interpolatable<Translation3d>
      Parameters:
      endValue - The upper bound, or end.
      t - How far between the lower and upper bound we are. This should be bounded in [0, 1].
      Returns:
      The interpolated value.