Package com.pathplanner.lib.path
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 triggerstargetPosition
- The target field position in metersrotationOffset
- 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 degreesminPosition
- Starting waypoint relative position of the zonemaxPosition
- 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 Summary
ConstructorDescriptionPointTowardsZone
(String name, Translation2d targetPosition, double minWaypointRelativePos, double maxWaypointRelativePos) Create a new point towards zone without a rotation offsetPointTowardsZone
(String name, Translation2d targetPosition, Rotation2d rotationOffset, double minPosition, double maxPosition) Creates an instance of aPointTowardsZone
record class. -
Method Summary
Modifier and TypeMethodDescriptionfinal boolean
Indicates whether some other object is "equal to" this one.flip()
Flip this point towards zone to the other side of the field, maintaining a blue alliance originfinal int
hashCode()
Returns a hash code value for this object.double
Returns the value of themaxPosition
record component.double
Returns the value of theminPosition
record component.name()
Returns the value of thename
record component.Returns the value of therotationOffset
record component.Returns the value of thetargetPosition
record component.final String
toString()
Returns a string representation of this record class.
-
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 triggerstargetPosition
- The target field position in metersminWaypointRelativePos
- Starting position of the zonemaxWaypointRelativePos
- End position of the zone
-
PointTowardsZone
public PointTowardsZone(String name, Translation2d targetPosition, Rotation2d rotationOffset, double minPosition, double maxPosition) Creates an instance of aPointTowardsZone
record class.- Parameters:
name
- the value for thename
record componenttargetPosition
- the value for thetargetPosition
record componentrotationOffset
- the value for therotationOffset
record componentminPosition
- the value for theminPosition
record componentmaxPosition
- the value for themaxPosition
record component
-
-
Method Details
-
flip
Flip this point towards zone to the other side of the field, maintaining a blue alliance origin- Returns:
- The flipped zone
-
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. -
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. -
equals
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 withObjects::equals(Object,Object)
; primitive components are compared with '=='. -
name
Returns the value of thename
record component.- Returns:
- the value of the
name
record component
-
targetPosition
Returns the value of thetargetPosition
record component.- Returns:
- the value of the
targetPosition
record component
-
rotationOffset
Returns the value of therotationOffset
record component.- Returns:
- the value of the
rotationOffset
record component
-
minPosition
public double minPosition()Returns the value of theminPosition
record component.- Returns:
- the value of the
minPosition
record component
-
maxPosition
public double maxPosition()Returns the value of themaxPosition
record component.- Returns:
- the value of the
maxPosition
record component
-