21template <std::derived_from<TrajectoryConstra
int> Constra
int>
35 [[deprecated(
"Use constructor taking Ellipse2d instead.")]]
37 units::meter_t xWidth,
38 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} {}
57 units::meters_per_second_t velocity)
const override {
59 return m_constraint.MaxVelocity(pose, curvature, velocity);
61 return units::meters_per_second_t{
62 std::numeric_limits<double>::infinity()};
68 units::meters_per_second_t speed)
const override {
70 return m_constraint.MinMaxAcceleration(pose, curvature, speed);
78 Constraint m_constraint;
Represents a 2d ellipse space containing translational, rotational, and scaling components.
Definition Ellipse2d.h:26
constexpr bool Contains(const Translation2d &point) const
Checks if a point is contained within this ellipse.
Definition Ellipse2d.h:146
Enforces a particular constraint only within an elliptical region.
Definition EllipticalRegionConstraint.h:22
constexpr EllipticalRegionConstraint(const Ellipse2d &ellipse, const Constraint &constraint)
Constructs a new EllipticalRegionConstraint.
Definition EllipticalRegionConstraint.h:51
constexpr EllipticalRegionConstraint(const Translation2d ¢er, units::meter_t xWidth, units::meter_t yWidth, const Rotation2d &rotation, const Constraint &constraint)
Constructs a new EllipticalRegionConstraint.
Definition EllipticalRegionConstraint.h:36
constexpr 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.
Definition EllipticalRegionConstraint.h:55
constexpr 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,...
Definition EllipticalRegionConstraint.h:66
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition Pose2d.h:107
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition TrajectoryConstraint.h:21
Represents a translation in 2D space.
Definition Translation2d.h:29
Represents a minimum and maximum acceleration.
Definition TrajectoryConstraint.h:37