WPILibC++ 2025.0.0-alpha-1-14-g3b6f38d
Ellipse2d.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <stdexcept>
8
9#include <gcem.hpp>
10#include <wpi/SymbolExports.h>
11#include <wpi/array.h>
12
13#include "frc/geometry/Pose2d.h"
17#include "units/length.h"
18#include "units/math.h"
19
20namespace frc {
21
22/**
23 * Represents a 2d ellipse space containing translational, rotational, and
24 * scaling components.
25 */
27 public:
28 /**
29 * Constructs an ellipse around a center point and two semi-axes, a horizontal
30 * and vertical one.
31 *
32 * @param center The center of the ellipse.
33 * @param xSemiAxis The x semi-axis.
34 * @param ySemiAxis The y semi-axis.
35 */
36 constexpr Ellipse2d(const Pose2d& center, units::meter_t xSemiAxis,
37 units::meter_t ySemiAxis)
38 : m_center{center}, m_xSemiAxis{xSemiAxis}, m_ySemiAxis{ySemiAxis} {
39 if (xSemiAxis <= 0_m || ySemiAxis <= 0_m) {
40 throw std::invalid_argument("Ellipse2d semi-axes must be positive");
41 }
42 }
43
44 /**
45 * Constructs a perfectly circular ellipse with the specified radius.
46 *
47 * @param center The center of the circle.
48 * @param radius The radius of the circle.
49 */
50 constexpr Ellipse2d(const Translation2d& center, double radius)
51 : m_center{center, Rotation2d{}},
52 m_xSemiAxis{radius},
53 m_ySemiAxis{radius} {}
54
55 /**
56 * Returns the center of the ellipse.
57 *
58 * @return The center of the ellipse.
59 */
60 constexpr const Pose2d& Center() const { return m_center; }
61
62 /**
63 * Returns the rotational component of the ellipse.
64 *
65 * @return The rotational component of the ellipse.
66 */
67 constexpr const Rotation2d& Rotation() const { return m_center.Rotation(); }
68
69 /**
70 * Returns the x semi-axis.
71 *
72 * @return The x semi-axis.
73 */
74 constexpr units::meter_t XSemiAxis() const { return m_xSemiAxis; }
75
76 /**
77 * Returns the y semi-axis.
78 *
79 * @return The y semi-axis.
80 */
81 constexpr units::meter_t YSemiAxis() const { return m_ySemiAxis; }
82
83 /**
84 * Returns the focal points of the ellipse. In a perfect circle, this will
85 * always return the center.
86 *
87 * @return The focal points.
88 */
90 // Major semi-axis
91 auto a = units::math::max(m_xSemiAxis, m_ySemiAxis);
92
93 // Minor semi-axis
94 auto b = units::math::min(m_xSemiAxis, m_ySemiAxis); // NOLINT
95
96 auto c = units::math::sqrt(a * a - b * b);
97
98 if (m_xSemiAxis > m_ySemiAxis) {
99 return wpi::array{
100 (m_center + Transform2d{-c, 0_m, Rotation2d{}}).Translation(),
101 (m_center + Transform2d{c, 0_m, Rotation2d{}}).Translation()};
102 } else {
103 return wpi::array{
104 (m_center + Transform2d{0_m, -c, Rotation2d{}}).Translation(),
105 (m_center + Transform2d{0_m, c, Rotation2d{}}).Translation()};
106 }
107 }
108
109 /**
110 * Transforms the center of the ellipse and returns the new ellipse.
111 *
112 * @param other The transform to transform by.
113 * @return The transformed ellipse.
114 */
115 constexpr Ellipse2d TransformBy(const Transform2d& other) const {
116 return Ellipse2d{m_center.TransformBy(other), m_xSemiAxis, m_ySemiAxis};
117 }
118
119 /**
120 * Rotates the center of the ellipse and returns the new ellipse.
121 *
122 * @param other The rotation to transform by.
123 * @return The rotated ellipse.
124 */
125 constexpr Ellipse2d RotateBy(const Rotation2d& other) const {
126 return Ellipse2d{m_center.RotateBy(other), m_xSemiAxis, m_ySemiAxis};
127 }
128
129 /**
130 * Checks if a point is intersected by this ellipse's circumference.
131 *
132 * @param point The point to check.
133 * @return True, if this ellipse's circumference intersects the point.
134 */
135 constexpr bool Intersects(const Translation2d& point) const {
136 return gcem::abs(1.0 - SolveEllipseEquation(point)) <= 1E-9;
137 }
138
139 /**
140 * Checks if a point is contained within this ellipse. This is inclusive, if
141 * the point lies on the circumference this will return {@code true}.
142 *
143 * @param point The point to check.
144 * @return True, if the point is within or on the ellipse.
145 */
146 constexpr bool Contains(const Translation2d& point) const {
147 return SolveEllipseEquation(point) <= 1.0;
148 }
149
150 /**
151 * Returns the distance between the perimeter of the ellipse and the point.
152 *
153 * @param point The point to check.
154 * @return The distance (0, if the point is contained by the ellipse)
155 */
156 units::meter_t Distance(const Translation2d& point) const;
157
158 /**
159 * Returns the nearest point that is contained within the ellipse.
160 *
161 * @param point The point that this will find the nearest point to.
162 * @return A new point that is nearest to {@code point} and contained in the
163 * ellipse.
164 */
166
167 /**
168 * Checks equality between this Ellipse2d and another object.
169 *
170 * @param other The other object.
171 * @return Whether the two objects are equal.
172 */
173 constexpr bool operator==(const Ellipse2d& other) const {
174 return m_center == other.m_center &&
175 units::math::abs(m_xSemiAxis - other.m_xSemiAxis) < 1E-9_m &&
176 units::math::abs(m_ySemiAxis - other.m_ySemiAxis) < 1E-9_m;
177 }
178
179 private:
180 Pose2d m_center;
181 units::meter_t m_xSemiAxis;
182 units::meter_t m_ySemiAxis;
183
184 /**
185 * Solves the equation of an ellipse from the given point. This is a helper
186 * function used to determine if that point lies inside of or on an ellipse.
187 *
188 * <pre>
189 * (x - h)²/a² + (y - k)²/b² = 1
190 * </pre>
191 *
192 * @param point The point to solve for.
193 * @return < 1.0 if the point lies inside the ellipse, == 1.0 if a point lies
194 * on the ellipse, and > 1.0 if the point lies outsides the ellipse.
195 */
196 constexpr double SolveEllipseEquation(const Translation2d& point) const {
197 // Rotate the point by the inverse of the ellipse's rotation
198 auto rotPoint =
199 point.RotateAround(m_center.Translation(), -m_center.Rotation());
200
201 auto x = rotPoint.X() - m_center.X();
202 auto y = rotPoint.Y() - m_center.Y();
203
204 return (x * x) / (m_xSemiAxis * m_xSemiAxis) +
205 (y * y) / (m_ySemiAxis * m_ySemiAxis);
206 }
207};
208
209} // namespace frc
210
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2d ellipse space containing translational, rotational, and scaling components.
Definition: Ellipse2d.h:26
constexpr bool operator==(const Ellipse2d &other) const
Checks equality between this Ellipse2d and another object.
Definition: Ellipse2d.h:173
constexpr bool Intersects(const Translation2d &point) const
Checks if a point is intersected by this ellipse's circumference.
Definition: Ellipse2d.h:135
constexpr const Rotation2d & Rotation() const
Returns the rotational component of the ellipse.
Definition: Ellipse2d.h:67
constexpr units::meter_t YSemiAxis() const
Returns the y semi-axis.
Definition: Ellipse2d.h:81
Translation2d FindNearestPoint(const Translation2d &point) const
Returns the nearest point that is contained within the ellipse.
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.
Definition: Ellipse2d.h:36
constexpr Ellipse2d TransformBy(const Transform2d &other) const
Transforms the center of the ellipse and returns the new ellipse.
Definition: Ellipse2d.h:115
constexpr wpi::array< Translation2d, 2 > FocalPoints() const
Returns the focal points of the ellipse.
Definition: Ellipse2d.h:89
constexpr bool Contains(const Translation2d &point) const
Checks if a point is contained within this ellipse.
Definition: Ellipse2d.h:146
constexpr Ellipse2d RotateBy(const Rotation2d &other) const
Rotates the center of the ellipse and returns the new ellipse.
Definition: Ellipse2d.h:125
constexpr units::meter_t XSemiAxis() const
Returns the x semi-axis.
Definition: Ellipse2d.h:74
constexpr const Pose2d & Center() const
Returns the center of the ellipse.
Definition: Ellipse2d.h:60
units::meter_t Distance(const Translation2d &point) const
Returns the distance between the perimeter of the ellipse and the point.
constexpr Ellipse2d(const Translation2d &center, double radius)
Constructs a perfectly circular ellipse with the specified radius.
Definition: Ellipse2d.h:50
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition: Pose2d.h:103
constexpr units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition: Pose2d.h:96
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition: Pose2d.h:89
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition: Pose2d.h:82
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Represents a transformation for a Pose2d in the pose's frame.
Definition: Transform2d.h:18
Represents a translation in 2D space.
Definition: Translation2d.h:28
constexpr Translation2d RotateAround(const Translation2d &other, const Rotation2d &rot) const
Rotates this translation around another translation in 2D space.
Definition: Translation2d.inc:33
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:79
This class is a wrapper around std::array that does compile time size checking.
Definition: array.h:26
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition: math.h:726
constexpr auto sqrt(const UnitType &value) noexcept -> unit_t< square_root< typename units::traits::unit_t_traits< UnitType >::unit_type >, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the square root of value
Definition: math.h:485
Definition: AprilTagDetector_cv.h:11
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition: abs.hpp:40
static constexpr const velocity::meters_per_second_t c(299792458.0)
Speed of light in vacuum.
constexpr UnitTypeLhs() min(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs)
Definition: base.h:3413
constexpr UnitTypeLhs() max(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs)
Definition: base.h:3421
b
Definition: data.h:44