TrajectoryGenerator

class wpimath.trajectory.TrajectoryGenerator

Bases: pybind11_object

Helper class used to generate trajectories with various constraints.

static generateTrajectory(*args, **kwargs)

Overloaded function.

  1. generateTrajectory(initial: wpimath.spline._spline.Spline3.ControlVector, interiorWaypoints: List[wpimath.geometry._geometry.Translation2d], end: wpimath.spline._spline.Spline3.ControlVector, config: wpimath._controls._controls.trajectory.TrajectoryConfig) -> wpimath._controls._controls.trajectory.Trajectory

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.

  1. generateTrajectory(start: wpimath.geometry._geometry.Pose2d, interiorWaypoints: List[wpimath.geometry._geometry.Translation2d], end: wpimath.geometry._geometry.Pose2d, config: wpimath._controls._controls.trajectory.TrajectoryConfig) -> wpimath._controls._controls.trajectory.Trajectory

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.

  1. generateTrajectory(controlVectors: List[wpimath.spline._spline.Spline5.ControlVector], config: wpimath._controls._controls.trajectory.TrajectoryConfig) -> wpimath._controls._controls.trajectory.Trajectory

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.

  1. generateTrajectory(waypoints: List[wpimath.geometry._geometry.Pose2d], config: wpimath._controls._controls.trajectory.TrajectoryConfig) -> wpimath._controls._controls.trajectory.Trajectory

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.

static setErrorHandler(func: Callable[[str], None]) None

Set error reporting function. By default, it is output to stderr.

Parameters:

func – Error reporting function.

static splinePointsFromSplines(*args, **kwargs)

Overloaded function.

  1. splinePointsFromSplines(splines: List[wpimath.spline._spline.CubicHermiteSpline]) -> List[Tuple[wpimath.geometry._geometry.Pose2d, radians_per_meter]]

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.

  1. splinePointsFromSplines(splines: List[wpimath.spline._spline.QuinticHermiteSpline]) -> List[Tuple[wpimath.geometry._geometry.Pose2d, radians_per_meter]]

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.