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.
  • 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

    • 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 interface TrajectoryConstraint
      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 interface TrajectoryConstraint
      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.