WPILibC++ 2024.3.2
RectangularRegionConstraint.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <concepts>
8#include <limits>
9
13
14namespace frc {
15/**
16 * Enforces a particular constraint only within a rectangular region.
17 */
18template <std::derived_from<TrajectoryConstraint> Constraint>
20 public:
21 /**
22 * Constructs a new RectangularRegionConstraint.
23 *
24 * @param bottomLeftPoint The bottom left point of the rectangular region in
25 * which to enforce the constraint.
26 * @param topRightPoint The top right point of the rectangular region in which
27 * to enforce the constraint.
28 * @param constraint The constraint to enforce when the robot is within the
29 * region.
30 */
32 const Translation2d& topRightPoint,
33 const Constraint& constraint)
34 : m_bottomLeftPoint(bottomLeftPoint),
35 m_topRightPoint(topRightPoint),
36 m_constraint(constraint) {}
37
38 units::meters_per_second_t MaxVelocity(
39 const Pose2d& pose, units::curvature_t curvature,
40 units::meters_per_second_t velocity) const override {
41 if (IsPoseInRegion(pose)) {
42 return m_constraint.MaxVelocity(pose, curvature, velocity);
43 } else {
44 return units::meters_per_second_t{
45 std::numeric_limits<double>::infinity()};
46 }
47 }
48
50 units::meters_per_second_t speed) const override {
51 if (IsPoseInRegion(pose)) {
52 return m_constraint.MinMaxAcceleration(pose, curvature, speed);
53 } else {
54 return {};
55 }
56 }
57
58 /**
59 * Returns whether the specified robot pose is within the region that the
60 * constraint is enforced in.
61 *
62 * @param pose The robot pose.
63 * @return Whether the robot pose is within the constraint region.
64 */
65 bool IsPoseInRegion(const Pose2d& pose) const {
66 return pose.X() >= m_bottomLeftPoint.X() &&
67 pose.X() <= m_topRightPoint.X() &&
68 pose.Y() >= m_bottomLeftPoint.Y() && pose.Y() <= m_topRightPoint.Y();
69 }
70
71 private:
72 Translation2d m_bottomLeftPoint;
73 Translation2d m_topRightPoint;
74 Constraint m_constraint;
75};
76} // namespace frc
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