WPILibC++ 2024.3.2
frc::TrajectoryGenerator Class Reference

Helper class used to generate trajectories with various constraints. More...

#include <frc/trajectory/TrajectoryGenerator.h>

Public Types

using PoseWithCurvature = std::pair< Pose2d, units::curvature_t >
 

Static Public Member Functions

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. More...
 
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. More...
 
static Trajectory GenerateTrajectory (std::vector< Spline< 5 >::ControlVector > controlVectors, const TrajectoryConfig &config)
 Generates a trajectory from the given quintic control vectors and config. More...
 
static Trajectory GenerateTrajectory (const std::vector< Pose2d > &waypoints, const TrajectoryConfig &config)
 Generates a trajectory from the given waypoints and config. More...
 
template<typename Spline >
static std::vector< PoseWithCurvatureSplinePointsFromSplines (const std::vector< Spline > &splines)
 Generate spline points from a vector of splines by parameterizing the splines. More...
 
static void SetErrorHandler (std::function< void(const char *)> func)
 Set error reporting function. More...
 

Detailed Description

Helper class used to generate trajectories with various constraints.

Member Typedef Documentation

◆ PoseWithCurvature

Member Function Documentation

◆ GenerateTrajectory() [1/4]

static Trajectory frc::TrajectoryGenerator::GenerateTrajectory ( const Pose2d start,
const std::vector< Translation2d > &  interiorWaypoints,
const Pose2d end,
const TrajectoryConfig config 
)
static

Generates a trajectory from the given waypoints and config.

This method uses clamped cubic splines – a method in which the initial pose, final pose, and interior waypoints are provided. The headings are automatically determined at the interior points to ensure continuous curvature.

Parameters
startThe starting pose.
interiorWaypointsThe interior waypoints.
endThe ending pose.
configThe configuration for the trajectory.
Returns
The generated trajectory.

◆ GenerateTrajectory() [2/4]

static Trajectory frc::TrajectoryGenerator::GenerateTrajectory ( const std::vector< Pose2d > &  waypoints,
const TrajectoryConfig config 
)
static

Generates a trajectory from the given waypoints and config.

This method uses quintic hermite splines – therefore, all points must be represented by Pose2d objects. Continuous curvature is guaranteed in this method.

Parameters
waypointsList of waypoints..
configThe configuration for the trajectory.
Returns
The generated trajectory.

◆ GenerateTrajectory() [3/4]

static Trajectory frc::TrajectoryGenerator::GenerateTrajectory ( Spline< 3 >::ControlVector  initial,
const std::vector< Translation2d > &  interiorWaypoints,
Spline< 3 >::ControlVector  end,
const TrajectoryConfig config 
)
static

Generates a trajectory from the given control vectors and config.

This method uses clamped cubic splines – a method in which the exterior control vectors and interior waypoints are provided. The headings are automatically determined at the interior points to ensure continuous curvature.

Parameters
initialThe initial control vector.
interiorWaypointsThe interior waypoints.
endThe ending control vector.
configThe configuration for the trajectory.
Returns
The generated trajectory.

◆ GenerateTrajectory() [4/4]

static Trajectory frc::TrajectoryGenerator::GenerateTrajectory ( std::vector< Spline< 5 >::ControlVector >  controlVectors,
const TrajectoryConfig config 
)
static

Generates a trajectory from the given quintic control vectors and config.

This method uses quintic hermite splines – therefore, all points must be represented by control vectors. Continuous curvature is guaranteed in this method.

Parameters
controlVectorsList of quintic control vectors.
configThe configuration for the trajectory.
Returns
The generated trajectory.

◆ SetErrorHandler()

static void frc::TrajectoryGenerator::SetErrorHandler ( std::function< void(const char *)>  func)
static

Set error reporting function.

By default, it is output to stderr.

Parameters
funcError reporting function.

◆ SplinePointsFromSplines()

template<typename Spline >
static std::vector< PoseWithCurvature > frc::TrajectoryGenerator::SplinePointsFromSplines ( const std::vector< Spline > &  splines)
inlinestatic

Generate spline points from a vector of splines by parameterizing the splines.

Parameters
splinesThe splines to parameterize.
Returns
The spline points for use in time parameterization of a trajectory.

The documentation for this class was generated from the following file: