Rectangle2d
- class wpimath.Rectangle2d(*args, **kwargs)
Bases:
pybind11_objectRepresents a 2d rectangular space containing translational, rotational, and scaling components.
Overloaded function.
__init__(self: wpimath._wpimath.Rectangle2d, center: wpimath._wpimath.Pose2d, xWidth: wpimath.units.meters, yWidth: wpimath.units.meters) -> None
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.
__init__(self: wpimath._wpimath.Rectangle2d, cornerA: wpimath._wpimath.Translation2d, cornerB: wpimath._wpimath.Translation2d) -> None
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.
- WPIStruct = <capsule object "WPyStruct">
- center() wpimath._wpimath.Pose2d
Returns the center of the rectangle.
- Returns:
The center of the rectangle.
- contains(point: wpimath._wpimath.Translation2d) bool
Checks if a point is contained within the rectangle. This is inclusive, if the point lies on the perimeter it will return true.
- Parameters:
point – The point to check.
- Returns:
True, if the rectangle contains the point or the perimeter intersects the point.
- distance(point: wpimath._wpimath.Translation2d) wpimath.units.meters
Returns the distance between the perimeter of the rectangle and the point.
- Parameters:
point – The point to check.
- Returns:
The distance (0, if the point is contained by the rectangle)
- static fromFeet(center: wpimath._wpimath.Pose2d, xWidth: wpimath.units.feet, yWidth: wpimath.units.feet) wpimath._wpimath.Rectangle2d
- intersects(point: wpimath._wpimath.Translation2d) bool
Checks if a point is intersected by the rectangle’s perimeter.
- Parameters:
point – The point to check.
- Returns:
True, if the rectangle’s perimeter intersects the point.
- nearest(point: wpimath._wpimath.Translation2d) wpimath._wpimath.Translation2d
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
pointand contained in the rectangle.
- rotateBy(other: wpimath._wpimath.Rotation2d) wpimath._wpimath.Rectangle2d
Rotates the center of the rectangle and returns the new rectangle.
- Parameters:
other – The rotation to transform by.
- Returns:
The rotated rectangle.
- rotation() wpimath._wpimath.Rotation2d
Returns the rotational component of the rectangle.
- Returns:
The rotational component of the rectangle.
- transformBy(other: wpimath._wpimath.Transform2d) wpimath._wpimath.Rectangle2d
Transforms the center of the rectangle and returns the new rectangle.
- Parameters:
other – The transform to transform by.
- Returns:
The transformed rectangle
- property xwidth
- property xwidth_feet
- property ywidth
- property ywidth_feet