public class PathFollower
Generic class Path
follower for time-independent pose reference tracking.
class Path
Modifier and Type | Field and Description |
---|---|
protected Path |
path
Path being followed if
isFollowing is true. |
Constructor and Description |
---|
PathFollower(Pose2d admissibleError,
NanoClock clock)
Generic
class Path follower for time-independent pose reference tracking. |
PathFollower(Pose2d admissibleError)
Generic
class Path follower for time-independent pose reference tracking. |
Modifier and Type | Method and Description |
---|---|
void |
followPath(Path path)
Follow the given
path . |
protected NanoClock |
getClock()
clock
|
Pose2d |
getLastError()
Robot pose error computed in the last
update call. |
Path |
getPath()
Path being followed if
isFollowing is true. |
protected DriveSignal |
internalUpdate(Pose2d currentPose) |
boolean |
isFollowing()
Returns true if the current path has finished executing.
|
protected void |
setLastError(Pose2d p)
Robot pose error computed in the last
update call. |
protected void |
setPath(Path p)
Path being followed if
isFollowing is true. |
DriveSignal |
update(Pose2d currentPose)
Run a single iteration of the path follower.
|
@NotNull protected Path path
Path being followed if isFollowing
is true.
isFollowing
@JvmOverloads public PathFollower(@NotNull Pose2d admissibleError, @NotNull NanoClock clock)
Generic class Path
follower for time-independent pose reference tracking.
clock
- clockclass Path
@JvmOverloads public PathFollower(@NotNull Pose2d admissibleError)
Generic class Path
follower for time-independent pose reference tracking.
class Path
@NotNull public Path getPath()
Path being followed if isFollowing
is true.
isFollowing
protected void setPath(@NotNull Path p)
Path being followed if isFollowing
is true.
isFollowing
@NotNull public Pose2d getLastError()
Robot pose error computed in the last update
call.
update
protected void setLastError(@NotNull Pose2d p)
Robot pose error computed in the last update
call.
update
public void followPath(@NotNull Path path)
Follow the given path
.
path
- pathpath
public boolean isFollowing()
Returns true if the current path has finished executing.
@NotNull public DriveSignal update(@NotNull Pose2d currentPose)
Run a single iteration of the path follower.
currentPose
- current robot pose@NotNull protected DriveSignal internalUpdate(@NotNull Pose2d currentPose)
@NotNull protected NanoClock getClock()
clock