Class Path
- java.lang.Object
-
- io.github.frc5024.purepursuit.pathgen.Path
-
- Direct Known Subclasses:
BezierPath,RawPath,SmoothPath
public class Path extends java.lang.ObjectA "Path" is a list of closely spaces points in space for a robot to follow. The default Path class will generate paths with any number of waypoints, and create linear sub-paths.
-
-
Field Summary
Fields Modifier and Type Field Description protected java.lang.Stringnameprotected doublepathGenStartTimeMsprotected doublepathGenTimeMsprotected java.util.ArrayList<Translation2d>pointsprotected Translation2d[]waypoints
-
Constructor Summary
Constructors Constructor Description Path(double spacing, Translation2d... waypoints)Create a motion path from pointsPath(Translation2d... waypoints)Create a motion path from points
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description protected voidbeginTimingGeneration()Begins an internal timer for profiling path gen timeXYChartgetPathVisualization()Get a chart showing every generated path point in 2D space.Translation2d[]getPoses()Get a list of all poses along the pathprotected voidsaveAndLogGenerationTime()Logs how long path gen tookjava.lang.StringtoString()
-
-
-
Field Detail
-
points
protected java.util.ArrayList<Translation2d> points
-
waypoints
protected Translation2d[] waypoints
-
pathGenStartTimeMs
protected double pathGenStartTimeMs
-
pathGenTimeMs
protected double pathGenTimeMs
-
name
protected java.lang.String name
-
-
Constructor Detail
-
Path
public Path(Translation2d... waypoints)
Create a motion path from points- Parameters:
waypoints- Path waypoints to follow
-
Path
public Path(double spacing, Translation2d... waypoints)Create a motion path from points- Parameters:
spacing- Amount of space between "inner" points in meterswaypoints- Path waypoints to follow
-
-
Method Detail
-
beginTimingGeneration
protected void beginTimingGeneration()
Begins an internal timer for profiling path gen time
-
saveAndLogGenerationTime
protected void saveAndLogGenerationTime()
Logs how long path gen took
-
getPoses
public Translation2d[] getPoses()
Get a list of all poses along the path- Returns:
- Poses
-
toString
public java.lang.String toString()
- Overrides:
toStringin classjava.lang.Object
-
getPathVisualization
public XYChart getPathVisualization()
Get a chart showing every generated path point in 2D space. Can be written to disk for debugging and demos.- Returns:
- Path visualization
-
-