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