Class MaxVelocityConstraint
- java.lang.Object
-
- edu.wpi.first.math.trajectory.constraint.MaxVelocityConstraint
-
- All Implemented Interfaces:
TrajectoryConstraint
public class MaxVelocityConstraint extends Object implements TrajectoryConstraint
Represents a constraint that enforces a max velocity. This can be composed with theEllipticalRegionConstraint
orRectangularRegionConstraint
to enforce a max velocity in a region.
-
-
Nested Class Summary
-
Nested classes/interfaces inherited from interface edu.wpi.first.math.trajectory.constraint.TrajectoryConstraint
TrajectoryConstraint.MinMax
-
-
Constructor Summary
Constructors Constructor Description MaxVelocityConstraint(double maxVelocityMetersPerSecond)
Constructs a new MaxVelocityConstraint.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description double
getMaxVelocityMetersPerSecond(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)
Returns the max velocity given the current pose and curvature.TrajectoryConstraint.MinMax
getMinMaxAccelerationMetersPerSecondSq(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
-
-
-
Constructor Detail
-
MaxVelocityConstraint
public MaxVelocityConstraint(double maxVelocityMetersPerSecond)
Constructs a new MaxVelocityConstraint.- Parameters:
maxVelocityMetersPerSecond
- The max velocity.
-
-
Method Detail
-
getMaxVelocityMetersPerSecond
public double getMaxVelocityMetersPerSecond(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)
Description copied from interface:TrajectoryConstraint
Returns the max velocity given the current pose and curvature.- Specified by:
getMaxVelocityMetersPerSecond
in interfaceTrajectoryConstraint
- 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
public TrajectoryConstraint.MinMax getMinMaxAccelerationMetersPerSecondSq(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)
Description copied from interface:TrajectoryConstraint
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.- Specified by:
getMinMaxAccelerationMetersPerSecondSq
in interfaceTrajectoryConstraint
- 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.
-
-