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