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