Package frc.robot.lib.BLine
Record Class Path.TranslationTarget
java.lang.Object
java.lang.Record
frc.robot.lib.BLine.Path.TranslationTarget
- Record Components:
translation- The target position in field coordinatesintermediateHandoffRadiusMeters- Optional radius at which to switch to the next target. If empty, the global default is used.
- All Implemented Interfaces:
Path.PathElement
- Enclosing class:
- Path
public static record Path.TranslationTarget(edu.wpi.first.math.geometry.Translation2d translation, Optional<Double> intermediateHandoffRadiusMeters)
extends Record
implements Path.PathElement
A translation target defining a position the robot should drive through.
Translation targets form the "backbone" of a path. The robot will drive through each translation target in sequence. An optional intermediate handoff radius determines when the path follower switches to the next target.
-
Constructor Summary
ConstructorsConstructorDescriptionTranslationTarget(double x, double y) Creates a translation target from x, y coordinates using default handoff radius.TranslationTarget(double x, double y, double handoffRadius) Creates a translation target from x, y coordinates with custom handoff radius.TranslationTarget(edu.wpi.first.math.geometry.Translation2d translation) Creates a translation target using the default handoff radius.TranslationTarget(edu.wpi.first.math.geometry.Translation2d translation, Optional<Double> intermediateHandoffRadiusMeters) Creates an instance of aTranslationTargetrecord class. -
Method Summary
Modifier and TypeMethodDescriptioncopy()Creates a copy of this translation target.final booleanIndicates whether some other object is "equal to" this one.final inthashCode()Returns a hash code value for this object.Returns the value of theintermediateHandoffRadiusMetersrecord component.final StringtoString()Returns a string representation of this record class.edu.wpi.first.math.geometry.Translation2dReturns the value of thetranslationrecord component.
-
Constructor Details
-
TranslationTarget
public TranslationTarget(edu.wpi.first.math.geometry.Translation2d translation) Creates a translation target using the default handoff radius.- Parameters:
translation- The target position
-
TranslationTarget
public TranslationTarget(double x, double y) Creates a translation target from x, y coordinates using default handoff radius.- Parameters:
x- The x coordinate in metersy- The y coordinate in meters
-
TranslationTarget
public TranslationTarget(double x, double y, double handoffRadius) Creates a translation target from x, y coordinates with custom handoff radius.- Parameters:
x- The x coordinate in metersy- The y coordinate in metershandoffRadius- The intermediate handoff radius in meters
-
TranslationTarget
public TranslationTarget(edu.wpi.first.math.geometry.Translation2d translation, Optional<Double> intermediateHandoffRadiusMeters) Creates an instance of aTranslationTargetrecord class.- Parameters:
translation- the value for thetranslationrecord componentintermediateHandoffRadiusMeters- the value for theintermediateHandoffRadiusMetersrecord component
-
-
Method Details
-
copy
Creates a copy of this translation target.- Specified by:
copyin interfacePath.PathElement- Returns:
- A new TranslationTarget with the same values
-
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. All components in this record class are compared withObjects::equals(Object,Object). -
translation
public edu.wpi.first.math.geometry.Translation2d translation()Returns the value of thetranslationrecord component.- Returns:
- the value of the
translationrecord component
-
intermediateHandoffRadiusMeters
Returns the value of theintermediateHandoffRadiusMetersrecord component.- Returns:
- the value of the
intermediateHandoffRadiusMetersrecord component
-