14#include "wpi/units/length.hpp"
21template <std::derived_from<TrajectoryConstra
int> Constra
int>
32 const Constraint& constraint)
33 : m_ellipse{ellipse}, m_constraint{constraint} {}
36 const Pose2d& pose, wpi::units::curvature_t curvature,
37 wpi::units::meters_per_second_t velocity)
const override {
39 return m_constraint.MaxVelocity(pose, curvature, velocity);
41 return wpi::units::meters_per_second_t{
42 std::numeric_limits<double>::infinity()};
47 const Pose2d& pose, wpi::units::curvature_t curvature,
48 wpi::units::meters_per_second_t velocity)
const override {
50 return m_constraint.MinMaxAcceleration(pose, curvature, velocity);
58 Constraint m_constraint;
Represents a 2d ellipse space containing translational, rotational, and scaling components.
Definition Ellipse2d.hpp:26
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 EllipticalRegionConstraint.hpp:46
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 EllipticalRegionConstraint.hpp:35
constexpr EllipticalRegionConstraint(const Ellipse2d &ellipse, const Constraint &constraint)
Constructs a new EllipticalRegionConstraint.
Definition EllipticalRegionConstraint.hpp:31
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
constexpr TrajectoryConstraint()=default
Definition LinearSystem.hpp:20
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.hpp:36