WPILibC++ 2024.3.2
TrajectoryGenerator.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <functional>
8#include <memory>
9#include <utility>
10#include <vector>
11
12#include <wpi/SymbolExports.h>
13
19
20namespace frc {
21/**
22 * Helper class used to generate trajectories with various constraints.
23 */
25 public:
26 using PoseWithCurvature = std::pair<Pose2d, units::curvature_t>;
27
28 /**
29 * Generates a trajectory from the given control vectors and config. This
30 * method uses clamped cubic splines -- a method in which the exterior control
31 * vectors and interior waypoints are provided. The headings are automatically
32 * determined at the interior points to ensure continuous curvature.
33 *
34 * @param initial The initial control vector.
35 * @param interiorWaypoints The interior waypoints.
36 * @param end The ending control vector.
37 * @param config The configuration for the trajectory.
38 * @return The generated trajectory.
39 */
42 const std::vector<Translation2d>& interiorWaypoints,
44
45 /**
46 * Generates a trajectory from the given waypoints and config. This method
47 * uses clamped cubic splines -- a method in which the initial pose, final
48 * pose, and interior waypoints are provided. The headings are automatically
49 * determined at the interior points to ensure continuous curvature.
50 *
51 * @param start The starting pose.
52 * @param interiorWaypoints The interior waypoints.
53 * @param end The ending pose.
54 * @param config The configuration for the trajectory.
55 * @return The generated trajectory.
56 */
58 const Pose2d& start, const std::vector<Translation2d>& interiorWaypoints,
59 const Pose2d& end, const TrajectoryConfig& config);
60
61 /**
62 * Generates a trajectory from the given quintic control vectors and config.
63 * This method uses quintic hermite splines -- therefore, all points must be
64 * represented by control vectors. Continuous curvature is guaranteed in this
65 * method.
66 *
67 * @param controlVectors List of quintic control vectors.
68 * @param config The configuration for the trajectory.
69 * @return The generated trajectory.
70 */
72 std::vector<Spline<5>::ControlVector> controlVectors,
73 const TrajectoryConfig& config);
74
75 /**
76 * Generates a trajectory from the given waypoints and config. This method
77 * uses quintic hermite splines -- therefore, all points must be represented
78 * by Pose2d objects. Continuous curvature is guaranteed in this method.
79 *
80 * @param waypoints List of waypoints..
81 * @param config The configuration for the trajectory.
82 * @return The generated trajectory.
83 */
84 static Trajectory GenerateTrajectory(const std::vector<Pose2d>& waypoints,
85 const TrajectoryConfig& config);
86
87 /**
88 * Generate spline points from a vector of splines by parameterizing the
89 * splines.
90 *
91 * @param splines The splines to parameterize.
92 *
93 * @return The spline points for use in time parameterization of a trajectory.
94 */
95 template <typename Spline>
96 static std::vector<PoseWithCurvature> SplinePointsFromSplines(
97 const std::vector<Spline>& splines) {
98 // Create the vector of spline points.
99 std::vector<PoseWithCurvature> splinePoints;
100
101 // Add the first point to the vector.
102 splinePoints.push_back(splines.front().GetPoint(0.0));
103
104 // Iterate through the vector and parameterize each spline, adding the
105 // parameterized points to the final vector.
106 for (auto&& spline : splines) {
107 auto points = SplineParameterizer::Parameterize(spline);
108 // Append the array of poses to the vector. We are removing the first
109 // point because it's a duplicate of the last point from the previous
110 // spline.
111 splinePoints.insert(std::end(splinePoints), std::begin(points) + 1,
112 std::end(points));
113 }
114 return splinePoints;
115 }
116
117 /**
118 * Set error reporting function. By default, it is output to stderr.
119 *
120 * @param func Error reporting function.
121 */
122 static void SetErrorHandler(std::function<void(const char*)> func);
123
124 private:
125 static void ReportError(const char* error);
126
127 static const Trajectory kDoNothingTrajectory;
128 static std::function<void(const char*)> s_errorFunc;
129};
130} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Represents a two-dimensional parametric spline that interpolates between two points.
Definition: Spline.h:25
static std::vector< PoseWithCurvature > Parameterize(const Spline< Dim > &spline, double t0=0.0, double t1=1.0)
Parametrizes the spline.
Definition: SplineParameterizer.h:72
Represents the configuration for generating a trajectory.
Definition: TrajectoryConfig.h:35
Helper class used to generate trajectories with various constraints.
Definition: TrajectoryGenerator.h:24
std::pair< Pose2d, units::curvature_t > PoseWithCurvature
Definition: TrajectoryGenerator.h:26
static Trajectory GenerateTrajectory(const Pose2d &start, const std::vector< Translation2d > &interiorWaypoints, const Pose2d &end, const TrajectoryConfig &config)
Generates a trajectory from the given waypoints and config.
static void SetErrorHandler(std::function< void(const char *)> func)
Set error reporting function.
static Trajectory GenerateTrajectory(const std::vector< Pose2d > &waypoints, const TrajectoryConfig &config)
Generates a trajectory from the given waypoints and config.
static std::vector< PoseWithCurvature > SplinePointsFromSplines(const std::vector< Spline > &splines)
Generate spline points from a vector of splines by parameterizing the splines.
Definition: TrajectoryGenerator.h:96
static Trajectory GenerateTrajectory(Spline< 3 >::ControlVector initial, const std::vector< Translation2d > &interiorWaypoints, Spline< 3 >::ControlVector end, const TrajectoryConfig &config)
Generates a trajectory from the given control vectors and config.
static Trajectory GenerateTrajectory(std::vector< Spline< 5 >::ControlVector > controlVectors, const TrajectoryConfig &config)
Generates a trajectory from the given quintic control vectors and config.
Represents a time-parameterized trajectory.
Definition: Trajectory.h:25
Definition: AprilTagPoseEstimator.h:15
void ReportError(int32_t status, const char *fileName, int lineNumber, const char *funcName, fmt::string_view format, Args &&... args)
Reports an error to the driver station (using HAL_SendError).
Definition: Errors.h:78