Represents a 2d ellipse space containing translational, rotational, and scaling components.
More...
#include <frc/geometry/Ellipse2d.h>
|
constexpr | Ellipse2d (const Pose2d ¢er, units::meter_t xSemiAxis, units::meter_t ySemiAxis) |
| Constructs an ellipse around a center point and two semi-axes, a horizontal and vertical one.
|
|
constexpr | Ellipse2d (const Translation2d ¢er, double radius) |
| Constructs a perfectly circular ellipse with the specified radius.
|
|
constexpr const Pose2d & | Center () const |
| Returns the center of the ellipse.
|
|
constexpr const Rotation2d & | Rotation () const |
| Returns the rotational component of the ellipse.
|
|
constexpr units::meter_t | XSemiAxis () const |
| Returns the x semi-axis.
|
|
constexpr units::meter_t | YSemiAxis () const |
| Returns the y semi-axis.
|
|
constexpr wpi::array< Translation2d, 2 > | FocalPoints () const |
| Returns the focal points of the ellipse.
|
|
constexpr Ellipse2d | TransformBy (const Transform2d &other) const |
| Transforms the center of the ellipse and returns the new ellipse.
|
|
constexpr Ellipse2d | RotateBy (const Rotation2d &other) const |
| Rotates the center of the ellipse and returns the new ellipse.
|
|
constexpr bool | Intersects (const Translation2d &point) const |
| Checks if a point is intersected by this ellipse's circumference.
|
|
constexpr bool | Contains (const Translation2d &point) const |
| Checks if a point is contained within this ellipse.
|
|
units::meter_t | Distance (const Translation2d &point) const |
| Returns the distance between the perimeter of the ellipse and the point.
|
|
Translation2d | Nearest (const Translation2d &point) const |
| Returns the nearest point that is contained within the ellipse.
|
|
constexpr bool | operator== (const Ellipse2d &other) const |
| Checks equality between this Ellipse2d and another object.
|
|
Represents a 2d ellipse space containing translational, rotational, and scaling components.
◆ Ellipse2d() [1/2]
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
-
center | The center of the ellipse. |
xSemiAxis | The x semi-axis. |
ySemiAxis | The y semi-axis. |
◆ Ellipse2d() [2/2]
frc::Ellipse2d::Ellipse2d |
( |
const Translation2d & | center, |
|
|
double | radius ) |
|
inlineconstexpr |
Constructs a perfectly circular ellipse with the specified radius.
- Parameters
-
center | The center of the circle. |
radius | The radius of the circle. |
◆ Center()
const Pose2d & frc::Ellipse2d::Center |
( |
| ) |
const |
|
inlineconstexpr |
Returns the center of the ellipse.
- Returns
- The center of the ellipse.
◆ Contains()
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
-
- Returns
- True, if the point is within or on the ellipse.
◆ Distance()
units::meter_t frc::Ellipse2d::Distance |
( |
const Translation2d & | point | ) |
const |
|
inline |
Returns the distance between the perimeter of the ellipse and the point.
- Parameters
-
- Returns
- The distance (0, if the point is contained by the ellipse)
◆ FocalPoints()
Returns the focal points of the ellipse.
In a perfect circle, this will always return the center.
- Returns
- The focal points.
◆ Intersects()
bool frc::Ellipse2d::Intersects |
( |
const Translation2d & | point | ) |
const |
|
inlineconstexpr |
Checks if a point is intersected by this ellipse's circumference.
- Parameters
-
- Returns
- True, if this ellipse's circumference intersects the point.
◆ 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.
◆ operator==()
bool frc::Ellipse2d::operator== |
( |
const Ellipse2d & | other | ) |
const |
|
inlineconstexpr |
Checks equality between this Ellipse2d and another object.
- Parameters
-
- Returns
- Whether the two objects are equal.
◆ RotateBy()
Rotates the center of the ellipse and returns the new ellipse.
- Parameters
-
other | The rotation to transform by. |
- Returns
- The rotated ellipse.
◆ Rotation()
const Rotation2d & frc::Ellipse2d::Rotation |
( |
| ) |
const |
|
inlineconstexpr |
Returns the rotational component of the ellipse.
- Returns
- The rotational component of the ellipse.
◆ TransformBy()
Transforms the center of the ellipse and returns the new ellipse.
- Parameters
-
other | The transform to transform by. |
- Returns
- The transformed ellipse.
◆ XSemiAxis()
units::meter_t frc::Ellipse2d::XSemiAxis |
( |
| ) |
const |
|
inlineconstexpr |
Returns the x semi-axis.
- Returns
- The x semi-axis.
◆ YSemiAxis()
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: