WPILibC++ 2027.0.0-alpha-2
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/length.h"
18#include "units/math.h"
19
20namespace frc {
21
22/**
23 * Represents a translation in 3D 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. When the
27 * robot is at the origin facing in the positive X direction, forward is
28 * positive X, left is positive Y, and up is positive Z.
29 */
31 public:
32 /**
33 * Constructs a Translation3d with X, Y, and Z components equal to zero.
34 */
35 constexpr Translation3d() = default;
36
37 /**
38 * Constructs a Translation3d with the X, Y, and Z 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 * @param z The z component of the translation.
44 */
45 constexpr Translation3d(units::meter_t x, units::meter_t y, units::meter_t z)
46 : m_x{x}, m_y{y}, m_z{z} {}
47
48 /**
49 * Constructs a Translation3d with the provided distance and angle. This is
50 * essentially converting from polar coordinates to Cartesian coordinates.
51 *
52 * @param distance The distance from the origin to the end of the translation.
53 * @param angle The angle between the x-axis and the translation vector.
54 */
55 constexpr Translation3d(units::meter_t distance, const Rotation3d& angle) {
56 auto rectangular = Translation3d{distance, 0_m, 0_m}.RotateBy(angle);
57 m_x = rectangular.X();
58 m_y = rectangular.Y();
59 m_z = rectangular.Z();
60 }
61
62 /**
63 * Constructs a Translation3d from a 3D translation vector. The values are
64 * assumed to be in meters.
65 *
66 * @param vector The translation vector.
67 */
68 constexpr explicit Translation3d(const Eigen::Vector3d& vector)
69 : m_x{units::meter_t{vector.x()}},
70 m_y{units::meter_t{vector.y()}},
71 m_z{units::meter_t{vector.z()}} {}
72
73 /**
74 * Constructs a 3D translation from a 2D translation in the X-Y plane.
75 *
76 * @param translation The 2D translation.
77 * @see Pose3d(Pose2d)
78 * @see Transform3d(Transform2d)
79 */
80 constexpr explicit Translation3d(const Translation2d& translation)
81 : Translation3d{translation.X(), translation.Y(), 0_m} {}
82
83 /**
84 * Calculates the distance between two translations in 3D space.
85 *
86 * The distance between translations is defined as
87 * √((x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)²).
88 *
89 * @param other The translation to compute the distance to.
90 *
91 * @return The distance between the two translations.
92 */
93 constexpr units::meter_t Distance(const Translation3d& other) const {
94 return units::math::sqrt(units::math::pow<2>(other.m_x - m_x) +
95 units::math::pow<2>(other.m_y - m_y) +
96 units::math::pow<2>(other.m_z - m_z));
97 }
98
99 /**
100 * Returns the X component of the translation.
101 *
102 * @return The Z component of the translation.
103 */
104 constexpr units::meter_t X() const { return m_x; }
105
106 /**
107 * Returns the Y component of the translation.
108 *
109 * @return The Y component of the translation.
110 */
111 constexpr units::meter_t Y() const { return m_y; }
112
113 /**
114 * Returns the Z component of the translation.
115 *
116 * @return The Z component of the translation.
117 */
118 constexpr units::meter_t Z() const { return m_z; }
119
120 /**
121 * Returns a 3D translation vector representation of this translation.
122 *
123 * @return A 3D translation vector representation of this translation.
124 */
125 constexpr Eigen::Vector3d ToVector() const {
126 return Eigen::Vector3d{{m_x.value(), m_y.value(), m_z.value()}};
127 }
128
129 /**
130 * Returns the norm, or distance from the origin to the translation.
131 *
132 * @return The norm of the translation.
133 */
134 constexpr units::meter_t Norm() const {
135 return units::math::sqrt(m_x * m_x + m_y * m_y + m_z * m_z);
136 }
137
138 /**
139 * Applies a rotation to the translation in 3D space.
140 *
141 * For example, rotating a Translation3d of &lt;2, 0, 0&gt; by 90 degrees
142 * around the Z axis will return a Translation3d of &lt;0, 2, 0&gt;.
143 *
144 * @param other The rotation to rotate the translation by.
145 *
146 * @return The new rotated translation.
147 */
148 constexpr Translation3d RotateBy(const Rotation3d& other) const {
149 Quaternion p{0.0, m_x.value(), m_y.value(), m_z.value()};
150 auto qprime = other.GetQuaternion() * p * other.GetQuaternion().Inverse();
151 return Translation3d{units::meter_t{qprime.X()}, units::meter_t{qprime.Y()},
152 units::meter_t{qprime.Z()}};
153 }
154
155 /**
156 * Rotates this translation around another translation in 3D space.
157 *
158 * @param other The other translation to rotate around.
159 * @param rot The rotation to rotate the translation by.
160 * @return The new rotated translation.
161 */
163 const Rotation3d& rot) const {
164 return (*this - other).RotateBy(rot) + other;
165 }
166
167 /**
168 * Returns a Translation2d representing this Translation3d projected into the
169 * X-Y plane.
170 */
171 constexpr Translation2d ToTranslation2d() const {
172 return Translation2d{m_x, m_y};
173 }
174
175 /**
176 * Returns the sum of two translations in 3D space.
177 *
178 * For example, Translation3d{1.0, 2.5, 3.5} + Translation3d{2.0, 5.5, 7.5} =
179 * Translation3d{3.0, 8.0, 11.0}.
180 *
181 * @param other The translation to add.
182 *
183 * @return The sum of the translations.
184 */
185 constexpr Translation3d operator+(const Translation3d& other) const {
186 return {X() + other.X(), Y() + other.Y(), Z() + other.Z()};
187 }
188
189 /**
190 * Returns the difference between two translations.
191 *
192 * For example, Translation3d{5.0, 4.0, 3.0} - Translation3d{1.0, 2.0, 3.0} =
193 * Translation3d{4.0, 2.0, 0.0}.
194 *
195 * @param other The translation to subtract.
196 *
197 * @return The difference between the two translations.
198 */
199 constexpr Translation3d operator-(const Translation3d& other) const {
200 return operator+(-other);
201 }
202
203 /**
204 * Returns the inverse of the current translation. This is equivalent to
205 * negating all components of the translation.
206 *
207 * @return The inverse of the current translation.
208 */
209 constexpr Translation3d operator-() const { return {-m_x, -m_y, -m_z}; }
210
211 /**
212 * Returns the translation multiplied by a scalar.
213 *
214 * For example, Translation3d{2.0, 2.5, 4.5} * 2 = Translation3d{4.0, 5.0,
215 * 9.0}.
216 *
217 * @param scalar The scalar to multiply by.
218 *
219 * @return The scaled translation.
220 */
221 constexpr Translation3d operator*(double scalar) const {
222 return {scalar * m_x, scalar * m_y, scalar * m_z};
223 }
224
225 /**
226 * Returns the translation divided by a scalar.
227 *
228 * For example, Translation3d{2.0, 2.5, 4.5} / 2 = Translation3d{1.0, 1.25,
229 * 2.25}.
230 *
231 * @param scalar The scalar to divide by.
232 *
233 * @return The scaled translation.
234 */
235 constexpr Translation3d operator/(double scalar) const {
236 return operator*(1.0 / scalar);
237 }
238
239 /**
240 * Checks equality between this Translation3d and another object.
241 *
242 * @param other The other object.
243 * @return Whether the two objects are equal.
244 */
245 constexpr bool operator==(const Translation3d& other) const {
246 return units::math::abs(m_x - other.m_x) < 1E-9_m &&
247 units::math::abs(m_y - other.m_y) < 1E-9_m &&
248 units::math::abs(m_z - other.m_z) < 1E-9_m;
249 }
250
251 /**
252 * Returns the nearest Translation3d from a collection of translations
253 * @param translations The collection of translations.
254 * @return The nearest Translation3d from the collection.
255 */
257 std::span<const Translation3d> translations) const {
258 return *std::min_element(
259 translations.begin(), translations.end(),
260 [this](const Translation3d& a, const Translation3d& b) {
261 return this->Distance(a) < this->Distance(b);
262 });
263 }
264
265 /**
266 * Returns the nearest Translation3d from a collection of translations
267 * @param translations The collection of translations.
268 * @return The nearest Translation3d from the collection.
269 */
271 std::initializer_list<Translation3d> translations) const {
272 return *std::min_element(
273 translations.begin(), translations.end(),
274 [this](const Translation3d& a, const Translation3d& b) {
275 return this->Distance(a) < this->Distance(b);
276 });
277 }
278
279 private:
280 units::meter_t m_x = 0_m;
281 units::meter_t m_y = 0_m;
282 units::meter_t m_z = 0_m;
283};
284
286void to_json(wpi::json& json, const Translation3d& state);
287
289void from_json(const wpi::json& json, Translation3d& state);
290
291} // namespace frc
292
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
namespace for Niels Lohmann
Definition json.h:99
Represents a quaternion.
Definition Quaternion.h:19
constexpr Quaternion Inverse() const
Returns the inverse of the quaternion.
Definition Quaternion.h:130
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
Represents a translation in 2D space.
Definition Translation2d.h:29
Represents a translation in 3D space.
Definition Translation3d.h:30
constexpr Translation3d Nearest(std::initializer_list< Translation3d > translations) const
Returns the nearest Translation3d from a collection of translations.
Definition Translation3d.h:270
constexpr Translation3d RotateBy(const Rotation3d &other) const
Applies a rotation to the translation in 3D space.
Definition Translation3d.h:148
constexpr Translation3d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation3d.h:235
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation3d.h:111
constexpr Translation3d RotateAround(const Translation3d &other, const Rotation3d &rot) const
Rotates this translation around another translation in 3D space.
Definition Translation3d.h:162
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:45
constexpr bool operator==(const Translation3d &other) const
Checks equality between this Translation3d and another object.
Definition Translation3d.h:245
constexpr Translation3d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation3d.h:221
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation3d.h:104
constexpr units::meter_t Z() const
Returns the Z component of the translation.
Definition Translation3d.h:118
constexpr Translation3d(const Eigen::Vector3d &vector)
Constructs a Translation3d from a 3D translation vector.
Definition Translation3d.h:68
constexpr Translation3d(const Translation2d &translation)
Constructs a 3D translation from a 2D translation in the X-Y plane.
Definition Translation3d.h:80
constexpr Translation3d operator-() const
Returns the inverse of the current translation.
Definition Translation3d.h:209
constexpr Translation3d operator+(const Translation3d &other) const
Returns the sum of two translations in 3D space.
Definition Translation3d.h:185
constexpr units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation3d.h:134
constexpr Translation3d operator-(const Translation3d &other) const
Returns the difference between two translations.
Definition Translation3d.h:199
constexpr units::meter_t Distance(const Translation3d &other) const
Calculates the distance between two translations in 3D space.
Definition Translation3d.h:93
constexpr Translation2d ToTranslation2d() const
Returns a Translation2d representing this Translation3d projected into the X-Y plane.
Definition Translation3d.h:171
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:256
constexpr Translation3d(units::meter_t distance, const Rotation3d &angle)
Constructs a Translation3d with the provided distance and angle.
Definition Translation3d.h:55
constexpr Eigen::Vector3d ToVector() const
Returns a 3D translation vector representation of this translation.
Definition Translation3d.h:125
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
constexpr auto sqrt(const UnitType &value) noexcept -> unit_t< square_root< typename units::traits::unit_t_traits< UnitType >::unit_type >, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the square root of value
Definition math.h:485
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)
constexpr auto pow(const UnitType &value) noexcept -> unit_t< typename units::detail::power_of_unit< power, typename units::traits::unit_t_traits< UnitType >::unit_type >::type, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the value of value raised to the power
Definition base.h:2810
Unit Conversion Library namespace.
Definition acceleration.h:33
Type representing an arbitrary unit.
Definition base.h:888