Package com.flarerobotics.lib.region
Class PolygonalRegion
java.lang.Object
com.flarerobotics.lib.region.PolygonalRegion
A polygonal region on the field. Used for dividing the field into smaller sections.
The vertices must be specified in (either CW or CCW) order, and the polygon must be
non-self-intersecting.
-
Constructor Summary
ConstructorsConstructorDescriptionPolygonalRegion
(List<edu.wpi.first.math.geometry.Translation2d> vertices) Constructs a new PolygonalRegion. -
Method Summary
Modifier and TypeMethodDescriptionboolean
collidesWith
(PolygonalRegion other) Test whether this polygon collides (overlaps) with another polygon.boolean
containsPoint
(edu.wpi.first.math.geometry.Translation2d point) Returns whether the given 2D point lies within this polygon (including boundary).List<edu.wpi.first.math.geometry.Translation2d>
Returns the list of vertices in order.boolean
isPoseWithinArea
(edu.wpi.first.math.geometry.Pose2d pose) Returns whether the given pose (x, y) lies within this polygon.
-
Constructor Details
-
PolygonalRegion
Constructs a new PolygonalRegion.- Parameters:
vertices
- The ordered list of corner points (A, B, C, ...). Must form a simple (non-self-intersecting) polygon.
-
-
Method Details
-
getVertices
Returns the list of vertices in order.- Returns:
- A list of Translation2d corners.
-
isPoseWithinArea
public boolean isPoseWithinArea(edu.wpi.first.math.geometry.Pose2d pose) Returns whether the given pose (x, y) lies within this polygon.- Parameters:
pose
- The pose to check.- Returns:
- True if the pose's (x, y) is inside or on the boundary.
-
containsPoint
public boolean containsPoint(edu.wpi.first.math.geometry.Translation2d point) Returns whether the given 2D point lies within this polygon (including boundary). Uses the ray-casting (crossing-number) algorithm.- Parameters:
point
- The point to test.- Returns:
- True if the point is inside or on an edge.
-
collidesWith
Test whether this polygon collides (overlaps) with another polygon.- Parameters:
other
- The other PolygonalRegion to test against.- Returns:
- True if they overlap at all.
-