-
Notifications
You must be signed in to change notification settings - Fork 1
Advanced Path Generation
nab138 edited this page Jan 28, 2024
·
1 revision
Paths will likely not look like you want by default. There are many parameters that you can tweak to adjust your paths.
If you want your path to go through specific points, you can specify an ArrayList of Pose2ds instead of a single target. Example:
ArrayList<Pose2d> waypoints = new ArrayList<Pose2d>();
waypoints.add(new Pose2d(12, 6, new Rotation2d()));
waypoints.add(new Pose2d(13, 5, new Rotation2d()));
waypoints.add(new Pose2d(3, 3, new Rotation2d()));
Trajectory myPath = m_robotDrive.pathfinder.generateTrajectory(startingPose, waypoints, trajectoryConfig);If the path isn't behaving how you'd like around corners or other issues are appearing, you can tweak some parameters in the PathfinderBuilder. A full list of these and their default values are available on the PathfinderBuilder javadoc.
Example of using these methods:
pathfinder = new PathfinderBuilder(Field.CRESCENDO_2024)
.setRobotLength(DriveConstants.kWheelBase)
.setRobotWidth(DriveConstants.kTrackWidth)
.build();
By default, points are injected along the path and around corners to ensure a smooth path that does not intersect things. Disabling or changing these settings may cause trajectories that clip, but could provide smoother results.
-
setInjectPoints: Takes a boolean, true or false, for whether or not to inject points on straightaways. -
setPointSpacing: Sets how far apart points area spaced on straightaways, in meters. This does not affect corner point spacing, and does nothing if you disable point injections.
-
setCornerDist: How big to make the corners. This value in meters is used to determine how far along the straightaway it should go to start the bezier curve. -
setCornerPointSpacing: How much space between points on the corners. This is not a distance, rather how much "t" will increment between each point. See the following animation [source: wikipedia] to understand how this works:
-
setCornerSplitPercent: Changes how "Greedy" corners are. An example of this is the case where two corners are very close, and straightaway distance between them is less than the corner distance. This percentage (max 50%) is here to determine how much of the straightaway the corner will take up. The max is 50% to stop corners from overlapping -
setNormalizeCorners: Takes a boolean for whether or not to normalize the corners. Disabling this can greatly help path generation with a higher corner dist and can remove weird artifacts between corners, but will cause issues with certain path following algorithms.