Represents a 2d rectangular space containing translational, rotational, and scaling components.
More...
#include <frc/geometry/Rectangle2d.h>
|
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.
|
|
constexpr | Rectangle2d (const Translation2d &cornerA, const Translation2d &cornerB) |
| Creates an unrotated rectangle from the given corners.
|
|
constexpr const Pose2d & | Center () const |
| Returns the center of the rectangle.
|
|
constexpr const Rotation2d & | Rotation () const |
| Returns the rotational component of the rectangle.
|
|
constexpr units::meter_t | XWidth () const |
| Returns the x size component of the rectangle.
|
|
constexpr units::meter_t | YWidth () const |
| Returns the y size component of the rectangle.
|
|
constexpr Rectangle2d | TransformBy (const Transform2d &other) const |
| Transforms the center of the rectangle and returns the new rectangle.
|
|
constexpr Rectangle2d | RotateBy (const Rotation2d &other) const |
| Rotates the center of the rectangle and returns the new rectangle.
|
|
constexpr bool | Intersects (const Translation2d &point) const |
| Checks if a point is intersected by the rectangle's perimeter.
|
|
constexpr bool | Contains (const Translation2d &point) const |
| Checks if a point is contained within the rectangle.
|
|
constexpr units::meter_t | Distance (const Translation2d &point) const |
| Returns the distance between the perimeter of the rectangle and the point.
|
|
constexpr Translation2d | Nearest (const Translation2d &point) const |
| Returns the nearest point that is contained within the rectangle.
|
|
constexpr bool | operator== (const Rectangle2d &other) const |
| Checks equality between this Rectangle2d and another object.
|
|
Represents a 2d rectangular space containing translational, rotational, and scaling components.
◆ Rectangle2d() [1/2]
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
-
center | The position (translation and rotation) of the rectangle. |
xWidth | The x size component of the rectangle, in unrotated coordinate frame. |
yWidth | The y size component of the rectangle, in unrotated coordinate frame. |
◆ Rectangle2d() [2/2]
Creates an unrotated rectangle from the given corners.
The corners should be diagonally opposite of each other.
- Parameters
-
cornerA | The first corner of the rectangle. |
cornerB | The second corner of the rectangle. |
◆ Center()
const Pose2d & frc::Rectangle2d::Center |
( |
| ) |
const |
|
inlineconstexpr |
Returns the center of the rectangle.
- Returns
- The center of the rectangle.
◆ Contains()
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
-
- Returns
- True, if the rectangle contains the point or the perimeter intersects the point.
◆ Distance()
units::meter_t frc::Rectangle2d::Distance |
( |
const Translation2d & | point | ) |
const |
|
inlineconstexpr |
Returns the distance between the perimeter of the rectangle and the point.
- Parameters
-
- Returns
- The distance (0, if the point is contained by the rectangle)
◆ Intersects()
bool frc::Rectangle2d::Intersects |
( |
const Translation2d & | point | ) |
const |
|
inlineconstexpr |
Checks if a point is intersected by the rectangle's perimeter.
- Parameters
-
- Returns
- True, if the rectangle's perimeter intersects the point.
◆ Nearest()
Returns the nearest point that is contained within the rectangle.
- Parameters
-
point | The point that this will find the nearest point to. |
- Returns
- A new point that is nearest to
point
and contained in the rectangle.
◆ operator==()
bool frc::Rectangle2d::operator== |
( |
const Rectangle2d & | other | ) |
const |
|
inlineconstexpr |
Checks equality between this Rectangle2d and another object.
- Parameters
-
- Returns
- Whether the two objects are equal.
◆ RotateBy()
Rotates the center of the rectangle and returns the new rectangle.
- Parameters
-
other | The rotation to transform by. |
- Returns
- The rotated rectangle.
◆ Rotation()
const Rotation2d & frc::Rectangle2d::Rotation |
( |
| ) |
const |
|
inlineconstexpr |
Returns the rotational component of the rectangle.
- Returns
- The rotational component of the rectangle.
◆ TransformBy()
Transforms the center of the rectangle and returns the new rectangle.
- Parameters
-
other | The transform to transform by. |
- Returns
- The transformed rectangle
◆ XWidth()
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()
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: