Package edu.wpi.first.math.geometry
Class Ellipse2d
java.lang.Object
edu.wpi.first.math.geometry.Ellipse2d
- All Implemented Interfaces:
ProtobufSerializable
,StructSerializable
,WPISerializable
Represents a 2d ellipse space containing translational, rotational, and scaling components.
-
Field Summary
Modifier and TypeFieldDescriptionstatic final Ellipse2dProto
Ellipse2d protobuf for serialization.static final Ellipse2dStruct
Ellipse2d struct for serialization. -
Constructor Summary
ConstructorDescriptionConstructs an ellipse around a center point and two semi-axes, a horizontal and vertical one.Constructs an ellipse around a center point and two semi-axes, a horizontal and vertical one.Ellipse2d
(Translation2d center, double radius) Constructs a perfectly circular ellipse with the specified radius.Ellipse2d
(Translation2d center, Distance radius) Constructs a perfectly circular ellipse with the specified radius. -
Method Summary
Modifier and TypeMethodDescriptionboolean
contains
(Translation2d point) Checks if a point is contained within this ellipse.boolean
Checks equality between this Ellipse2d and another object.Returns the center of the ellipse.double
getDistance
(Translation2d point) Returns the distance between the perimeter of the ellipse and the point.Returns the focal points of the ellipse.getMeasureDistance
(Translation2d point) Returns the distance between the perimeter of the ellipse and the point in a measure.Returns the x semi-axis in a measure.Returns the y semi-axis in a measure.Returns the rotational component of the ellipse.double
Returns the x semi-axis.double
Returns the y semi-axis.int
hashCode()
boolean
intersects
(Translation2d point) Checks if a point is intersected by this ellipse's circumference.nearest
(Translation2d point) Returns the nearest point that is contained within the ellipse.rotateBy
(Rotation2d other) Rotates the center of the ellipse and returns the new ellipse.toString()
transformBy
(Transform2d other) Transforms the center of the ellipse and returns the new ellipse.
-
Field Details
-
proto
Ellipse2d protobuf for serialization. -
struct
Ellipse2d struct for serialization.
-
-
Constructor Details
-
Ellipse2d
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
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
Constructs a perfectly circular ellipse with the specified radius.- Parameters:
center
- The center of the circle.radius
- The radius of the circle.
-
Ellipse2d
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
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
Returns the x semi-axis.- Returns:
- The x semi-axis.
-
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
Rotates the center of the ellipse and returns the new ellipse.- Parameters:
other
- The rotation to transform by.- Returns:
- The rotated ellipse.
-
intersects
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
Checks if a point is contained within this ellipse. This is inclusive, if the point lies on the circumference this will returntrue
.- Parameters:
point
- The point to check.- Returns:
- True, if the point is within or on the ellipse.
-
getDistance
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
-
equals
Checks equality between this Ellipse2d and another object. -
hashCode
-