42      const std::vector<Translation2d>& interiorWaypoints,
 
   58      const Pose2d& start, 
const std::vector<Translation2d>& interiorWaypoints,
 
   95  template <
typename Spline>
 
   97      const std::vector<Spline>& splines) {
 
   99    std::vector<PoseWithCurvature> splinePoints;
 
  102    splinePoints.push_back(splines.front().GetPoint(0.0).value());
 
  106    for (
auto&& spline : splines) {
 
  107      auto points = SplineParameterizer::Parameterize(spline);
 
  111      splinePoints.insert(std::end(splinePoints), std::begin(points) + 1,
 
 
  128  static std::function<void(
const char*)> s_errorFunc;
 
 
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
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:29
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
Represents a control vector for a spline.
Definition Spline.h:48