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