Package frc.robot.lib.BLine
Record Class Path.Waypoint
java.lang.Object
java.lang.Record
frc.robot.lib.BLine.Path.Waypoint
- Record Components:
translationTarget- The position target for this waypointrotationTarget- 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
ConstructorsConstructorDescriptionWaypoint(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 aWaypointrecord class. -
Method Summary
Modifier and TypeMethodDescriptioncopy()Creates a deep copy of this waypoint.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 therotationTargetrecord component.final StringtoString()Returns a string representation of this record class.Returns the value of thetranslationTargetrecord component.
-
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 positionhandoffRadius- The intermediate handoff radius in metersrotation- 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 positionhandoffRadius- The intermediate handoff radius in metersrotation- The target holonomic rotationprofiledRotation- 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 positionrotation- 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 positionrotation- The target holonomic rotationprofiledRotation- 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 rotationhandoffRadius- 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 rotationprofiledRotation- 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 rotationhandoffRadius- The intermediate handoff radius in metersprofiledRotation- 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 metersy- The y coordinate in metersrot- The target holonomic rotation
-
Waypoint
Creates an instance of aWaypointrecord class.- Parameters:
translationTarget- the value for thetranslationTargetrecord componentrotationTarget- the value for therotationTargetrecord component
-
-
Method Details
-
copy
Creates a deep copy of this waypoint.- Specified by:
copyin interfacePath.PathElement- Returns:
- A new Waypoint with copied translation and rotation targets
-
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). -
translationTarget
Returns the value of thetranslationTargetrecord component.- Returns:
- the value of the
translationTargetrecord component
-
rotationTarget
Returns the value of therotationTargetrecord component.- Returns:
- the value of the
rotationTargetrecord component
-