From d8d8b899765271dd5a965d344d2307bd9e07caee Mon Sep 17 00:00:00 2001 From: Michael Jansen Date: Fri, 13 Oct 2023 19:39:00 -0400 Subject: [PATCH] re-add the fromPathPoints PathPlannerPath factory method (#399) * re-add fromPathPoints factory to java pplib * format --- .../pathplanner/lib/path/PathPlannerPath.java | 17 +++++++++++++++++ .../com/pathplanner/lib/path/PathPoint.java | 9 --------- 2 files changed, 17 insertions(+), 9 deletions(-) diff --git a/pathplannerlib/src/main/java/com/pathplanner/lib/path/PathPlannerPath.java b/pathplannerlib/src/main/java/com/pathplanner/lib/path/PathPlannerPath.java index f77bd0c8..19bf1dc0 100644 --- a/pathplannerlib/src/main/java/com/pathplanner/lib/path/PathPlannerPath.java +++ b/pathplannerlib/src/main/java/com/pathplanner/lib/path/PathPlannerPath.java @@ -110,6 +110,23 @@ private PathPlannerPath(PathConstraints globalConstraints, GoalEndState goalEndS this.allPoints = new ArrayList<>(); } + /** + * Creat a path with pre-generated points. This should already be a smooth path. + * + * @param pathPoints Path points along the smooth curve of the path + * @param constraints The global constraints of the path + * @param goalEndState The goal end state of the path + * @return A PathPlannerPath following the given pathpoints + */ + public static PathPlannerPath fromPathPoints( + List pathPoints, PathConstraints constraints, GoalEndState goalEndState) { + PathPlannerPath path = new PathPlannerPath(constraints, goalEndState); + path.allPoints = pathPoints; + path.precalcValues(); + + return path; + } + /** * Create the bezier points necessary to create a path using a list of poses * diff --git a/pathplannerlib/src/main/java/com/pathplanner/lib/path/PathPoint.java b/pathplannerlib/src/main/java/com/pathplanner/lib/path/PathPoint.java index eae2e641..22975a41 100644 --- a/pathplannerlib/src/main/java/com/pathplanner/lib/path/PathPoint.java +++ b/pathplannerlib/src/main/java/com/pathplanner/lib/path/PathPoint.java @@ -45,15 +45,6 @@ public PathPoint(Translation2d position, Rotation2d holonomicRotation) { this.holonomicRotation = holonomicRotation; } - /** - * Create a path point - * - * @param position Position of the point - */ - public PathPoint(Translation2d position) { - this.position = position; - } - @Override public boolean equals(Object o) { if (this == o) return true;