Class RectangularRegionConstraint
java.lang.Object
edu.wpi.first.math.trajectory.constraint.RectangularRegionConstraint
- All Implemented Interfaces:
TrajectoryConstraint
Enforces a particular constraint only within a rectangular region.
-
Nested Class Summary
Nested classes/interfaces inherited from interface edu.wpi.first.math.trajectory.constraint.TrajectoryConstraint
TrajectoryConstraint.MinMax -
Constructor Summary
ConstructorsConstructorDescriptionRectangularRegionConstraint(Rectangle2d rectangle, TrajectoryConstraint constraint) Constructs a new RectangularRegionConstraint.RectangularRegionConstraint(Translation2d bottomLeftPoint, Translation2d topRightPoint, TrajectoryConstraint constraint) Deprecated, for removal: This API element is subject to removal in a future version.Use constructor taking Rectangle2d instead. -
Method Summary
Modifier and TypeMethodDescriptiondoublegetMaxVelocity(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.
-
Constructor Details
-
RectangularRegionConstraint
@Deprecated(since="2025", forRemoval=true) public RectangularRegionConstraint(Translation2d bottomLeftPoint, Translation2d topRightPoint, TrajectoryConstraint constraint) Deprecated, for removal: This API element is subject to removal in a future version.Use constructor taking Rectangle2d instead.Constructs a new RectangularRegionConstraint.- Parameters:
bottomLeftPoint- The bottom left point of the rectangular region in which to enforce the constraint.topRightPoint- The top right point of the rectangular region in which to enforce the constraint.constraint- The constraint to enforce when the robot is within the region.
-
RectangularRegionConstraint
Constructs a new RectangularRegionConstraint.- Parameters:
rectangle- The rectangular region in which to enforce the constraint.constraint- The constraint to enforce when the robot is within the region.
-
-
Method Details
-
getMaxVelocity
Description copied from interface:TrajectoryConstraintReturns the max velocity given the current pose and curvature.- Specified by:
getMaxVelocityin interfaceTrajectoryConstraint- 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
public TrajectoryConstraint.MinMax getMinMaxAcceleration(Pose2d pose, double curvature, double velocity) Description copied from interface:TrajectoryConstraintReturns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.- Specified by:
getMinMaxAccelerationin interfaceTrajectoryConstraint- 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.
-