Class Ellipse2d

java.lang.Object
edu.wpi.first.math.geometry.Ellipse2d
All Implemented Interfaces:
ProtobufSerializable, StructSerializable, WPISerializable

public class Ellipse2d extends Object implements ProtobufSerializable, StructSerializable
Represents a 2d ellipse space containing translational, rotational, and scaling components.
  • Field Details

  • Constructor Details

    • Ellipse2d

      public Ellipse2d(Pose2d center, double xSemiAxis, double ySemiAxis)
      Constructs an ellipse around a center point and two semi-axes, a horizontal and vertical one.
      Parameters:
      center - The center of the ellipse.
      xSemiAxis - The x semi-axis.
      ySemiAxis - The y semi-axis.
    • Ellipse2d

      public Ellipse2d(Pose2d center, Distance xSemiAxis, Distance ySemiAxis)
      Constructs an ellipse around a center point and two semi-axes, a horizontal and vertical one. The X and Y semi-axis will be converted to and tracked as meters.
      Parameters:
      center - The center of the ellipse.
      xSemiAxis - The x semi-axis.
      ySemiAxis - The y semi-axis.
    • Ellipse2d

      public Ellipse2d(Translation2d center, double radius)
      Constructs a perfectly circular ellipse with the specified radius.
      Parameters:
      center - The center of the circle.
      radius - The radius of the circle.
    • Ellipse2d

      public Ellipse2d(Translation2d center, Distance radius)
      Constructs a perfectly circular ellipse with the specified radius. The radius will be converted to and tracked as meters.
      Parameters:
      center - The center of the circle.
      radius - The radius of the circle.
  • Method Details

    • getCenter

      public Pose2d getCenter()
      Returns the center of the ellipse.
      Returns:
      The center of the ellipse.
    • getRotation

      Returns the rotational component of the ellipse.
      Returns:
      The rotational component of the ellipse.
    • getXSemiAxis

      public double getXSemiAxis()
      Returns the x semi-axis.
      Returns:
      The x semi-axis.
    • getYSemiAxis

      public double getYSemiAxis()
      Returns the y semi-axis.
      Returns:
      The y semi-axis.
    • getMeasureXSemiAxis

      Returns the x semi-axis in a measure.
      Returns:
      The x semi-axis in a measure.
    • getMeasureYSemiAxis

      Returns the y semi-axis in a measure.
      Returns:
      The y semi-axis in a measure.
    • getFocalPoints

      Returns the focal points of the ellipse. In a perfect circle, this will always return the center.
      Returns:
      The focal points.
    • transformBy

      Transforms the center of the ellipse and returns the new ellipse.
      Parameters:
      other - The transform to transform by.
      Returns:
      The transformed ellipse.
    • rotateBy

      public Ellipse2d rotateBy(Rotation2d other)
      Rotates the center of the ellipse and returns the new ellipse.
      Parameters:
      other - The rotation to transform by.
      Returns:
      The rotated ellipse.
    • intersects

      public boolean intersects(Translation2d point)
      Checks if a point is intersected by this ellipse's circumference.
      Parameters:
      point - The point to check.
      Returns:
      True, if this ellipse's circumference intersects the point.
    • contains

      public boolean contains(Translation2d point)
      Checks if a point is contained within this ellipse. This is inclusive, if the point lies on the circumference this will return true.
      Parameters:
      point - The point to check.
      Returns:
      True, if the point is within or on the ellipse.
    • getDistance

      public double getDistance(Translation2d point)
      Returns the distance between the perimeter of the ellipse and the point.
      Parameters:
      point - The point to check.
      Returns:
      The distance (0, if the point is contained by the ellipse)
    • getMeasureDistance

      Returns the distance between the perimeter of the ellipse and the point in a measure.
      Parameters:
      point - The point to check.
      Returns:
      The distance (0, if the point is contained by the ellipse) in a measure.
    • nearest

      Returns the nearest point that is contained within the ellipse.
      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 ellipse.
    • toString

      public String toString()
      Overrides:
      toString in class Object
    • equals

      public boolean equals(Object obj)
      Checks equality between this Ellipse2d and another object.
      Overrides:
      equals in class Object
      Parameters:
      obj - The other object.
      Returns:
      Whether the two objects are equal or not.
    • hashCode

      public int hashCode()
      Overrides:
      hashCode in class Object