Class TrajectoryFollower
java.lang.Object
me.wobblyyyy.pathfinder.followers.TrajectoryFollower
- All Implemented Interfaces:
Follower
public class TrajectoryFollower extends java.lang.Object implements Follower
A lovely follower designed for trajectories. Normal followers, although
quite cool, aren't exactly as lovely as trajectory followers. Trajectories
are at least 25% more epic than normal lines.
- Since:
- 0.5.0
- Author:
- Colin Robertson
-
Field Summary
Fields Modifier and Type Field Description private Drive
drive
private boolean
hasFinished
private Odometry
odometry
private double
power
private Trajectory
trajectory
-
Constructor Summary
Constructors Constructor Description TrajectoryFollower(Trajectory trajectory, Odometry odometry, Drive drive, PathfinderConfig config)
-
Method Summary
Modifier and Type Method Description void
calculate()
Calculate a list of all the instructions needed to follow the path.void
drive()
Drive the robot itself.RTransform
getTransform(Point current, Point target, Angle angle)
Get a robot transformation based on current position, target position, and current angle.boolean
isDone()
Whether or not the follower has finished its execution.void
update()
Update the follower's drive values.Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Field Details
-
power
private final double power -
trajectory
-
odometry
-
drive
-
hasFinished
private boolean hasFinished
-
-
Constructor Details
-
TrajectoryFollower
public TrajectoryFollower(Trajectory trajectory, Odometry odometry, Drive drive, PathfinderConfig config)
-
-
Method Details
-
update
public void update()Description copied from interface:Follower
Update the follower's drive values. -
calculate
public void calculate()Description copied from interface:Follower
Calculate a list of all the instructions needed to follow the path.This should (needs to, really) be run before the robot makes any sort of movement in any direction - otherwise, you're defeating the whole purpose of having a pre-planned route.
-
getTransform
Get a robot transformation based on current position, target position, and current angle.- Parameters:
current
- the robot's current position.target
- the robot's target position.angle
- the angle the robot should face.- Returns:
- a new transformation based on the current and target points, as well as the provided angle.
-
drive
public void drive()Description copied from interface:Follower
Drive the robot itself.The drive method should almost always call another drive method, a drive method that's contained in a Drive class, actually. Driving the robot within the follower is a shitty idea, and you shouldn't do it.
-
isDone
public boolean isDone()Description copied from interface:Follower
Whether or not the follower has finished its execution.
-