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.
-
Nested Class Summary
Nested classes/interfaces inherited from interface edu.wpi.first.math.trajectory.constraint.TrajectoryConstraint
TrajectoryConstraint.MinMax
-
Constructor Summary
ConstructorsConstructorDescriptionEllipticalRegionConstraint
(Ellipse2d ellipse, TrajectoryConstraint constraint) Constructs a new EllipticalRegionConstraint.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. -
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.
-
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 in meters.yWidth
- The height of the ellipse in which to enforce the constraint in meters.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
-
getMaxVelocity
Description copied from interface:TrajectoryConstraint
Returns the max velocity given the current pose and curvature.- Specified by:
getMaxVelocity
in 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:TrajectoryConstraint
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.- Specified by:
getMinMaxAcceleration
in 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.
-