Interface TrajectoryConstraint


  • public interface TrajectoryConstraint
    An interface for defining user-defined velocity and acceleration constraints while generating trajectories.
    • Method Detail

      • getMaxVelocityMetersPerSecond

        double getMaxVelocityMetersPerSecond​(edu.wpi.first.math.geometry.Pose2d poseMeters,
                                             double curvatureRadPerMeter,
                                             double velocityMetersPerSecond)
        Returns the max velocity given the current pose and curvature.
        Parameters:
        poseMeters - The pose at the current point in the trajectory.
        curvatureRadPerMeter - The curvature at the current point in the trajectory.
        velocityMetersPerSecond - The velocity at the current point in the trajectory before constraints are applied.
        Returns:
        The absolute maximum velocity.
      • getMinMaxAccelerationMetersPerSecondSq

        TrajectoryConstraint.AccelerationLimit getMinMaxAccelerationMetersPerSecondSq​(edu.wpi.first.math.geometry.Pose2d poseMeters,
                                                                                      double curvatureRadPerMeter,
                                                                                      double velocityMetersPerSecond)
        Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
        Parameters:
        poseMeters - The pose at the current point in the trajectory.
        curvatureRadPerMeter - The curvature at the current point in the trajectory.
        velocityMetersPerSecond - The speed at the current point in the trajectory.
        Returns:
        The min and max acceleration bounds.