Package io.github.frc5024.purepursuit
Class PurePursuitController
- java.lang.Object
-
- io.github.frc5024.purepursuit.PurePursuitController
-
public class PurePursuitController extends java.lang.Object
A pure pursuit controller implementation
-
-
Constructor Summary
Constructors Constructor Description PurePursuitController(Path path, double lookaheadDistance, double lookaheadGain, double drivebaseWidth, double kMaxOutput)
Create a PurePursuit ControllerPurePursuitController(Path path, double lookaheadDistance, double lookaheadGain, double drivebaseWidth, double kMaxOutput, boolean followReverse)
Create a PurePursuit Controller
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description Translation2d
calculateHolonomic(Pose2d robotPose)
Calculate outputs for a holonomic drivebaseDifferentialDriveWheelSpeeds
calculateTank(Pose2d robotPose)
Calculate ou tputs for a tank drivebasevoid
configLookahead(double lookaheadDistance)
Set the lookahead distancevoid
configLookahead(double lookaheadDistance, double lookaheadGain)
Set the lookahead distance and gainvoid
reset()
Reset the controller
-
-
-
Constructor Detail
-
PurePursuitController
public PurePursuitController(Path path, double lookaheadDistance, double lookaheadGain, double drivebaseWidth, double kMaxOutput)
Create a PurePursuit Controller- Parameters:
path
- Path to followlookaheadDistance
- How far to look ahead in meterslookaheadGain
- Gain on lookahead (0.1 is usually a good val)drivebaseWidth
- Drivebase width in meterskMaxOutput
- Maximum output percent
-
PurePursuitController
public PurePursuitController(Path path, double lookaheadDistance, double lookaheadGain, double drivebaseWidth, double kMaxOutput, boolean followReverse)
Create a PurePursuit Controller- Parameters:
path
- Path to followlookaheadDistance
- How far to look ahead in meterslookaheadGain
- Gain on lookahead (0.1 is usually a good val)drivebaseWidth
- Drivebase width in meterskMaxOutput
- Maximum output percentfollowReverse
- Should the path be followed with the back of the chassis?
-
-
Method Detail
-
reset
public void reset()
Reset the controller
-
configLookahead
public void configLookahead(double lookaheadDistance)
Set the lookahead distance- Parameters:
lookaheadDistance
- How far to look ahead in meters
-
configLookahead
public void configLookahead(double lookaheadDistance, double lookaheadGain)
Set the lookahead distance and gain- Parameters:
lookaheadDistance
- How far to look ahead in meterslookaheadGain
- Gain on lookahead (0.1 is usually a good val)
-
calculateTank
public DifferentialDriveWheelSpeeds calculateTank(Pose2d robotPose)
Calculate ou tputs for a tank drivebase- Parameters:
robotPose
- Robot's pose- Returns:
- Output velocity percentages
-
calculateHolonomic
public Translation2d calculateHolonomic(Pose2d robotPose)
Calculate outputs for a holonomic drivebase- Parameters:
robotPose
- Robot's pose- Returns:
- Vector facing in the desired direction of travel, with magnitude matching the desired speed
-
-