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!");
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())} {}
78 constexpr units::meter_t
XWidth()
const {
return m_xWidth; }
85 constexpr units::meter_t
YWidth()
const {
return m_yWidth; }
94 return Rectangle2d{m_center.TransformBy(other), m_xWidth, m_yWidth};
104 return Rectangle2d{m_center.RotateBy(other), m_xWidth, m_yWidth};
115 auto pointInRect = point - m_center.Translation();
116 pointInRect = pointInRect.
RotateBy(-m_center.Rotation());
123 m_yWidth / 2.0) <= 1E-9_m) {
142 point.
RotateAround(m_center.Translation(), -m_center.Rotation());
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);
158 return Nearest(point).Distance(point);
170 if (Contains(point)) {
176 point.
RotateAround(m_center.Translation(), -m_center.Rotation());
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)};
186 return rotPoint.
RotateAround(m_center.Translation(), m_center.Rotation());
196 return m_center == other.m_center &&
203 units::meter_t m_xWidth;
204 units::meter_t m_yWidth;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
Represents a 2d rectangular space containing translational, rotational, and scaling components.
Definition Rectangle2d.h:25
constexpr Translation2d Nearest(const Translation2d &point) const
Returns the nearest point that is contained within the rectangle.
Definition Rectangle2d.h:168
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 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 ¢er, 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:31
Represents a translation in 2D space.
Definition Translation2d.h:29
constexpr Translation2d RotateAround(const Translation2d &other, const Rotation2d &rot) const
Rotates this translation around another translation in 2D space.
Definition Translation2d.h:152
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.h:83
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition Translation2d.h:135
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
Unit Conversion Library namespace.
Definition acceleration.h:33