Class Transform3d

java.lang.Object
edu.wpi.first.math.geometry.Transform3d
All Implemented Interfaces:
ProtobufSerializable, StructSerializable, WPISerializable

public class Transform3d
extends Object
implements ProtobufSerializable, StructSerializable
Represents a transformation for a Pose3d in the pose's frame.
  • Field Details

  • Constructor Details

    • Transform3d

      public Transform3d​(Pose3d initial, Pose3d last)
      Constructs the transform that maps the initial pose to the final pose.
      Parameters:
      initial - The initial pose for the transformation.
      last - The final pose for the transformation.
    • Transform3d

      public Transform3d​(Translation3d translation, Rotation3d rotation)
      Constructs a transform with the given translation and rotation components.
      Parameters:
      translation - Translational component of the transform.
      rotation - Rotational component of the transform.
    • Transform3d

      public Transform3d​(double x, double y, double z, Rotation3d rotation)
      Constructs a transform with x, y, and z translations instead of a separate Translation3d.
      Parameters:
      x - The x component of the translational component of the transform.
      y - The y component of the translational component of the transform.
      z - The z component of the translational component of the transform.
      rotation - The rotational component of the transform.
    • Transform3d

      public Transform3d()
      Constructs the identity transform -- maps an initial pose to itself.
  • Method Details

    • times

      public Transform3d times​(double scalar)
      Multiplies the transform by the scalar.
      Parameters:
      scalar - The scalar.
      Returns:
      The scaled Transform3d.
    • div

      public Transform3d div​(double scalar)
      Divides the transform by the scalar.
      Parameters:
      scalar - The scalar.
      Returns:
      The scaled Transform3d.
    • plus

      public Transform3d plus​(Transform3d other)
      Composes two transformations. The second transform is applied relative to the orientation of the first.
      Parameters:
      other - The transform to compose with this one.
      Returns:
      The composition of the two transformations.
    • getTranslation

      Returns the translation component of the transformation.
      Returns:
      The translational component of the transform.
    • getX

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

      public double getY()
      Returns the Y component of the transformation's translation.
      Returns:
      The y component of the transformation's translation.
    • getZ

      public double getZ()
      Returns the Z component of the transformation's translation.
      Returns:
      The z component of the transformation's translation.
    • getRotation

      Returns the rotational component of the transformation.
      Returns:
      Reference to the rotational component of the transform.
    • inverse

      public Transform3d inverse()
      Invert the transformation. This is useful for undoing a transformation.
      Returns:
      The inverted transformation.
    • toString

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

      public boolean equals​(Object obj)
      Checks equality between this Transform3d 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