Package com.pathplanner.lib.path
Record Class RotationTarget
java.lang.Object
java.lang.Record
com.pathplanner.lib.path.RotationTarget
- Record Components:
position- Waypoint relative position of this targetrotation- Target rotation
A target holonomic rotation at a position along a path
-
Constructor Summary
ConstructorsConstructorDescriptionRotationTarget(double position, Rotation2d rotation) Creates an instance of aRotationTargetrecord class. -
Method Summary
Modifier and TypeMethodDescriptionfinal booleanIndicates whether some other object is "equal to" this one.flip()Flip a rotation target for the other side of the field, maintaining a blue alliance originfinal inthashCode()Returns a hash code value for this object.doubleposition()Returns the value of thepositionrecord component.rotation()Returns the value of therotationrecord component.final StringtoString()Returns a string representation of this record class.
-
Constructor Details
-
Method Details
-
flip
Flip a rotation target for the other side of the field, maintaining a blue alliance origin- Returns:
- The flipped rotation target
-
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 '=='. -
position
public double position()Returns the value of thepositionrecord component.- Returns:
- the value of the
positionrecord component
-
rotation
Returns the value of therotationrecord component.- Returns:
- the value of the
rotationrecord component
-