Class 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 Controller
      PurePursuitController​(Path path, double lookaheadDistance, double lookaheadGain, double drivebaseWidth, double kMaxOutput, boolean followReverse)
      Create a PurePursuit Controller
    • Constructor Detail

      • PurePursuitController

        public PurePursuitController​(Path path,
                                     double lookaheadDistance,
                                     double lookaheadGain,
                                     double drivebaseWidth,
                                     double kMaxOutput)
        Create a PurePursuit Controller
        Parameters:
        path - Path to follow
        lookaheadDistance - How far to look ahead in meters
        lookaheadGain - Gain on lookahead (0.1 is usually a good val)
        drivebaseWidth - Drivebase width in meters
        kMaxOutput - 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 follow
        lookaheadDistance - How far to look ahead in meters
        lookaheadGain - Gain on lookahead (0.1 is usually a good val)
        drivebaseWidth - Drivebase width in meters
        kMaxOutput - Maximum output percent
        followReverse - 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 meters
        lookaheadGain - 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