18template <std::derived_from<TrajectoryConstra
int> Constra
int>
33 const Constraint& constraint)
34 : m_bottomLeftPoint(bottomLeftPoint),
35 m_topRightPoint(topRightPoint),
36 m_constraint(constraint) {}
40 units::meters_per_second_t velocity)
const override {
42 return m_constraint.MaxVelocity(pose, curvature, velocity);
44 return units::meters_per_second_t{
45 std::numeric_limits<double>::infinity()};
50 units::meters_per_second_t speed)
const override {
52 return m_constraint.MinMaxAcceleration(pose, curvature, speed);
66 return pose.
X() >= m_bottomLeftPoint.
X() &&
67 pose.
X() <= m_topRightPoint.
X() &&
68 pose.
Y() >= m_bottomLeftPoint.
Y() && pose.
Y() <= m_topRightPoint.
Y();
74 Constraint m_constraint;
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
constexpr units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition: Pose2d.h:96
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition: Pose2d.h:89
Enforces a particular constraint only within a rectangular region.
Definition: RectangularRegionConstraint.h:19
RectangularRegionConstraint(const Translation2d &bottomLeftPoint, const Translation2d &topRightPoint, const Constraint &constraint)
Constructs a new RectangularRegionConstraint.
Definition: RectangularRegionConstraint.h:31
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: RectangularRegionConstraint.h:38
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: RectangularRegionConstraint.h:49
bool IsPoseInRegion(const Pose2d &pose) const
Returns whether the specified robot pose is within the region that the constraint is enforced in.
Definition: RectangularRegionConstraint.h:65
An interface for defining user-defined velocity and acceleration constraints while generating traject...
Definition: TrajectoryConstraint.h:22
Represents a translation in 2D space.
Definition: Translation2d.h:27
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:76
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition: Translation2d.h:83
Definition: AprilTagPoseEstimator.h:15
Represents a minimum and maximum acceleration.
Definition: TrajectoryConstraint.h:37