WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
Translation2d.hpp
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 <algorithm>
8#include <initializer_list>
9#include <span>
10
11#include <Eigen/Core>
12
14#include "wpi/units/area.hpp"
15#include "wpi/units/length.hpp"
16#include "wpi/units/math.hpp"
18
19namespace wpi::util {
20class json;
21} // namespace wpi::util
22
23namespace wpi::math {
24
25/**
26 * Represents a translation in 2D space.
27 * This object can be used to represent a point or a vector.
28 *
29 * This assumes that you are using conventional mathematical axes.
30 * When the robot is at the origin facing in the positive X direction, forward
31 * is positive X and left is positive Y.
32 */
34 public:
35 /**
36 * Constructs a Translation2d with X and Y components equal to zero.
37 */
38 constexpr Translation2d() = default;
39
40 /**
41 * Constructs a Translation2d with the X and Y components equal to the
42 * provided values.
43 *
44 * @param x The x component of the translation.
45 * @param y The y component of the translation.
46 */
47 constexpr Translation2d(wpi::units::meter_t x, wpi::units::meter_t y)
48 : m_x{x}, m_y{y} {}
49
50 /**
51 * Constructs a Translation2d with the provided distance and angle. This is
52 * essentially converting from polar coordinates to Cartesian coordinates.
53 *
54 * @param distance The distance from the origin to the end of the translation.
55 * @param angle The angle between the x-axis and the translation vector.
56 */
57 constexpr Translation2d(wpi::units::meter_t distance, const Rotation2d& angle)
58 : m_x{distance * angle.Cos()}, m_y{distance * angle.Sin()} {}
59
60 /**
61 * Constructs a Translation2d from a 2D translation vector. The values are
62 * assumed to be in meters.
63 *
64 * @param vector The translation vector.
65 */
66 constexpr explicit Translation2d(const Eigen::Vector2d& vector)
67 : m_x{wpi::units::meter_t{vector.x()}},
68 m_y{wpi::units::meter_t{vector.y()}} {}
69
70 /**
71 * Calculates the distance between two translations in 2D space.
72 *
73 * The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²).
74 *
75 * @param other The translation to compute the distance to.
76 *
77 * @return The distance between the two translations.
78 */
79 constexpr wpi::units::meter_t Distance(const Translation2d& other) const {
80 return wpi::units::math::hypot(other.m_x - m_x, other.m_y - m_y);
81 }
82
83 /**
84 * Calculates the square of the distance between two translations in 2D space.
85 * This is equivalent to squaring the result of Distance(Translation2d), but
86 * avoids computing a square root.
87 *
88 * The square of the distance between translations is defined as
89 * (x₂−x₁)²+(y₂−y₁)².
90 *
91 * @param other The translation to compute the squared distance to.
92 * @return The square of the distance between the two translations.
93 */
94 constexpr wpi::units::square_meter_t SquaredDistance(
95 const Translation2d& other) const {
96 return wpi::units::math::pow<2>(other.m_x - m_x) +
97 wpi::units::math::pow<2>(other.m_y - m_y);
98 }
99
100 /**
101 * Returns the X component of the translation.
102 *
103 * @return The X component of the translation.
104 */
105 constexpr wpi::units::meter_t X() const { return m_x; }
106
107 /**
108 * Returns the Y component of the translation.
109 *
110 * @return The Y component of the translation.
111 */
112 constexpr wpi::units::meter_t Y() const { return m_y; }
113
114 /**
115 * Returns a 2D translation vector representation of this translation.
116 *
117 * @return A 2D translation vector representation of this translation.
118 */
119 constexpr Eigen::Vector2d ToVector() const {
120 return Eigen::Vector2d{{m_x.value(), m_y.value()}};
121 }
122
123 /**
124 * Returns the norm, or distance from the origin to the translation.
125 *
126 * @return The norm of the translation.
127 */
128 constexpr wpi::units::meter_t Norm() const {
129 return wpi::units::math::hypot(m_x, m_y);
130 }
131
132 /**
133 * Returns the squared norm, or squared distance from the origin to the
134 * translation. This is equivalent to squaring the result of Norm(), but
135 * avoids computing a square root.
136 *
137 * @return The squared norm of the translation.
138 */
139 constexpr wpi::units::square_meter_t SquaredNorm() const {
140 return wpi::units::math::pow<2>(m_x) + wpi::units::math::pow<2>(m_y);
141 }
142
143 /**
144 * Returns the angle this translation forms with the positive X axis.
145 *
146 * @return The angle of the translation
147 */
148 constexpr Rotation2d Angle() const {
149 return Rotation2d{m_x.value(), m_y.value()};
150 }
151
152 /**
153 * Applies a rotation to the translation in 2D space.
154 *
155 * This multiplies the translation vector by a counterclockwise rotation
156 * matrix of the given angle.
157 *
158 * <pre>
159 * [x_new] [other.cos, -other.sin][x]
160 * [y_new] = [other.sin, other.cos][y]
161 * </pre>
162 *
163 * For example, rotating a Translation2d of &lt;2, 0&gt; by 90 degrees will
164 * return a Translation2d of &lt;0, 2&gt;.
165 *
166 * @param other The rotation to rotate the translation by.
167 *
168 * @return The new rotated translation.
169 */
170 constexpr Translation2d RotateBy(const Rotation2d& other) const {
171 return {m_x * other.Cos() - m_y * other.Sin(),
172 m_x * other.Sin() + m_y * other.Cos()};
173 }
174
175 /**
176 * Rotates this translation around another translation in 2D space.
177 *
178 * <pre>
179 * [x_new] [rot.cos, -rot.sin][x - other.x] [other.x]
180 * [y_new] = [rot.sin, rot.cos][y - other.y] + [other.y]
181 * </pre>
182 *
183 * @param other The other translation to rotate around.
184 * @param rot The rotation to rotate the translation by.
185 * @return The new rotated translation.
186 */
188 const Rotation2d& rot) const {
189 return {(m_x - other.X()) * rot.Cos() - (m_y - other.Y()) * rot.Sin() +
190 other.X(),
191 (m_x - other.X()) * rot.Sin() + (m_y - other.Y()) * rot.Cos() +
192 other.Y()};
193 }
194
195 /**
196 * Computes the dot product between this translation and another translation
197 * in 2D space.
198 *
199 * The dot product between two translations is defined as x₁x₂+y₁y₂.
200 *
201 * @param other The translation to compute the dot product with.
202 * @return The dot product between the two translations.
203 */
204 constexpr wpi::units::square_meter_t Dot(const Translation2d& other) const {
205 return m_x * other.X() + m_y * other.Y();
206 }
207
208 /**
209 * Computes the cross product between this translation and another translation
210 * in 2D space.
211 *
212 * The 2D cross product between two translations is defined as x₁y₂-x₂y₁.
213 *
214 * @param other The translation to compute the cross product with.
215 * @return The cross product between the two translations.
216 */
217 constexpr wpi::units::square_meter_t Cross(const Translation2d& other) const {
218 return m_x * other.Y() - m_y * other.X();
219 }
220
221 /**
222 * Returns the sum of two translations in 2D space.
223 *
224 * For example, Translation3d{1.0, 2.5} + Translation3d{2.0, 5.5} =
225 * Translation3d{3.0, 8.0}.
226 *
227 * @param other The translation to add.
228 *
229 * @return The sum of the translations.
230 */
231 constexpr Translation2d operator+(const Translation2d& other) const {
232 return {X() + other.X(), Y() + other.Y()};
233 }
234
235 /**
236 * Returns the difference between two translations.
237 *
238 * For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} =
239 * Translation2d{4.0, 2.0}.
240 *
241 * @param other The translation to subtract.
242 *
243 * @return The difference between the two translations.
244 */
245 constexpr Translation2d operator-(const Translation2d& other) const {
246 return *this + -other;
247 }
248
249 /**
250 * Returns the inverse of the current translation. This is equivalent to
251 * rotating by 180 degrees, flipping the point over both axes, or negating all
252 * components of the translation.
253 *
254 * @return The inverse of the current translation.
255 */
256 constexpr Translation2d operator-() const { return {-m_x, -m_y}; }
257
258 /**
259 * Returns the translation multiplied by a scalar.
260 *
261 * For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}.
262 *
263 * @param scalar The scalar to multiply by.
264 *
265 * @return The scaled translation.
266 */
267 constexpr Translation2d operator*(double scalar) const {
268 return {scalar * m_x, scalar * m_y};
269 }
270
271 /**
272 * Returns the translation divided by a scalar.
273 *
274 * For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}.
275 *
276 * @param scalar The scalar to divide by.
277 *
278 * @return The scaled translation.
279 */
280 constexpr Translation2d operator/(double scalar) const {
281 return operator*(1.0 / scalar);
282 }
283
284 /**
285 * Checks equality between this Translation2d and another object.
286 *
287 * @param other The other object.
288 * @return Whether the two objects are equal.
289 */
290 constexpr bool operator==(const Translation2d& other) const {
291 return wpi::units::math::abs(m_x - other.m_x) < 1E-9_m &&
292 wpi::units::math::abs(m_y - other.m_y) < 1E-9_m;
293 }
294
295 /**
296 * Returns the nearest Translation2d from a collection of translations
297 * @param translations The collection of translations.
298 * @return The nearest Translation2d from the collection.
299 */
301 std::span<const Translation2d> translations) const {
302 return *std::min_element(
303 translations.begin(), translations.end(),
304 [this](const Translation2d& a, const Translation2d& b) {
305 return this->Distance(a) < this->Distance(b);
306 });
307 }
308
309 /**
310 * Returns the nearest Translation2d from a collection of translations
311 * @param translations The collection of translations.
312 * @return The nearest Translation2d from the collection.
313 */
315 std::initializer_list<Translation2d> translations) const {
316 return *std::min_element(
317 translations.begin(), translations.end(),
318 [this](const Translation2d& a, const Translation2d& b) {
319 return this->Distance(a) < this->Distance(b);
320 });
321 }
322
323 private:
324 wpi::units::meter_t m_x = 0_m;
325 wpi::units::meter_t m_y = 0_m;
326};
327
329void to_json(wpi::util::json& json, const Translation2d& state);
330
332void from_json(const wpi::util::json& json, Translation2d& state);
333
334} // namespace wpi::math
335
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:29
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.hpp:238
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.hpp:245
Represents a translation in 2D space.
Definition Translation2d.hpp:33
constexpr Rotation2d Angle() const
Returns the angle this translation forms with the positive X axis.
Definition Translation2d.hpp:148
constexpr Translation2d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation2d.hpp:280
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition Translation2d.hpp:170
constexpr Translation2d RotateAround(const Translation2d &other, const Rotation2d &rot) const
Rotates this translation around another translation in 2D space.
Definition Translation2d.hpp:187
constexpr wpi::units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.hpp:112
constexpr bool operator==(const Translation2d &other) const
Checks equality between this Translation2d and another object.
Definition Translation2d.hpp:290
constexpr Translation2d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation2d.hpp:267
constexpr wpi::units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.hpp:105
constexpr Translation2d operator-() const
Returns the inverse of the current translation.
Definition Translation2d.hpp:256
constexpr Translation2d Nearest(std::initializer_list< Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.hpp:314
constexpr wpi::units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation2d.hpp:128
constexpr Translation2d()=default
Constructs a Translation2d with X and Y components equal to zero.
constexpr wpi::units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2D space.
Definition Translation2d.hpp:79
constexpr Translation2d(wpi::units::meter_t distance, const Rotation2d &angle)
Constructs a Translation2d with the provided distance and angle.
Definition Translation2d.hpp:57
constexpr Eigen::Vector2d ToVector() const
Returns a 2D translation vector representation of this translation.
Definition Translation2d.hpp:119
constexpr Translation2d operator+(const Translation2d &other) const
Returns the sum of two translations in 2D space.
Definition Translation2d.hpp:231
constexpr wpi::units::square_meter_t Cross(const Translation2d &other) const
Computes the cross product between this translation and another translation in 2D space.
Definition Translation2d.hpp:217
constexpr Translation2d(const Eigen::Vector2d &vector)
Constructs a Translation2d from a 2D translation vector.
Definition Translation2d.hpp:66
constexpr wpi::units::square_meter_t Dot(const Translation2d &other) const
Computes the dot product between this translation and another translation in 2D space.
Definition Translation2d.hpp:204
constexpr Translation2d Nearest(std::span< const Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.hpp:300
constexpr wpi::units::square_meter_t SquaredNorm() const
Returns the squared norm, or squared distance from the origin to the translation.
Definition Translation2d.hpp:139
constexpr wpi::units::square_meter_t SquaredDistance(const Translation2d &other) const
Calculates the square of the distance between two translations in 2D space.
Definition Translation2d.hpp:94
constexpr Translation2d operator-(const Translation2d &other) const
Returns the difference between two translations.
Definition Translation2d.hpp:245
constexpr Translation2d(wpi::units::meter_t x, wpi::units::meter_t y)
Constructs a Translation2d with the X and Y components equal to the provided values.
Definition Translation2d.hpp:47
Definition json.hpp:85
Definition LinearSystem.hpp:20
WPILIB_DLLEXPORT void to_json(wpi::util::json &json, const Translation2d &state)
WPILIB_DLLEXPORT void from_json(const wpi::util::json &json, Translation2d &state)
Definition raw_os_ostream.hpp:19
Definition CvSource.hpp:15