Class Follower


  • public class Follower
    extends java.lang.Object
    A lookahead finder for finding new points in a 2D path.

    This is a Java implementation of https://github.com/AtsushiSakai/PythonRobotics/blob/9274aacefb8fb52feac544fc26d075046f703afd/PathTracking/pure_pursuit/pure_pursuit.py#L77-L10
    • Field Detail

      • m_path

        public Path m_path
    • Constructor Detail

      • Follower

        public Follower​(Path path,
                        double lookaheadDistance,
                        double lookaheadGain,
                        double drivebaseWidth)
        Create a path follower
        Parameters:
        path - Path to follow
        lookaheadDistance - Lookahead distance
        lookaheadGain - The minimum distance required to fetch a new pose
        drivebaseWidth - Drivebase width
    • Method Detail

      • setLookaheadDistance

        public void setLookaheadDistance​(double distance)
        Set the lookahead distance
        Parameters:
        distance - Distance to look ahead for a new goal pose
      • getLookaheadDistance

        public double getLookaheadDistance()
        Get the current lookahead distance
        Returns:
        Distance to goal pose look radius
      • setLookaheadGain

        public void setLookaheadGain​(double gain)
        Set the max area around the lookahead to accept pose deviation. Generally leave this as 0.1
        Parameters:
        gain - Check area
      • getLookaheadGain

        public double getLookaheadGain()
        Get the lookahead gain
        Returns:
        Gain
      • getDrivebaseWidth

        public double getDrivebaseWidth()
        Get the width of the drivebase
        Returns:
        Drivebase width
      • reset

        public void reset()
        Reset the follower
      • getNextPoint

        public Translation2d getNextPoint​(Pose2d robotPose)
        Get the next goal pose
        Parameters:
        robotPose - Robot's current pose
        Returns:
        Next goal in path
      • getFinalPose

        public Translation2d getFinalPose()
        Get the final pose of the path
        Returns:
        Final pose