Record Class Path.Waypoint

java.lang.Object
java.lang.Record
frc.robot.lib.BLine.Path.Waypoint
Record Components:
translationTarget - The position target for this waypoint
rotationTarget - The holonomic rotation target for this waypoint
All Implemented Interfaces:
Path.PathElement
Enclosing class:
Path

public static record Path.Waypoint(Path.TranslationTarget translationTarget, Path.RotationTarget rotationTarget) extends Record implements Path.PathElement
A waypoint that combines both a translation target and a rotation target.

Waypoints are the most common path element type, defining both where the robot should be and what holonomic rotation it should have at that location. The rotation target within a waypoint has its t_ratio automatically set based on position in the path.

Multiple constructors are provided for convenience:


 // From Pose2d
 new Waypoint(new Pose2d(1, 2, Rotation2d.fromDegrees(90)))
 
 // With custom handoff radius
 new Waypoint(new Pose2d(1, 2, rot), 0.3)
 
 // From individual components
 new Waypoint(new Translation2d(1, 2), Rotation2d.fromDegrees(90))
 
 // With profiled rotation disabled
 new Waypoint(pose, false)
 
  • Constructor Summary

    Constructors
    Constructor
    Description
    Waypoint(double x, double y, edu.wpi.first.math.geometry.Rotation2d rot)
    Creates a waypoint from x, y coordinates and a rotation.
    Waypoint(edu.wpi.first.math.geometry.Pose2d pose)
    Creates a waypoint from a Pose2d.
    Waypoint(edu.wpi.first.math.geometry.Pose2d pose, boolean profiledRotation)
    Creates a waypoint from a Pose2d with optional profiled rotation.
    Waypoint(edu.wpi.first.math.geometry.Pose2d pose, double handoffRadius)
    Creates a waypoint from a Pose2d with custom handoff radius.
    Waypoint(edu.wpi.first.math.geometry.Pose2d pose, double handoffRadius, boolean profiledRotation)
    Creates a waypoint from a Pose2d with custom handoff radius and rotation profiling.
    Waypoint(edu.wpi.first.math.geometry.Translation2d translation, double handoffRadius, edu.wpi.first.math.geometry.Rotation2d rotation)
    Creates a waypoint from a translation, handoff radius, and rotation.
    Waypoint(edu.wpi.first.math.geometry.Translation2d translation, double handoffRadius, edu.wpi.first.math.geometry.Rotation2d rotation, boolean profiledRotation)
    Creates a waypoint with optional profiled rotation control.
    Waypoint(edu.wpi.first.math.geometry.Translation2d translation, edu.wpi.first.math.geometry.Rotation2d rotation)
    Creates a waypoint from a translation and rotation using default handoff radius.
    Waypoint(edu.wpi.first.math.geometry.Translation2d translation, edu.wpi.first.math.geometry.Rotation2d rotation, boolean profiledRotation)
    Creates a waypoint with optional profiled rotation using default handoff radius.
    Waypoint(Path.TranslationTarget translationTarget, Path.RotationTarget rotationTarget)
    Creates an instance of a Waypoint record class.
  • Method Summary

    Modifier and Type
    Method
    Description
    Creates a deep copy of this waypoint.
    final boolean
    Indicates whether some other object is "equal to" this one.
    final int
    Returns a hash code value for this object.
    Returns the value of the rotationTarget record component.
    final String
    Returns a string representation of this record class.
    Returns the value of the translationTarget record component.

    Methods inherited from class java.lang.Object

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

    • Waypoint

      public Waypoint(edu.wpi.first.math.geometry.Translation2d translation, double handoffRadius, edu.wpi.first.math.geometry.Rotation2d rotation)
      Creates a waypoint from a translation, handoff radius, and rotation.
      Parameters:
      translation - The target position
      handoffRadius - The intermediate handoff radius in meters
      rotation - The target holonomic rotation
    • Waypoint

      public Waypoint(edu.wpi.first.math.geometry.Translation2d translation, double handoffRadius, edu.wpi.first.math.geometry.Rotation2d rotation, boolean profiledRotation)
      Creates a waypoint with optional profiled rotation control.
      Parameters:
      translation - The target position
      handoffRadius - The intermediate handoff radius in meters
      rotation - The target holonomic rotation
      profiledRotation - Whether to interpolate rotation along the path segment
    • Waypoint

      public Waypoint(edu.wpi.first.math.geometry.Translation2d translation, edu.wpi.first.math.geometry.Rotation2d rotation)
      Creates a waypoint from a translation and rotation using default handoff radius.
      Parameters:
      translation - The target position
      rotation - The target holonomic rotation
    • Waypoint

      public Waypoint(edu.wpi.first.math.geometry.Translation2d translation, edu.wpi.first.math.geometry.Rotation2d rotation, boolean profiledRotation)
      Creates a waypoint with optional profiled rotation using default handoff radius.
      Parameters:
      translation - The target position
      rotation - The target holonomic rotation
      profiledRotation - Whether to interpolate rotation along the path segment
    • Waypoint

      public Waypoint(edu.wpi.first.math.geometry.Pose2d pose)
      Creates a waypoint from a Pose2d.
      Parameters:
      pose - The pose containing position and rotation
    • Waypoint

      public Waypoint(edu.wpi.first.math.geometry.Pose2d pose, double handoffRadius)
      Creates a waypoint from a Pose2d with custom handoff radius.
      Parameters:
      pose - The pose containing position and rotation
      handoffRadius - The intermediate handoff radius in meters
    • Waypoint

      public Waypoint(edu.wpi.first.math.geometry.Pose2d pose, boolean profiledRotation)
      Creates a waypoint from a Pose2d with optional profiled rotation.
      Parameters:
      pose - The pose containing position and rotation
      profiledRotation - Whether to interpolate rotation along the path segment
    • Waypoint

      public Waypoint(edu.wpi.first.math.geometry.Pose2d pose, double handoffRadius, boolean profiledRotation)
      Creates a waypoint from a Pose2d with custom handoff radius and rotation profiling.
      Parameters:
      pose - The pose containing position and rotation
      handoffRadius - The intermediate handoff radius in meters
      profiledRotation - Whether to interpolate rotation along the path segment
    • Waypoint

      public Waypoint(double x, double y, edu.wpi.first.math.geometry.Rotation2d rot)
      Creates a waypoint from x, y coordinates and a rotation.
      Parameters:
      x - The x coordinate in meters
      y - The y coordinate in meters
      rot - The target holonomic rotation
    • Waypoint

      public Waypoint(Path.TranslationTarget translationTarget, Path.RotationTarget rotationTarget)
      Creates an instance of a Waypoint record class.
      Parameters:
      translationTarget - the value for the translationTarget record component
      rotationTarget - the value for the rotationTarget record component
  • Method Details

    • copy

      public Path.Waypoint copy()
      Creates a deep copy of this waypoint.
      Specified by:
      copy in interface Path.PathElement
      Returns:
      A new Waypoint with copied translation and rotation targets
    • toString

      public final String toString()
      Returns a string representation of this record class. The representation contains the name of the class, followed by the name and value of each of the record components.
      Specified by:
      toString in class Record
      Returns:
      a string representation of this object
    • hashCode

      public final int hashCode()
      Returns a hash code value for this object. The value is derived from the hash code of each of the record components.
      Specified by:
      hashCode in class Record
      Returns:
      a hash code value for this object
    • equals

      public final boolean equals(Object o)
      Indicates whether some other object is "equal to" this one. The objects are equal if the other object is of the same class and if all the record components are equal. All components in this record class are compared with Objects::equals(Object,Object).
      Specified by:
      equals in class Record
      Parameters:
      o - the object with which to compare
      Returns:
      true if this object is the same as the o argument; false otherwise.
    • translationTarget

      public Path.TranslationTarget translationTarget()
      Returns the value of the translationTarget record component.
      Returns:
      the value of the translationTarget record component
    • rotationTarget

      public Path.RotationTarget rotationTarget()
      Returns the value of the rotationTarget record component.
      Returns:
      the value of the rotationTarget record component