19template <std::derived_from<TrajectoryConstra
int> Constra
int>
30 const Constraint& constraint)
31 : m_rectangle{rectangle}, m_constraint{constraint} {}
34 const Pose2d& pose, wpi::units::curvature_t curvature,
35 wpi::units::meters_per_second_t velocity)
const override {
37 return m_constraint.MaxVelocity(pose, curvature, velocity);
39 return wpi::units::meters_per_second_t{
40 std::numeric_limits<double>::infinity()};
45 const Pose2d& pose, wpi::units::curvature_t curvature,
46 wpi::units::meters_per_second_t velocity)
const override {
48 return m_constraint.MinMaxAcceleration(pose, curvature, velocity);
56 Constraint m_constraint;
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:30
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition Pose2d.hpp:110
Represents a 2d rectangular space containing translational, rotational, and scaling components.
Definition Rectangle2d.hpp:24
constexpr RectangularRegionConstraint(const Rectangle2d &rectangle, const Constraint &constraint)
Constructs a new RectangularRegionConstraint.
Definition RectangularRegionConstraint.hpp:29
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.
Definition RectangularRegionConstraint.hpp:33
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,...
Definition RectangularRegionConstraint.hpp:44
constexpr TrajectoryConstraint()=default
Definition LinearSystem.hpp:20
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.hpp:36