14#include "wpi/units/length.hpp"
15#include "wpi/units/math.hpp"
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!");
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())} {}
77 constexpr wpi::units::meter_t
XWidth()
const {
return m_xWidth; }
84 constexpr wpi::units::meter_t
YWidth()
const {
return m_yWidth; }
93 return Rectangle2d{m_center.TransformBy(other), m_xWidth, m_yWidth};
103 return Rectangle2d{m_center.RotateBy(other), m_xWidth, m_yWidth};
114 auto pointInRect = point - m_center.Translation();
115 pointInRect = pointInRect.
RotateBy(-m_center.Rotation());
117 if (wpi::units::math::abs(wpi::units::math::abs(pointInRect.X()) -
118 m_xWidth / 2.0) <= 1E-9_m) {
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) {
124 return wpi::units::math::abs(pointInRect.X()) <= m_xWidth / 2.0;
141 point.
RotateAround(m_center.Translation(), -m_center.Rotation());
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);
157 return Nearest(point).Distance(point);
175 point.
RotateAround(m_center.Translation(), -m_center.Rotation());
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)};
185 return rotPoint.
RotateAround(m_center.Translation(), m_center.Rotation());
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;
202 wpi::units::meter_t m_xWidth;
203 wpi::units::meter_t m_yWidth;
#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 ¢er, 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 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