Record Class PointTowardsZone

java.lang.Object
java.lang.Record
com.pathplanner.lib.path.PointTowardsZone
Record Components:
name - The name of this zone. Used for point towards zone triggers
targetPosition - The target field position in meters
rotationOffset - A rotation offset to add on top of the angle to the target position. For example, if you want the robot to point away from the target position, use a rotation offset of 180 degrees
minPosition - Starting waypoint relative position of the zone
maxPosition - End waypoint relative position of the zone

public record PointTowardsZone(String name, Translation2d targetPosition, Rotation2d rotationOffset, double minPosition, double maxPosition) extends Record
A zone on a path that will force the robot to point towards a position on the field
  • Constructor Details

    • PointTowardsZone

      public PointTowardsZone(String name, Translation2d targetPosition, double minWaypointRelativePos, double maxWaypointRelativePos)
      Create a new point towards zone without a rotation offset
      Parameters:
      name - The name of this zone. Used for point towards zone triggers
      targetPosition - The target field position in meters
      minWaypointRelativePos - Starting position of the zone
      maxWaypointRelativePos - End position of the zone
    • PointTowardsZone

      public PointTowardsZone(String name, Translation2d targetPosition, Rotation2d rotationOffset, double minPosition, double maxPosition)
      Creates an instance of a PointTowardsZone record class.
      Parameters:
      name - the value for the name record component
      targetPosition - the value for the targetPosition record component
      rotationOffset - the value for the rotationOffset record component
      minPosition - the value for the minPosition record component
      maxPosition - the value for the maxPosition record component
  • Method Details

    • flip

      public PointTowardsZone flip()
      Flip this point towards zone to the other side of the field, maintaining a blue alliance origin
      Returns:
      The flipped zone
    • 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. Reference components are compared with Objects::equals(Object,Object); primitive components are compared with '=='.
      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.
    • name

      public String name()
      Returns the value of the name record component.
      Returns:
      the value of the name record component
    • targetPosition

      public Translation2d targetPosition()
      Returns the value of the targetPosition record component.
      Returns:
      the value of the targetPosition record component
    • rotationOffset

      public Rotation2d rotationOffset()
      Returns the value of the rotationOffset record component.
      Returns:
      the value of the rotationOffset record component
    • minPosition

      public double minPosition()
      Returns the value of the minPosition record component.
      Returns:
      the value of the minPosition record component
    • maxPosition

      public double maxPosition()
      Returns the value of the maxPosition record component.
      Returns:
      the value of the maxPosition record component