Ellipse2d
- class wpimath.Ellipse2d(*args, **kwargs)
Bases:
pybind11_objectRepresents a 2d ellipse space containing translational, rotational, and scaling components.
Overloaded function.
__init__(self: wpimath._wpimath.Ellipse2d, center: wpimath._wpimath.Pose2d, xSemiAxis: wpimath.units.meters, ySemiAxis: wpimath.units.meters) -> None
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.
__init__(self: wpimath._wpimath.Ellipse2d, center: wpimath._wpimath.Translation2d, radius: typing.SupportsFloat | typing.SupportsIndex) -> None
Constructs a perfectly circular ellipse with the specified radius.
- Parameters:
center – The center of the circle.
radius – The radius of the circle.
- WPIStruct = <capsule object "WPyStruct">
- center() wpimath._wpimath.Pose2d
Returns the center of the ellipse.
- Returns:
The center of the ellipse.
- contains(point: wpimath._wpimath.Translation2d) bool
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.
- distance(point: wpimath._wpimath.Translation2d) wpimath.units.meters
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)
- focalPoints() Tuple[wpimath._wpimath.Translation2d, wpimath._wpimath.Translation2d]
Returns the focal points of the ellipse. In a perfect circle, this will always return the center.
- Returns:
The focal points.
- static fromFeet(center: wpimath._wpimath.Pose2d, xSemiAxis: wpimath.units.feet, ySemiAxis: wpimath.units.feet) wpimath._wpimath.Ellipse2d
- intersects(point: wpimath._wpimath.Translation2d) bool
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.
- nearest(point: wpimath._wpimath.Translation2d) wpimath._wpimath.Translation2d
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
pointand contained in the ellipse.
- rotateBy(other: wpimath._wpimath.Rotation2d) wpimath._wpimath.Ellipse2d
Rotates the center of the ellipse and returns the new ellipse.
- Parameters:
other – The rotation to transform by.
- Returns:
The rotated ellipse.
- rotation() wpimath._wpimath.Rotation2d
Returns the rotational component of the ellipse.
- Returns:
The rotational component of the ellipse.
- transformBy(other: wpimath._wpimath.Transform2d) wpimath._wpimath.Ellipse2d
Transforms the center of the ellipse and returns the new ellipse.
- Parameters:
other – The transform to transform by.
- Returns:
The transformed ellipse.
- property xsemiaxis
- property xsemiaxis_feet
- property ysemiaxis
- property ysemiaxis_feet