Package me.nabdev.pathfinding.structures
Class Path
- All Implemented Interfaces:
Serializable
,Cloneable
,Iterable<Vertex>
,Collection<Vertex>
,List<Vertex>
,RandomAccess
A Path is a list of Vertices that represent a path from a start point to a
target point.
- See Also:
-
Field Summary
FieldsModifier and TypeFieldDescriptionThe snap mode used to create this path.Fields inherited from class java.util.AbstractList
modCount
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionvoid
Add a path to the end of this path, to be used BEFORE processing the path.ArrayList<edu.wpi.first.math.geometry.Pose2d>
Get the path as a Pose2d ArrayList.edu.wpi.first.math.trajectory.Trajectory
asTrajectory
(edu.wpi.first.math.trajectory.TrajectoryConfig config) Get the path as a Trajectory.end()
Get the last vertex in the path (not including the target vertex)edu.wpi.first.math.geometry.Rotation2d
Get rotation at the final point of the pathGet the full path including the start and target vertices.getStart()
Get the start vertex.Get the target vertex.Get the unsnapped target vertex.void
processPath
(Pathfinder.PathfindSnapMode snapMode) Apply all processing to the path to prepare it for use.void
setUnsnappedTarget
(Vertex unsnappedTarget) Set the original unsnapped target vertex (the target vertex before it was snapped to be outside of all obstacles).double[]
Get the path as a double array [x, y, rotation, x, y, rotation, ...].Methods inherited from class java.util.ArrayList
add, add, addAll, addAll, clear, clone, contains, ensureCapacity, equals, forEach, get, hashCode, indexOf, isEmpty, iterator, lastIndexOf, listIterator, listIterator, remove, remove, removeAll, removeIf, removeRange, replaceAll, retainAll, set, size, sort, spliterator, subList, toArray, toArray, trimToSize
Methods inherited from class java.util.AbstractCollection
containsAll, toString
Methods inherited from class java.lang.Object
finalize, getClass, notify, notifyAll, wait, wait, wait
Methods inherited from interface java.util.Collection
parallelStream, stream, toArray
Methods inherited from interface java.util.List
containsAll
-
Field Details
-
snapMode
The snap mode used to create this path.
-
-
Constructor Details
-
Path
Creates a new Path with the given start and target vertices.- Parameters:
start
- The start vertex of the path.target
- The target vertex of the path.pathfinder
- The Pathfinder that created this path.
-
Path
Creates a new Path with the given start and target vertices and the given- Parameters:
start
- The start vertex of the path.target
- The target vertex of the path.points
- The points in the path.
-
-
Method Details
-
setUnsnappedTarget
Set the original unsnapped target vertex (the target vertex before it was snapped to be outside of all obstacles).- Parameters:
unsnappedTarget
- The original unsnapped target vertex.
-
addPath
Add a path to the end of this path, to be used BEFORE processing the path.- Parameters:
path
- The path to add.
-
getUnsnappedTarget
Get the unsnapped target vertex.- Returns:
- The unsnapped target vertex
-
end
Get the last vertex in the path (not including the target vertex)- Returns:
- The last vertex in the path.
-
processPath
Apply all processing to the path to prepare it for use.- Parameters:
snapMode
- The snap mode to use.
-
getFinalRot
public edu.wpi.first.math.geometry.Rotation2d getFinalRot()Get rotation at the final point of the path- Returns:
- The final rotation of the path.
-
toDoubleArray
public double[] toDoubleArray()Get the path as a double array [x, y, rotation, x, y, rotation, ...]. Rotation is in degrees.- Returns:
- The path as a double array.
-
asPose2dList
Get the path as a Pose2d ArrayList.- Returns:
- An ArrayList of Pose2ds representing the path.
-
asTrajectory
public edu.wpi.first.math.trajectory.Trajectory asTrajectory(edu.wpi.first.math.trajectory.TrajectoryConfig config) throws ImpossiblePathException Get the path as a Trajectory.- Parameters:
config
- The TrajectoryConfig to use.- Returns:
- The path as a Trajectory.
- Throws:
ImpossiblePathException
- if the trajectory could not be generated.
-
getStart
Get the start vertex.- Returns:
- The start vertex
-
getTarget
Get the target vertex.- Returns:
- The target vertex
-
getFullPath
Get the full path including the start and target vertices.- Returns:
- The full path including the start and target vertices.
-