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