Class EllipticalRegionConstraint

java.lang.Object
edu.wpi.first.math.trajectory.constraint.EllipticalRegionConstraint
All Implemented Interfaces:
TrajectoryConstraint

Enforces a particular constraint only within an elliptical region.
  • Constructor Details

    • EllipticalRegionConstraint

      @Deprecated(since="2025", forRemoval=true) public EllipticalRegionConstraint(Translation2d center, double xWidth, double yWidth, Rotation2d rotation, TrajectoryConstraint constraint)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Use constructor taking Ellipse2d instead.
      Constructs a new EllipticalRegionConstraint.
      Parameters:
      center - The center of the ellipse in which to enforce the constraint.
      xWidth - The width of the ellipse in which to enforce the constraint.
      yWidth - The height of the ellipse in which to enforce the constraint.
      rotation - The rotation to apply to all radii around the origin.
      constraint - The constraint to enforce when the robot is within the region.
    • EllipticalRegionConstraint

      Constructs a new EllipticalRegionConstraint.
      Parameters:
      ellipse - The ellipse 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.