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