|
| RectangularRegionConstraint (const Translation2d &bottomLeftPoint, const Translation2d &topRightPoint, const Constraint &constraint) |
| Constructs a new RectangularRegionConstraint. More...
|
|
units::meters_per_second_t | MaxVelocity (const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t velocity) const override |
| Returns the max velocity given the current pose and curvature. More...
|
|
MinMax | MinMaxAcceleration (const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t speed) const override |
| Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed. More...
|
|
bool | IsPoseInRegion (const Pose2d &pose) const |
| Returns whether the specified robot pose is within the region that the constraint is enforced in. More...
|
|
| TrajectoryConstraint ()=default |
|
| TrajectoryConstraint (const TrajectoryConstraint &)=default |
|
TrajectoryConstraint & | operator= (const TrajectoryConstraint &)=default |
|
| TrajectoryConstraint (TrajectoryConstraint &&)=default |
|
TrajectoryConstraint & | operator= (TrajectoryConstraint &&)=default |
|
virtual | ~TrajectoryConstraint ()=default |
|
virtual units::meters_per_second_t | MaxVelocity (const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t velocity) const =0 |
| Returns the max velocity given the current pose and curvature. More...
|
|
virtual MinMax | MinMaxAcceleration (const Pose2d &pose, units::curvature_t curvature, units::meters_per_second_t speed) const =0 |
| Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and speed. More...
|
|
template<std::derived_from<
TrajectoryConstraint > Constraint>
class frc::RectangularRegionConstraint< Constraint >
Enforces a particular constraint only within a rectangular region.