Package me.nabdev.pathfinding.structures
Class Obstacle
java.lang.Object
me.nabdev.pathfinding.structures.Obstacle
Represents an obstacle on the map. An obstacle is a collection of vertices
and edges.
-
Field Summary
FieldsModifier and TypeFieldDescriptionThe id of the obstacle.The modifiers on this obstacle. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionCalculates the nearest point on the obstacle to the given vertex.Calculates the nearest point on the obstacle to the given vertex, assuming the given vertex is inside the obstaclestatic Obstacle
createObstacle
(Vertex... vertices) Create and initializes a new obstacle from the given vertices with the AlWAYS_ACTIVE modifier.getEdges()
Get all edges in this obstacle.Get all vertices this obstacle knows about.Get all vertices in this obstacle.void
initialize
(ArrayList<Vertex> vertices) Re-initializes the obstacle.boolean
Checks if the obstacle is convex and clockwise, used to validate the map.boolean
Checks if the given vertex is inside the obstacle.isRobotInObstacle
(ArrayList<Obstacle> obstacles, Vertex vertex) Detect if a vertex is inside any obstacle in the list.isRobotInObstacle
(ArrayList<Obstacle> obstacles, Vertex vertex, boolean notZone) Detect if a vertex is inside any obstacle in the list.
-
Field Details
-
id
The id of the obstacle. This will be used to add special behavior to obstacles which may only be used in certain situations. -
modifiers
The modifiers on this obstacle.
-
-
Constructor Details
-
Obstacle
public Obstacle(ArrayList<Vertex> vertices, ArrayList<Edge> edges, String id, ModifierCollection modifiers) Creates a new obstacle.- Parameters:
vertices
- All vertices on the map.edges
- The edges that make up the obstacle.id
- The id of the obstacle.modifiers
- The modifiers on this obstacle.
-
Obstacle
Creates a new obstacle with the always active modifier.- Parameters:
vertices
- All vertices on the map.edges
- The edges that make up the obstacle.id
- The id of the obstacle.
-
-
Method Details
-
initialize
Re-initializes the obstacle. This is used when the vertices are updated (usually via inflation)- Parameters:
vertices
- The new vertices.
-
isRobotInObstacle
Detect if a vertex is inside any obstacle in the list.- Parameters:
obstacles
- The list of obstacles to check.vertex
- The vertex to check.- Returns:
- The list of obstacles that the vertex is inside, empty if none.
-
isRobotInObstacle
public static ArrayList<Obstacle> isRobotInObstacle(ArrayList<Obstacle> obstacles, Vertex vertex, boolean notZone) Detect if a vertex is inside any obstacle in the list.- Parameters:
obstacles
- The list of obstacles to check.vertex
- The vertex to check.notZone
- If true, ignores obstacles with the zone modifier.- Returns:
- The list of obstacles that the vertex is inside, empty if none.
-
isInside
Checks if the given vertex is inside the obstacle.- Parameters:
pos
- The vertex to check.- Returns:
- True if the vertex is inside the obstacle, false otherwise.
-
calculateNearestPointFromInside
Calculates the nearest point on the obstacle to the given vertex, assuming the given vertex is inside the obstacle- Parameters:
v
- The vertex to calculate the nearest point to.- Returns:
- The nearest point on the obstacle to the given vertex.
-
calculateNearestPoint
Calculates the nearest point on the obstacle to the given vertex.- Parameters:
v
- The vertex to calculate the nearest point to.- Returns:
- The nearest point on the obstacle to the given vertex.
-
isConvexAndClockwise
public boolean isConvexAndClockwise()Checks if the obstacle is convex and clockwise, used to validate the map.- Returns:
- True if the obstacle is convex and clockwise, false otherwise.
-
createObstacle
Create and initializes a new obstacle from the given vertices with the AlWAYS_ACTIVE modifier. Generates the edge table automatically.- Parameters:
vertices
- The list of vertices in the obstacle.- Returns:
- The new obstacle.
-
getMasterVertices
Get all vertices this obstacle knows about. (The entire field, if it is a field obstacle)- Returns:
- The master list of vertices.
-
getVertices
Get all vertices in this obstacle.- Returns:
- The list of vertices.
-
getEdges
Get all edges in this obstacle.- Returns:
- The list of edges.
-