public class GeneralWaypoint extends Pose2d implements Waypoint
Waypoint
Constructor and Description |
---|
GeneralWaypoint()
Constructs a GeneralWaypoint.
|
GeneralWaypoint(double x,
double y) |
GeneralWaypoint(double x,
double y,
double movementSpeed,
double turnSpeed,
double followRadius)
Constructs a GeneralWaypoint with the provided values.
|
GeneralWaypoint(double x,
double y,
double rotationRadians,
double movementSpeed,
double turnSpeed,
double followRadius)
Constructs a GeneralWaypoint with the provided values.
|
GeneralWaypoint(Pose2d pose,
double movementSpeed,
double turnSpeed,
double followRadius)
Constructs a GeneralWaypoint with the provided values.
|
GeneralWaypoint(Translation2d translation,
Rotation2d rotation,
double movementSpeed,
double turnSpeed,
double followRadius)
Constructs a GeneralWaypoint with the provided values.
|
Modifier and Type | Method and Description |
---|---|
GeneralWaypoint |
disablePreferredAngle()
Disables this waypoint's preferredAngle.
|
double |
getFollowDistance()
Returns the follow distance for this waypoint.
|
double |
getFollowRadius()
Returns the follow radius of this waypoint.
|
double |
getMovementSpeed()
Returns the movement speed of this waypoint.
|
Pose2d |
getPose()
Returns this Waypoint's position.
|
double |
getPreferredAngle()
Returns this waypoint's preferred angle (in radians).
|
long |
getTimeout()
Returns the timeout period of this waypoint.
|
double |
getTurnSpeed()
Returns the turn speed of this waypoint.
|
WaypointType |
getType()
Returns this WayPoint's type.
|
void |
inherit(Waypoint waypoint)
Copies configuration from the given waypoint.
|
protected double |
normalizeSpeed(double raw)
Normalizes the given double to in the range [0, 1].
|
void |
reset()
Resets this waypoint.
|
GeneralWaypoint |
setFollowRadius(double followRadius)
Sets the follow radius of this waypoint.
|
GeneralWaypoint |
setMovementSpeed(double movementSpeed)
Sets the movement speed of this waypoint.
|
GeneralWaypoint |
setPreferredAngle(double angle)
Sets and enables this waypoint's preferred angle.
|
GeneralWaypoint |
setTimeout(long timeoutMiliseconds)
Sets the timeout period of this waypoint.
|
GeneralWaypoint |
setTurnSpeed(double turnSpeed)
Sets the turn speed of this waypoint.
|
java.lang.String |
toString() |
boolean |
usingPreferredAngle()
Returns true if this waypoint is using a preferred angle.
|
equals, exp, getHeading, getRotation, getTranslation, getX, getY, log, minus, plus, relativeTo, rotate, transformBy
public GeneralWaypoint()
public GeneralWaypoint(double x, double y)
public GeneralWaypoint(Translation2d translation, Rotation2d rotation, double movementSpeed, double turnSpeed, double followRadius)
translation
- The (x, y) translation of this waypoint.rotation
- The rotation (preferred angle) of this waypoint.movementSpeed
- The speed in which the robot moves at while traversing this waypoint, in the range [0, 1].turnSpeed
- The speed in which the robot turns at while traversing this waypoint, in the range [0, 1].followRadius
- The distance in which the robot traverses this waypoint. Please see guides to learn more about this value.public GeneralWaypoint(Pose2d pose, double movementSpeed, double turnSpeed, double followRadius)
pose
- Position and rotation (preferred angle) of this waypoint.movementSpeed
- The speed in which the robot moves at while traversing this waypoint, in the range [0, 1].turnSpeed
- The speed in which the robot turns at while traversing this waypoint, in the range [0, 1].followRadius
- The distance in which the robot traverses this waypoint. Please see guides to learn more about this value.public GeneralWaypoint(double x, double y, double movementSpeed, double turnSpeed, double followRadius)
x
- The x position of this waypoint.y
- The y position of this waypoint.movementSpeed
- The speed in which the robot moves at while traversing this waypoint, in the range [0, 1].turnSpeed
- The speed in which the robot turns at while traversing this waypoint, in the range [0, 1].followRadius
- The distance in which the robot traverses this waypoint. Please see guides to learn more about this value.public GeneralWaypoint(double x, double y, double rotationRadians, double movementSpeed, double turnSpeed, double followRadius)
x
- The x position of this waypoint.y
- The y position of this waypoint.rotationRadians
- The rotation (preferred angle) of this waypoint (in radians).movementSpeed
- The speed in which the robot moves at while traversing this waypoint, in the range [0, 1].turnSpeed
- The speed in which the robot turns at while traversing this waypoint, in the range [0, 1].followRadius
- The distance in which the robot traverses this waypoint. Please see guides to learn more about this value.public double getMovementSpeed()
public double getTurnSpeed()
public double getFollowRadius()
public double getPreferredAngle()
java.lang.IllegalStateException
- If this waypoint is not using a preferred angle.public boolean usingPreferredAngle()
public GeneralWaypoint setMovementSpeed(double movementSpeed)
movementSpeed
- Speed to set.public GeneralWaypoint setTurnSpeed(double turnSpeed)
turnSpeed
- Speed to be set.public GeneralWaypoint setFollowRadius(double followRadius)
followRadius
- Radius to be set.public GeneralWaypoint setPreferredAngle(double angle)
angle
- Angle to be set.public GeneralWaypoint setTimeout(long timeoutMiliseconds)
timeoutMiliseconds
- The timeout period of this waypoint.public GeneralWaypoint disablePreferredAngle()
public void reset()
protected double normalizeSpeed(double raw)
raw
- Value to be normalized.public void inherit(Waypoint waypoint)
waypoint
- Waypoint to copy.public WaypointType getType()
Waypoint
public Pose2d getPose()
Waypoint
public double getFollowDistance()
Waypoint
getFollowDistance
in interface Waypoint
public long getTimeout()
Waypoint
getTimeout
in interface Waypoint