WPILibC++ 2025.0.0-alpha-1-10-g1ccd8d1
frc::Rectangle2d Class Reference

Represents a 2d rectangular space containing translational, rotational, and scaling components. More...

#include <frc/geometry/Rectangle2d.h>

Public Member Functions

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. More...
 
constexpr Rectangle2d (const Translation2d &cornerA, const Translation2d &cornerB)
 Creates an unrotated rectangle from the given corners. More...
 
constexpr const Pose2dCenter () const
 Returns the center of the rectangle. More...
 
constexpr const Rotation2dRotation () const
 Returns the rotational component of the rectangle. More...
 
constexpr units::meter_t XWidth () const
 Returns the x size component of the rectangle. More...
 
constexpr units::meter_t YWidth () const
 Returns the y size component of the rectangle. More...
 
constexpr Rectangle2d TransformBy (const Transform2d &other) const
 Transforms the center of the rectangle and returns the new rectangle. More...
 
constexpr Rectangle2d RotateBy (const Rotation2d &other) const
 Rotates the center of the rectangle and returns the new rectangle. More...
 
constexpr bool Intersects (const Translation2d &point) const
 Checks if a point is intersected by the rectangle's perimeter. More...
 
constexpr bool Contains (const Translation2d &point) const
 Checks if a point is contained within the rectangle. More...
 
constexpr units::meter_t Distance (const Translation2d &point) const
 Returns the distance between the perimeter of the rectangle and the point. More...
 
constexpr Translation2d FindNearestPoint (const Translation2d &point) const
 Returns the nearest point that is contained within the rectangle. More...
 
constexpr bool operator== (const Rectangle2d &other) const
 Checks equality between this Rectangle2d and another object. More...
 

Detailed Description

Represents a 2d rectangular space containing translational, rotational, and scaling components.

Constructor & Destructor Documentation

◆ Rectangle2d() [1/2]

constexpr frc::Rectangle2d::Rectangle2d ( const Pose2d center,
units::meter_t  xWidth,
units::meter_t  yWidth 
)
inlineconstexpr

Constructs a rectangle at the specified position with the specified width and height.

Parameters
centerThe position (translation and rotation) of the rectangle.
xWidthThe x size component of the rectangle, in unrotated coordinate frame.
yWidthThe y size component of the rectangle, in unrotated coordinate frame.

◆ Rectangle2d() [2/2]

constexpr frc::Rectangle2d::Rectangle2d ( const Translation2d cornerA,
const Translation2d cornerB 
)
inlineconstexpr

Creates an unrotated rectangle from the given corners.

The corners should be diagonally opposite of each other.

Parameters
cornerAThe first corner of the rectangle.
cornerBThe second corner of the rectangle.

Member Function Documentation

◆ Center()

constexpr const Pose2d & frc::Rectangle2d::Center ( ) const
inlineconstexpr

Returns the center of the rectangle.

Returns
The center of the rectangle.

◆ Contains()

constexpr bool frc::Rectangle2d::Contains ( const Translation2d point) const
inlineconstexpr

Checks if a point is contained within the rectangle.

This is inclusive, if the point lies on the perimeter it will return true.

Parameters
pointThe point to check.
Returns
True, if the rectangle contains the point or the perimeter intersects the point.

◆ Distance()

constexpr units::meter_t frc::Rectangle2d::Distance ( const Translation2d point) const
inlineconstexpr

Returns the distance between the perimeter of the rectangle and the point.

Parameters
pointThe point to check.
Returns
The distance (0, if the point is contained by the rectangle)

◆ FindNearestPoint()

constexpr Translation2d frc::Rectangle2d::FindNearestPoint ( const Translation2d point) const
inlineconstexpr

Returns the nearest point that is contained within the rectangle.

Parameters
pointThe point that this will find the nearest point to.
Returns
A new point that is nearest to point and contained in the rectangle.

◆ Intersects()

constexpr bool frc::Rectangle2d::Intersects ( const Translation2d point) const
inlineconstexpr

Checks if a point is intersected by the rectangle's perimeter.

Parameters
pointThe point to check.
Returns
True, if the rectangle's perimeter intersects the point.

◆ operator==()

constexpr bool frc::Rectangle2d::operator== ( const Rectangle2d other) const
inlineconstexpr

Checks equality between this Rectangle2d and another object.

Parameters
otherThe other object.
Returns
Whether the two objects are equal.

◆ RotateBy()

constexpr Rectangle2d frc::Rectangle2d::RotateBy ( const Rotation2d other) const
inlineconstexpr

Rotates the center of the rectangle and returns the new rectangle.

Parameters
otherThe rotation to transform by.
Returns
The rotated rectangle.

◆ Rotation()

constexpr const Rotation2d & frc::Rectangle2d::Rotation ( ) const
inlineconstexpr

Returns the rotational component of the rectangle.

Returns
The rotational component of the rectangle.

◆ TransformBy()

constexpr Rectangle2d frc::Rectangle2d::TransformBy ( const Transform2d other) const
inlineconstexpr

Transforms the center of the rectangle and returns the new rectangle.

Parameters
otherThe transform to transform by.
Returns
The transformed rectangle

◆ XWidth()

constexpr units::meter_t frc::Rectangle2d::XWidth ( ) const
inlineconstexpr

Returns the x size component of the rectangle.

Returns
The x size component of the rectangle.

◆ YWidth()

constexpr units::meter_t frc::Rectangle2d::YWidth ( ) const
inlineconstexpr

Returns the y size component of the rectangle.

Returns
The y size component of the rectangle.

The documentation for this class was generated from the following file: