![]() |
WPILibC++ 2027.0.0-alpha-4
|
Enforces a particular constraint only within a rectangular region. More...
#include <wpi/math/trajectory/constraint/RectangularRegionConstraint.hpp>
Public Member Functions | |
| constexpr | RectangularRegionConstraint (const Translation2d &bottomLeftPoint, const Translation2d &topRightPoint, const Constraint &constraint) |
| Constructs a new RectangularRegionConstraint. | |
| constexpr | RectangularRegionConstraint (const Rectangle2d &rectangle, const Constraint &constraint) |
| Constructs a new RectangularRegionConstraint. | |
| constexpr wpi::units::meters_per_second_t | MaxVelocity (const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const override |
| Returns the max velocity given the current pose and curvature. | |
| constexpr MinMax | MinMaxAcceleration (const Pose2d &pose, wpi::units::curvature_t curvature, wpi::units::meters_per_second_t velocity) const override |
| Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and velocity. | |
| Public Member Functions inherited from wpi::math::TrajectoryConstraint | |
| constexpr | TrajectoryConstraint ()=default |
| constexpr | TrajectoryConstraint (const TrajectoryConstraint &)=default |
| constexpr TrajectoryConstraint & | operator= (const TrajectoryConstraint &)=default |
| constexpr | TrajectoryConstraint (TrajectoryConstraint &&)=default |
| constexpr TrajectoryConstraint & | operator= (TrajectoryConstraint &&)=default |
| virtual constexpr | ~TrajectoryConstraint ()=default |
Enforces a particular constraint only within a rectangular region.
|
inlineconstexpr |
Constructs a new RectangularRegionConstraint.
| 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. |
|
inlineconstexpr |
Constructs a new RectangularRegionConstraint.
| rectangle | The rectangular region in which to enforce the constraint. |
| constraint | The constraint to enforce when the robot is within the region. |
|
inlineconstexproverridevirtual |
Returns the max velocity given the current pose and curvature.
| pose | The pose at the current point in the trajectory. |
| curvature | The curvature at the current point in the trajectory. |
| velocity | The velocity at the current point in the trajectory before constraints are applied. |
Implements wpi::math::TrajectoryConstraint.
|
inlineconstexproverridevirtual |
Returns the minimum and maximum allowable acceleration for the trajectory given pose, curvature, and velocity.
| pose | The pose at the current point in the trajectory. |
| curvature | The curvature at the current point in the trajectory. |
| velocity | The velocity at the current point in the trajectory. |
Implements wpi::math::TrajectoryConstraint.