Class Vertex

java.lang.Object
me.nabdev.pathfinding.structures.Vertex
All Implemented Interfaces:
Comparable<Vertex>

public class Vertex extends Object implements Comparable<Vertex>
Represents a point in 2D space
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    Used with A*.
    All of the dynamic neighbors of this vertex in the visibility graph
    double
    Used with A*.
    double
    Used with A*.
    edu.wpi.first.math.geometry.Rotation2d
    The rotation of the vertex
    All of the static neighbors of this vertex in the visibility graph
    boolean
    This will be set to false if the point is inside of an obstacle or outside of the field bounds, since the robot could never be there.
    double
    The x coordinate of the vertex
    double
    The y coordinate of the vertex
  • Constructor Summary

    Constructors
    Constructor
    Description
    Vertex(double _x, double _y)
    Creates a new Vertex from an x and y coordinate, initialized with a rotation of 0
    Vertex(double _x, double _y, double rot)
    Creates a new Vertex from an x and y coordinate and a rotation
    Vertex(double _x, double _y, edu.wpi.first.math.geometry.Rotation2d rot)
    Creates a new Vertex from an x and y coordinate and a rotation
    Vertex(edu.wpi.first.math.geometry.Pose2d pose)
    Creates a new Vertex from a Pose2d
    Vertex(edu.wpi.first.math.geometry.Translation2d translation)
    Creates a new Vertex from a Translation2d with a rotation of 0
    Vertex(edu.wpi.first.math.geometry.Translation2d translation, double rot)
    Creates a new Vertex from a Translation2d with a rotation of 0
    Vertex(edu.wpi.first.math.geometry.Translation2d translation, edu.wpi.first.math.geometry.Rotation2d rot)
    Creates a new Vertex from a Translation2d with a rotation of 0
  • Method Summary

    Modifier and Type
    Method
    Description
    add(Vertex v2)
    Add a vertex to this vertex
    edu.wpi.first.math.geometry.Pose2d
    Get a pose2d representation of the current Vertex
    average(Vertex vertex)
    Average this vertex with another vertex
    int
     
    Create a vector to this vertex from a starting vertex
    Create a vector from this vertex to an ending vertex
    double
    distance(edu.wpi.first.math.geometry.Pose2d target)
    Get the euclidian distance between this vertex and a pose (Pythagorean theorem)
    double
    distance(Vertex target)
    Get the euclidian distance between this vertex and another vertex (Pythagorean theorem)
    boolean
    Check if this vertex represents the same spot as another vertex
    double
    F()
    Used with A*.
    fromPose2dArray(ArrayList<edu.wpi.first.math.geometry.Pose2d> poses)
    Converts an array of Pose2ds to an array of Vertices
    Get all of the neighbors of this vertex in the visibility graph
    Move this vertex by a vector (add the vector to the vertex)
    Subtract a vertex from this vertex
    Get a string representation of the vertex

    Methods inherited from class java.lang.Object

    clone, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
  • Field Details

    • x

      public double x
      The x coordinate of the vertex
    • y

      public double y
      The y coordinate of the vertex
    • rotation

      public edu.wpi.first.math.geometry.Rotation2d rotation
      The rotation of the vertex
    • G

      public double G
      Used with A*. The distance from the start vertex to the current vertex along the path
    • H

      public double H
      Used with A*. The distance from the current vertex to the end vertex
    • connection

      public Vertex connection
      Used with A*. The previous vertex in the path, saved so that the path can be traced backwards after reaching the target.
    • staticNeighbors

      public ArrayList<Vertex> staticNeighbors
      All of the static neighbors of this vertex in the visibility graph
    • dynamicNeighbors

      public ArrayList<Vertex> dynamicNeighbors
      All of the dynamic neighbors of this vertex in the visibility graph
    • validVisibility

      public boolean validVisibility
      This will be set to false if the point is inside of an obstacle or outside of the field bounds, since the robot could never be there.
  • Constructor Details

    • Vertex

      public Vertex(edu.wpi.first.math.geometry.Pose2d pose)
      Creates a new Vertex from a Pose2d
      Parameters:
      pose - The Pose2d to create the Vertex from
    • Vertex

      public Vertex(edu.wpi.first.math.geometry.Translation2d translation)
      Creates a new Vertex from a Translation2d with a rotation of 0
      Parameters:
      translation - The Translation2d to create the Vertex from
    • Vertex

      public Vertex(edu.wpi.first.math.geometry.Translation2d translation, double rot)
      Creates a new Vertex from a Translation2d with a rotation of 0
      Parameters:
      translation - The Translation2d to create the Vertex from
      rot - The rotation of the vertex, in degrees
    • Vertex

      public Vertex(edu.wpi.first.math.geometry.Translation2d translation, edu.wpi.first.math.geometry.Rotation2d rot)
      Creates a new Vertex from a Translation2d with a rotation of 0
      Parameters:
      translation - The Translation2d to create the Vertex from
      rot - The rotation of the vertex
    • Vertex

      public Vertex(double _x, double _y)
      Creates a new Vertex from an x and y coordinate, initialized with a rotation of 0
      Parameters:
      _x - The x coordinate of the vertex
      _y - The y coordinate of the vertex
    • Vertex

      public Vertex(double _x, double _y, edu.wpi.first.math.geometry.Rotation2d rot)
      Creates a new Vertex from an x and y coordinate and a rotation
      Parameters:
      _x - The x coordinate of the vertex
      _y - The y coordinate of the vertex
      rot - The rotation of the vertex
    • Vertex

      public Vertex(double _x, double _y, double rot)
      Creates a new Vertex from an x and y coordinate and a rotation
      Parameters:
      _x - The x coordinate of the vertex
      _y - The y coordinate of the vertex
      rot - The rotation of the vertex, in degrees
  • Method Details

    • F

      public double F()
      Used with A*. The sum of G and H
      Returns:
      G + H
    • fromPose2dArray

      public static ArrayList<Vertex> fromPose2dArray(ArrayList<edu.wpi.first.math.geometry.Pose2d> poses)
      Converts an array of Pose2ds to an array of Vertices
      Parameters:
      poses - The array of Pose2ds to convert
      Returns:
      The array of Vertices
    • asPose2d

      public edu.wpi.first.math.geometry.Pose2d asPose2d()
      Get a pose2d representation of the current Vertex
      Returns:
      The current Vertex as a Pose2d
    • getNeighbors

      public ArrayList<Vertex> getNeighbors()
      Get all of the neighbors of this vertex in the visibility graph
      Returns:
      All static and dynamic neighbors
    • createVectorFrom

      public Vector createVectorFrom(Vertex starting)
      Create a vector to this vertex from a starting vertex
      Parameters:
      starting - The starting vertex of the vector
      Returns:
      The vector from the starting vertex to this vertex
    • createVectorTo

      public Vector createVectorTo(Vertex ending)
      Create a vector from this vertex to an ending vertex
      Parameters:
      ending - The ending vertex of the vector
      Returns:
      The vector from this vertex to the ending vertex
    • moveByVector

      public Vertex moveByVector(Vector vector)
      Move this vertex by a vector (add the vector to the vertex)
      Parameters:
      vector - The vector to move the vertex by
      Returns:
      The new vertex after moving
    • average

      public Vertex average(Vertex vertex)
      Average this vertex with another vertex
      Parameters:
      vertex - The vertex to average with
      Returns:
      The position average of the two vertices
    • subtract

      public Vertex subtract(Vertex v2)
      Subtract a vertex from this vertex
      Parameters:
      v2 - The vertex to subtract
      Returns:
      The difference between this vertex and v2
    • add

      public Vertex add(Vertex v2)
      Add a vertex to this vertex
      Parameters:
      v2 - The vertex to add
      Returns:
      The sum of this vertex and v2
    • distance

      public double distance(Vertex target)
      Get the euclidian distance between this vertex and another vertex (Pythagorean theorem)
      Parameters:
      target - The vertex to get the distance to
      Returns:
      The distance between this vertex and target
    • distance

      public double distance(edu.wpi.first.math.geometry.Pose2d target)
      Get the euclidian distance between this vertex and a pose (Pythagorean theorem)
      Parameters:
      target - The pose to get the distance to
      Returns:
      The distance between this vertex and target
    • equals

      public boolean equals(Object o)
      Check if this vertex represents the same spot as another vertex
      Overrides:
      equals in class Object
      Parameters:
      o - The vertex to compare to
      Returns:
      True if the vertices are equal, false otherwise
    • toString

      public String toString()
      Get a string representation of the vertex
      Overrides:
      toString in class Object
      Returns:
      "(x, y)"
    • compareTo

      public int compareTo(Vertex o)
      Specified by:
      compareTo in interface Comparable<Vertex>