14#include "wpi/units/length.hpp"
21template <std::derived_from<TrajectoryConstra
int> Constra
int>
35 [[deprecated(
"Use constructor taking Ellipse2d instead.")]]
37 wpi::units::meter_t xWidth,
38 wpi::units::meter_t yWidth,
40 const Constraint& constraint)
41 : m_ellipse{
Pose2d{
center, rotation}, xWidth / 2.0, yWidth / 2.0},
42 m_constraint(constraint) {}
52 const Constraint& constraint)
53 : m_ellipse{ellipse}, m_constraint{constraint} {}
56 const Pose2d& pose, wpi::units::curvature_t curvature,
57 wpi::units::meters_per_second_t velocity)
const override {
59 return m_constraint.MaxVelocity(pose, curvature, velocity);
61 return wpi::units::meters_per_second_t{
62 std::numeric_limits<double>::infinity()};
67 const Pose2d& pose, wpi::units::curvature_t curvature,
68 wpi::units::meters_per_second_t velocity)
const override {
70 return m_constraint.MinMaxAcceleration(pose, curvature, velocity);
78 Constraint m_constraint;
@ center
Definition base.h:688
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:66
constexpr EllipticalRegionConstraint(const Translation2d ¢er, wpi::units::meter_t xWidth, wpi::units::meter_t yWidth, const Rotation2d &rotation, const Constraint &constraint)
Constructs a new EllipticalRegionConstraint.
Definition EllipticalRegionConstraint.hpp:36
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:55
constexpr EllipticalRegionConstraint(const Ellipse2d &ellipse, const Constraint &constraint)
Constructs a new EllipticalRegionConstraint.
Definition EllipticalRegionConstraint.hpp:51
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition Pose2d.hpp:107
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
constexpr TrajectoryConstraint()=default
Represents a translation in 2D space.
Definition Translation2d.hpp:30
Definition LinearSystem.hpp:20
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.hpp:36