Class RectangularRegionConstraint
java.lang.Object
edu.wpi.first.math.trajectory.constraint.RectangularRegionConstraint
- All Implemented Interfaces:
TrajectoryConstraint
public class RectangularRegionConstraint extends Object implements 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
Constructors Constructor Description RectangularRegionConstraint(Translation2d bottomLeftPoint, Translation2d topRightPoint, TrajectoryConstraint constraint)
Constructs a new RectangularRegionConstraint. -
Method Summary
Modifier and Type Method Description double
getMaxVelocityMetersPerSecond(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)
Returns the max velocity given the current pose and curvature.TrajectoryConstraint.MinMax
getMinMaxAccelerationMetersPerSecondSq(Pose2d poseMeters, double curvatureRadPerMeter, double velocityMetersPerSecond)
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed.boolean
isPoseInRegion(Pose2d robotPose)
Returns whether the specified robot pose is within the region that the constraint is enforced in.
-
Constructor Details
-
RectangularRegionConstraint
public RectangularRegionConstraint(Translation2d bottomLeftPoint, Translation2d topRightPoint, TrajectoryConstraint constraint)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.
-
-
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 interfaceTrajectoryConstraint
- 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 interfaceTrajectoryConstraint
- 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.
-
isPoseInRegion
Returns whether the specified robot pose is within the region that the constraint is enforced in.- Parameters:
robotPose
- The robot pose.- Returns:
- Whether the robot pose is within the constraint region.
-