Package edu.wpi.first.math.geometry
Class Rectangle2d
java.lang.Object
edu.wpi.first.math.geometry.Rectangle2d
- All Implemented Interfaces:
ProtobufSerializable
,StructSerializable
,WPISerializable
Represents a 2d rectangular space containing translational, rotational, and scaling components.
-
Field Summary
Modifier and TypeFieldDescriptionstatic final Rectangle2dProto
Rectangle2d protobuf for serialization.static final Rectangle2dStruct
Rectangle2d struct for serialization. -
Constructor Summary
ConstructorDescriptionRectangle2d
(Pose2d center, double xWidth, double yWidth) Constructs a rectangle at the specified position with the specified width and height.Rectangle2d
(Pose2d center, Distance xWidth, Distance yWidth) Constructs a rectangle at the specified position with the specified width and height.Rectangle2d
(Translation2d cornerA, Translation2d cornerB) Creates an unrotated rectangle from the given corners. -
Method Summary
Modifier and TypeMethodDescriptionboolean
contains
(Translation2d point) Checks if a point is contained within the rectangle.boolean
Checks equality between this Rectangle2d and another object.Returns the center of the rectangle.double
getDistance
(Translation2d point) Returns the distance between the perimeter of the rectangle and the point.getMeasureDistance
(Translation2d point) Returns the distance between the perimeter of the rectangle and the point in a measure.Returns the X size component of the rectangle in a measure.Returns the Y size component of the rectangle in a measure.Returns the rotational component of the rectangle.double
Returns the x size component of the rectangle.double
Returns the y size component of the rectangle.int
hashCode()
boolean
intersects
(Translation2d point) Checks if a point is intersected by the rectangle's perimeter.nearest
(Translation2d point) Returns the nearest point that is contained within the rectangle.rotateBy
(Rotation2d other) Rotates the center of the rectangle and returns the new rectangle.toString()
transformBy
(Transform2d other) Transforms the center of the rectangle and returns the new rectangle.
-
Field Details
-
proto
Rectangle2d protobuf for serialization. -
struct
Rectangle2d struct for serialization.
-
-
Constructor Details
-
Rectangle2d
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
Constructs a rectangle at the specified position with the specified width and height. The X and Y widths will be converted to and tracked as meters.- 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
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.
-
-
Method Details
-
getCenter
Returns the center of the rectangle.- Returns:
- The center of the rectangle.
-
getRotation
Returns the rotational component of the rectangle.- Returns:
- The rotational component of the rectangle.
-
getXWidth
Returns the x size component of the rectangle.- Returns:
- The x size component of the rectangle.
-
getYWidth
Returns the y size component of the rectangle.- Returns:
- The y size component of the rectangle.
-
getMeasureXWidth
Returns the X size component of the rectangle in a measure.- Returns:
- The x size component of the rectangle in a measure.
-
getMeasureYWidth
Returns the Y size component of the rectangle in a measure.- Returns:
- The y size component of the rectangle in a measure.
-
transformBy
Transforms the center of the rectangle and returns the new rectangle.- Parameters:
other
- The transform to transform by.- Returns:
- The transformed rectangle
-
rotateBy
Rotates the center of the rectangle and returns the new rectangle.- Parameters:
other
- The rotation to transform by.- Returns:
- The rotated rectangle.
-
intersects
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.
-
contains
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.
-
getDistance
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)
-
getMeasureDistance
Returns the distance between the perimeter of the rectangle and the point in a measure.- Parameters:
point
- The point to check.- Returns:
- The distance (0, if the point is contained by the rectangle) in a measure.
-
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.
-
toString
-
equals
Checks equality between this Rectangle2d and another object. -
hashCode
-