WPILibC++ 2025.0.0-alpha-1-10-g1ccd8d1
frc::Ellipse2d Class Reference

Represents a 2d ellipse space containing translational, rotational, and scaling components. More...

#include <frc/geometry/Ellipse2d.h>

Public Member Functions

constexpr Ellipse2d (const Pose2d &center, units::meter_t xSemiAxis, units::meter_t ySemiAxis)
 Constructs an ellipse around a center point and two semi-axes, a horizontal and vertical one. More...
 
constexpr Ellipse2d (const Translation2d &center, double radius)
 Constructs a perfectly circular ellipse with the specified radius. More...
 
constexpr const Pose2dCenter () const
 Returns the center of the ellipse. More...
 
constexpr const Rotation2dRotation () const
 Returns the rotational component of the ellipse. More...
 
constexpr units::meter_t XSemiAxis () const
 Returns the x semi-axis. More...
 
constexpr units::meter_t YSemiAxis () const
 Returns the y semi-axis. More...
 
constexpr wpi::array< Translation2d, 2 > FocalPoints () const
 Returns the focal points of the ellipse. More...
 
constexpr Ellipse2d TransformBy (const Transform2d &other) const
 Transforms the center of the ellipse and returns the new ellipse. More...
 
constexpr Ellipse2d RotateBy (const Rotation2d &other) const
 Rotates the center of the ellipse and returns the new ellipse. More...
 
constexpr bool Intersects (const Translation2d &point) const
 Checks if a point is intersected by this ellipse's circumference. More...
 
constexpr bool Contains (const Translation2d &point) const
 Checks if a point is contained within this ellipse. More...
 
units::meter_t Distance (const Translation2d &point) const
 Returns the distance between the perimeter of the ellipse and the point. More...
 
Translation2d FindNearestPoint (const Translation2d &point) const
 Returns the nearest point that is contained within the ellipse. More...
 
constexpr bool operator== (const Ellipse2d &other) const
 Checks equality between this Ellipse2d and another object. More...
 

Detailed Description

Represents a 2d ellipse space containing translational, rotational, and scaling components.

Constructor & Destructor Documentation

◆ Ellipse2d() [1/2]

constexpr frc::Ellipse2d::Ellipse2d ( const Pose2d center,
units::meter_t  xSemiAxis,
units::meter_t  ySemiAxis 
)
inlineconstexpr

Constructs an ellipse around a center point and two semi-axes, a horizontal and vertical one.

Parameters
centerThe center of the ellipse.
xSemiAxisThe x semi-axis.
ySemiAxisThe y semi-axis.

◆ Ellipse2d() [2/2]

constexpr frc::Ellipse2d::Ellipse2d ( const Translation2d center,
double  radius 
)
inlineconstexpr

Constructs a perfectly circular ellipse with the specified radius.

Parameters
centerThe center of the circle.
radiusThe radius of the circle.

Member Function Documentation

◆ Center()

constexpr const Pose2d & frc::Ellipse2d::Center ( ) const
inlineconstexpr

Returns the center of the ellipse.

Returns
The center of the ellipse.

◆ Contains()

constexpr bool frc::Ellipse2d::Contains ( const Translation2d point) const
inlineconstexpr

Checks if a point is contained within this ellipse.

This is inclusive, if the point lies on the circumference this will return true.

Parameters
pointThe point to check.
Returns
True, if the point is within or on the ellipse.

◆ Distance()

units::meter_t frc::Ellipse2d::Distance ( const Translation2d point) const

Returns the distance between the perimeter of the ellipse and the point.

Parameters
pointThe point to check.
Returns
The distance (0, if the point is contained by the ellipse)

◆ FindNearestPoint()

Translation2d frc::Ellipse2d::FindNearestPoint ( const Translation2d point) const

Returns the nearest point that is contained within the ellipse.

Parameters
pointThe point that this will find the nearest point to.
Returns
A new point that is nearest to point and contained in the ellipse.

◆ FocalPoints()

constexpr wpi::array< Translation2d, 2 > frc::Ellipse2d::FocalPoints ( ) const
inlineconstexpr

Returns the focal points of the ellipse.

In a perfect circle, this will always return the center.

Returns
The focal points.

◆ Intersects()

constexpr bool frc::Ellipse2d::Intersects ( const Translation2d point) const
inlineconstexpr

Checks if a point is intersected by this ellipse's circumference.

Parameters
pointThe point to check.
Returns
True, if this ellipse's circumference intersects the point.

◆ operator==()

constexpr bool frc::Ellipse2d::operator== ( const Ellipse2d other) const
inlineconstexpr

Checks equality between this Ellipse2d and another object.

Parameters
otherThe other object.
Returns
Whether the two objects are equal.

◆ RotateBy()

constexpr Ellipse2d frc::Ellipse2d::RotateBy ( const Rotation2d other) const
inlineconstexpr

Rotates the center of the ellipse and returns the new ellipse.

Parameters
otherThe rotation to transform by.
Returns
The rotated ellipse.

◆ Rotation()

constexpr const Rotation2d & frc::Ellipse2d::Rotation ( ) const
inlineconstexpr

Returns the rotational component of the ellipse.

Returns
The rotational component of the ellipse.

◆ TransformBy()

constexpr Ellipse2d frc::Ellipse2d::TransformBy ( const Transform2d other) const
inlineconstexpr

Transforms the center of the ellipse and returns the new ellipse.

Parameters
otherThe transform to transform by.
Returns
The transformed ellipse.

◆ XSemiAxis()

constexpr units::meter_t frc::Ellipse2d::XSemiAxis ( ) const
inlineconstexpr

Returns the x semi-axis.

Returns
The x semi-axis.

◆ YSemiAxis()

constexpr units::meter_t frc::Ellipse2d::YSemiAxis ( ) const
inlineconstexpr

Returns the y semi-axis.

Returns
The y semi-axis.

The documentation for this class was generated from the following file: