Interface TrajectoryConstraint
- All Known Implementing Classes:
CentripetalAccelerationConstraint
,DifferentialDriveKinematicsConstraint
,DifferentialDriveVoltageConstraint
,EllipticalRegionConstraint
,MaxVelocityConstraint
,MecanumDriveKinematicsConstraint
,RectangularRegionConstraint
,SwerveDriveKinematicsConstraint
public interface TrajectoryConstraint
An interface for defining user-defined velocity and acceleration constraints while generating
trajectories.
-
Nested Class Summary
Nested ClassesModifier and TypeInterfaceDescriptionstatic class
Represents a minimum and maximum acceleration. -
Method Summary
Modifier and TypeMethodDescriptiondouble
getMaxVelocity
(Pose2d pose, double curvature, double velocity) Returns the max velocity given the current pose and curvature.getMinMaxAcceleration
(Pose2d pose, double curvature, double velocity) Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.
-
Method Details
-
getMaxVelocity
Returns the max velocity given the current pose and curvature.- Parameters:
pose
- The pose at the current point in the trajectory.curvature
- The curvature at the current point in the trajectory rad/m.velocity
- The velocity at the current point in the trajectory before constraints are applied in m/s.- Returns:
- The absolute maximum velocity.
-
getMinMaxAcceleration
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.- Parameters:
pose
- The pose at the current point in the trajectory.curvature
- The curvature at the current point in the trajectory rad/m.velocity
- The speed at the current point in the trajectory in m/s.- Returns:
- The min and max acceleration bounds.
-