Class EasyTrajectory


  • public class EasyTrajectory
    extends java.lang.Object
    • Field Summary

      Fields 
      Modifier and Type Field Description
      boolean isQuintic
      Trajectory type From WPI: - Hermite clamped cubic: This is the recommended option for most users.
    • Constructor Summary

      Constructors 
      Constructor Description
      EasyTrajectory​(edu.wpi.first.wpilibj.geometry.Pose2d... points)
      Create a trajectory from a list of points
      EasyTrajectory​(edu.wpi.first.wpilibj.geometry.Pose2d start, edu.wpi.first.wpilibj.geometry.Pose2d end)
      Create a trajectory from a start and end position
      EasyTrajectory​(edu.wpi.first.wpilibj.geometry.Pose2d start, edu.wpi.first.wpilibj.geometry.Pose2d end, edu.wpi.first.wpilibj.geometry.Translation2d... innerPoints)
      Create a cubic spline trajectory from start, end, and s-curve points
      EasyTrajectory​(edu.wpi.first.wpilibj.geometry.Pose2d start, edu.wpi.first.wpilibj.geometry.Translation2d a, edu.wpi.first.wpilibj.geometry.Translation2d b, edu.wpi.first.wpilibj.geometry.Pose2d end)
      Create a cubic spline trajectory from start, end, and s-curve points
    • Method Summary

      All Methods Instance Methods Concrete Methods 
      Modifier and Type Method Description
      java.util.List<edu.wpi.first.wpilibj.geometry.Pose2d> getABSPoints()
      Get all defined absolute points.
      java.util.List<edu.wpi.first.wpilibj.geometry.Translation2d> getInteriorPoints()
      Get interior points.
      • Methods inherited from class java.lang.Object

        clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
    • Field Detail

      • isQuintic

        public boolean isQuintic
        Trajectory type From WPI: - Hermite clamped cubic: This is the recommended option for most users. Generation of trajectories using these splines involves specifying the (x, y) coordinates of all points, and the headings at the start and end waypoints. The headings at the interior waypoints are automatically determined to ensure continuous curvature (rate of change of the heading) throughout. - Hermite quintic: This is a more advanced option which requires the user to specify (x, y) coordinates and headings for all waypoints. This should be used if you are unhappy with the trajectories that are being generated by the clamped cubic splines or if you want finer control of headings at the interior points.
    • Constructor Detail

      • EasyTrajectory

        public EasyTrajectory​(edu.wpi.first.wpilibj.geometry.Pose2d start,
                              edu.wpi.first.wpilibj.geometry.Pose2d end)
        Create a trajectory from a start and end position
        Parameters:
        start - Start pose
        end - End pose
      • EasyTrajectory

        public EasyTrajectory​(edu.wpi.first.wpilibj.geometry.Pose2d... points)
        Create a trajectory from a list of points
        Parameters:
        points - Array of poses (Must have at least 2 poses)
      • EasyTrajectory

        public EasyTrajectory​(edu.wpi.first.wpilibj.geometry.Pose2d start,
                              edu.wpi.first.wpilibj.geometry.Translation2d a,
                              edu.wpi.first.wpilibj.geometry.Translation2d b,
                              edu.wpi.first.wpilibj.geometry.Pose2d end)
        Create a cubic spline trajectory from start, end, and s-curve points
        Parameters:
        start - Start pose
        a - First interior translation
        b - Second interior translation
        end - End pose
      • EasyTrajectory

        public EasyTrajectory​(edu.wpi.first.wpilibj.geometry.Pose2d start,
                              edu.wpi.first.wpilibj.geometry.Pose2d end,
                              edu.wpi.first.wpilibj.geometry.Translation2d... innerPoints)
        Create a cubic spline trajectory from start, end, and s-curve points
        Parameters:
        start - Start pose
        end - End pose
    • Method Detail

      • getABSPoints

        public java.util.List<edu.wpi.first.wpilibj.geometry.Pose2d> getABSPoints()
        Get all defined absolute points. If this is a cubic spline, they will be the start and end poses
        Returns:
        All Poses
      • getInteriorPoints

        public java.util.List<edu.wpi.first.wpilibj.geometry.Translation2d> getInteriorPoints()
        Get interior points. This will be null if not cubic
        Returns:
        Interior points