WPILibC++ 2025.0.0-alpha-1-14-g3b6f38d
Rectangle2d.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 <algorithm>
8#include <stdexcept>
9
10#include <wpi/SymbolExports.h>
11
12#include "frc/geometry/Pose2d.h"
16#include "units/length.h"
17#include "units/math.h"
18
19namespace frc {
20
21/**
22 * Represents a 2d rectangular space containing translational, rotational, and
23 * scaling components.
24 */
26 public:
27 /**
28 * Constructs a rectangle at the specified position with the specified width
29 * and height.
30 *
31 * @param center The position (translation and rotation) of the rectangle.
32 * @param xWidth The x size component of the rectangle, in unrotated
33 * coordinate frame.
34 * @param yWidth The y size component of the rectangle, in unrotated
35 * coordinate frame.
36 */
37 constexpr Rectangle2d(const Pose2d& center, units::meter_t xWidth,
38 units::meter_t yWidth)
39 : m_center{center}, m_xWidth{xWidth}, m_yWidth{yWidth} {
40 if (xWidth < 0_m || yWidth < 0_m) {
41 throw std::invalid_argument(
42 "Rectangle2d dimensions cannot be less than 0!");
43 }
44 }
45
46 /**
47 * Creates an unrotated rectangle from the given corners. The corners should
48 * be diagonally opposite of each other.
49 *
50 * @param cornerA The first corner of the rectangle.
51 * @param cornerB The second corner of the rectangle.
52 */
53 constexpr Rectangle2d(const Translation2d& cornerA,
54 const Translation2d& cornerB)
55 : m_center{(cornerA + cornerB) / 2.0, Rotation2d{}},
56 m_xWidth{units::math::abs(cornerA.X() - cornerB.X())},
57 m_yWidth{units::math::abs(cornerA.Y() - cornerB.Y())} {}
58
59 /**
60 * Returns the center of the rectangle.
61 *
62 * @return The center of the rectangle.
63 */
64 constexpr const Pose2d& Center() const { return m_center; }
65
66 /**
67 * Returns the rotational component of the rectangle.
68 *
69 * @return The rotational component of the rectangle.
70 */
71 constexpr const Rotation2d& Rotation() const { return m_center.Rotation(); }
72
73 /**
74 * Returns the x size component of the rectangle.
75 *
76 * @return The x size component of the rectangle.
77 */
78 constexpr units::meter_t XWidth() const { return m_xWidth; }
79
80 /**
81 * Returns the y size component of the rectangle.
82 *
83 * @return The y size component of the rectangle.
84 */
85 constexpr units::meter_t YWidth() const { return m_yWidth; }
86
87 /**
88 * Transforms the center of the rectangle and returns the new rectangle.
89 *
90 * @param other The transform to transform by.
91 * @return The transformed rectangle
92 */
93 constexpr Rectangle2d TransformBy(const Transform2d& other) const {
94 return Rectangle2d{m_center.TransformBy(other), m_xWidth, m_yWidth};
95 }
96
97 /**
98 * Rotates the center of the rectangle and returns the new rectangle.
99 *
100 * @param other The rotation to transform by.
101 * @return The rotated rectangle.
102 */
103 constexpr Rectangle2d RotateBy(const Rotation2d& other) const {
104 return Rectangle2d{m_center.RotateBy(other), m_xWidth, m_yWidth};
105 }
106
107 /**
108 * Checks if a point is intersected by the rectangle's perimeter.
109 *
110 * @param point The point to check.
111 * @return True, if the rectangle's perimeter intersects the point.
112 */
113 constexpr bool Intersects(const Translation2d& point) const {
114 // Move the point into the rectangle's coordinate frame
115 auto pointInRect = point - m_center.Translation();
116 pointInRect = pointInRect.RotateBy(-m_center.Rotation());
117
118 if (units::math::abs(units::math::abs(pointInRect.X()) - m_xWidth / 2.0) <=
119 1E-9_m) {
120 // Point rests on left/right perimeter
121 return units::math::abs(pointInRect.Y()) <= m_yWidth / 2.0;
122 } else if (units::math::abs(units::math::abs(pointInRect.Y()) -
123 m_yWidth / 2.0) <= 1E-9_m) {
124 // Point rests on top/bottom perimeter
125 return units::math::abs(pointInRect.X()) <= m_xWidth / 2.0;
126 }
127
128 return false;
129 }
130
131 /**
132 * Checks if a point is contained within the rectangle. This is inclusive, if
133 * the point lies on the perimeter it will return true.
134 *
135 * @param point The point to check.
136 * @return True, if the rectangle contains the point or the perimeter
137 * intersects the point.
138 */
139 constexpr bool Contains(const Translation2d& point) const {
140 // Rotate the point into the rectangle's coordinate frame
141 auto rotPoint =
142 point.RotateAround(m_center.Translation(), -m_center.Rotation());
143
144 // Check if within bounding box
145 return rotPoint.X() >= (m_center.X() - m_xWidth / 2.0) &&
146 rotPoint.X() <= (m_center.X() + m_xWidth / 2.0) &&
147 rotPoint.Y() >= (m_center.Y() - m_yWidth / 2.0) &&
148 rotPoint.Y() <= (m_center.Y() + m_yWidth / 2.0);
149 }
150
151 /**
152 * Returns the distance between the perimeter of the rectangle and the point.
153 *
154 * @param point The point to check.
155 * @return The distance (0, if the point is contained by the rectangle)
156 */
157 constexpr units::meter_t Distance(const Translation2d& point) const {
158 return FindNearestPoint(point).Distance(point);
159 }
160
161 /**
162 * Returns the nearest point that is contained within the rectangle.
163 *
164 * @param point The point that this will find the nearest point to.
165 * @return A new point that is nearest to {@code point} and contained in the
166 * rectangle.
167 */
168 constexpr Translation2d FindNearestPoint(const Translation2d& point) const {
169 // Check if already in rectangle
170 if (Contains(point)) {
171 return point;
172 }
173
174 // Rotate the point by the inverse of the rectangle's rotation
175 auto rotPoint =
176 point.RotateAround(m_center.Translation(), -m_center.Rotation());
177
178 // Find nearest point
179 rotPoint =
180 Translation2d{std::clamp(rotPoint.X(), m_center.X() - m_xWidth / 2.0,
181 m_center.X() + m_xWidth / 2.0),
182 std::clamp(rotPoint.Y(), m_center.Y() - m_yWidth / 2.0,
183 m_center.Y() + m_yWidth / 2.0)};
184
185 // Undo rotation
186 return rotPoint.RotateAround(m_center.Translation(), m_center.Rotation());
187 }
188
189 /**
190 * Checks equality between this Rectangle2d and another object.
191 *
192 * @param other The other object.
193 * @return Whether the two objects are equal.
194 */
195 constexpr bool operator==(const Rectangle2d& other) const {
196 return m_center == other.m_center &&
197 units::math::abs(m_xWidth - other.m_xWidth) < 1E-9_m &&
198 units::math::abs(m_yWidth - other.m_yWidth) < 1E-9_m;
199 }
200
201 private:
202 Pose2d m_center;
203 units::meter_t m_xWidth;
204 units::meter_t m_yWidth;
205};
206
207} // namespace frc
208
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Represents a 2d rectangular space containing translational, rotational, and scaling components.
Definition: Rectangle2d.h:25
constexpr const Rotation2d & Rotation() const
Returns the rotational component of the rectangle.
Definition: Rectangle2d.h:71
constexpr units::meter_t YWidth() const
Returns the y size component of the rectangle.
Definition: Rectangle2d.h:85
constexpr Translation2d FindNearestPoint(const Translation2d &point) const
Returns the nearest point that is contained within the rectangle.
Definition: Rectangle2d.h:168
constexpr bool Contains(const Translation2d &point) const
Checks if a point is contained within the rectangle.
Definition: Rectangle2d.h:139
constexpr Rectangle2d TransformBy(const Transform2d &other) const
Transforms the center of the rectangle and returns the new rectangle.
Definition: Rectangle2d.h:93
constexpr bool operator==(const Rectangle2d &other) const
Checks equality between this Rectangle2d and another object.
Definition: Rectangle2d.h:195
constexpr Rectangle2d(const Pose2d &center, units::meter_t xWidth, units::meter_t yWidth)
Constructs a rectangle at the specified position with the specified width and height.
Definition: Rectangle2d.h:37
constexpr bool Intersects(const Translation2d &point) const
Checks if a point is intersected by the rectangle's perimeter.
Definition: Rectangle2d.h:113
constexpr units::meter_t Distance(const Translation2d &point) const
Returns the distance between the perimeter of the rectangle and the point.
Definition: Rectangle2d.h:157
constexpr Rectangle2d RotateBy(const Rotation2d &other) const
Rotates the center of the rectangle and returns the new rectangle.
Definition: Rectangle2d.h:103
constexpr Rectangle2d(const Translation2d &cornerA, const Translation2d &cornerB)
Creates an unrotated rectangle from the given corners.
Definition: Rectangle2d.h:53
constexpr const Pose2d & Center() const
Returns the center of the rectangle.
Definition: Rectangle2d.h:64
constexpr units::meter_t XWidth() const
Returns the x size component of the rectangle.
Definition: Rectangle2d.h:78
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Represents a transformation for a Pose2d in the pose's frame.
Definition: Transform2d.h:18
Represents a translation in 2D space.
Definition: Translation2d.h:28
constexpr Translation2d RotateAround(const Translation2d &other, const Rotation2d &rot) const
Rotates this translation around another translation in 2D space.
Definition: Translation2d.inc:33
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:79
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition: Translation2d.inc:28
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition: math.h:726
Definition: AprilTagDetector_cv.h:11
Unit Conversion Library namespace.
Definition: temperature.h:31