Helper class used to generate trajectories with various constraints.
More...
#include <TrajectoryGenerator.h>
Helper class used to generate trajectories with various constraints.
◆ GenerateTrajectory() [1/4]
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
-
| start | The starting pose. |
| interiorWaypoints | The interior waypoints. |
| end | The ending pose. |
| config | The configuration for the trajectory. |
- Returns
- The generated trajectory.
◆ GenerateTrajectory() [2/4]
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
-
| waypoints | List of waypoints.. |
| config | The configuration for the trajectory. |
- Returns
- The generated trajectory.
◆ GenerateTrajectory() [3/4]
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
-
| initial | The initial control vector. |
| interiorWaypoints | The interior waypoints. |
| end | The ending control vector. |
| config | The configuration for the trajectory. |
- Returns
- The generated trajectory.
◆ GenerateTrajectory() [4/4]
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
-
| controlVectors | List of quintic control vectors. |
| config | The configuration for the trajectory. |
- Returns
- The generated trajectory.
◆ SetErrorHandler()
| static void frc::TrajectoryGenerator::SetErrorHandler |
( |
std::function< void(const char *)> |
func | ) |
|
|
inlinestatic |
Set error reporting function.
By default, it is output to stderr.
- Parameters
-
| func | Error 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
-
| splines | The 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: