WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
Pose3d.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#include <stdexcept>
11#include <utility>
12
13#include <Eigen/Core>
14
19
20namespace wpi::util {
21class json;
22} // namespace wpi::util
23
24namespace wpi::math {
25
26class Transform3d;
27
28/**
29 * Represents a 3D pose containing translational and rotational elements.
30 */
32 public:
33 /**
34 * Constructs a pose at the origin facing toward the positive X axis.
35 */
36 constexpr Pose3d() = default;
37
38 /**
39 * Constructs a pose with the specified translation and rotation.
40 *
41 * @param translation The translational component of the pose.
42 * @param rotation The rotational component of the pose.
43 */
44 constexpr Pose3d(Translation3d translation, Rotation3d rotation)
45 : m_translation{std::move(translation)},
46 m_rotation{std::move(rotation)} {}
47
48 /**
49 * Constructs a pose with x, y, and z translations instead of a separate
50 * Translation3d.
51 *
52 * @param x The x component of the translational component of the pose.
53 * @param y The y component of the translational component of the pose.
54 * @param z The z component of the translational component of the pose.
55 * @param rotation The rotational component of the pose.
56 */
57 constexpr Pose3d(wpi::units::meter_t x, wpi::units::meter_t y,
58 wpi::units::meter_t z, Rotation3d rotation)
59 : m_translation{x, y, z}, m_rotation{std::move(rotation)} {}
60
61 /**
62 * Constructs a pose with the specified affine transformation matrix.
63 *
64 * @param matrix The affine transformation matrix.
65 * @throws std::domain_error if the affine transformation matrix is invalid.
66 */
67 constexpr explicit Pose3d(const Eigen::Matrix4d& matrix)
68 : m_translation{
69 Eigen::Vector3d{{matrix(0, 3)}, {matrix(1, 3)}, {matrix(2, 3)}}},
70 m_rotation{
71 Eigen::Matrix3d{{matrix(0, 0), matrix(0, 1), matrix(0, 2)},
72 {matrix(1, 0), matrix(1, 1), matrix(1, 2)},
73 {matrix(2, 0), matrix(2, 1), matrix(2, 2)}}} {
74 if (matrix(3, 0) != 0.0 || matrix(3, 1) != 0.0 || matrix(3, 2) != 0.0 ||
75 matrix(3, 3) != 1.0) {
76 throw std::domain_error("Affine transformation matrix is invalid");
77 }
78 }
79
80 /**
81 * Constructs a 3D pose from a 2D pose in the X-Y plane.
82 *
83 * @param pose The 2D pose.
84 * @see Rotation3d(Rotation2d)
85 * @see Translation3d(Translation2d)
86 */
87 constexpr explicit Pose3d(const Pose2d& pose)
88 : m_translation{pose.X(), pose.Y(), 0_m},
89 m_rotation{0_rad, 0_rad, pose.Rotation().Radians()} {}
90
91 /**
92 * Transforms the pose by the given transformation and returns the new
93 * transformed pose. The transform is applied relative to the pose's frame.
94 * Note that this differs from Pose3d::RotateBy(const Rotation3d&), which is
95 * applied relative to the global frame and around the origin.
96 *
97 * @param other The transform to transform the pose by.
98 *
99 * @return The transformed pose.
100 */
101 constexpr Pose3d operator+(const Transform3d& other) const {
102 return TransformBy(other);
103 }
104
105 /**
106 * Returns the Transform3d that maps the one pose to another.
107 *
108 * @param other The initial pose of the transformation.
109 * @return The transform that maps the other pose to the current pose.
110 */
111 constexpr Transform3d operator-(const Pose3d& other) const;
112
113 /**
114 * Checks equality between this Pose3d and another object.
115 */
116 constexpr bool operator==(const Pose3d&) const = default;
117
118 /**
119 * Returns the underlying translation.
120 *
121 * @return Reference to the translational component of the pose.
122 */
123 constexpr const Translation3d& Translation() const { return m_translation; }
124
125 /**
126 * Returns the X component of the pose's translation.
127 *
128 * @return The x component of the pose's translation.
129 */
130 constexpr wpi::units::meter_t X() const { return m_translation.X(); }
131
132 /**
133 * Returns the Y component of the pose's translation.
134 *
135 * @return The y component of the pose's translation.
136 */
137 constexpr wpi::units::meter_t Y() const { return m_translation.Y(); }
138
139 /**
140 * Returns the Z component of the pose's translation.
141 *
142 * @return The z component of the pose's translation.
143 */
144 constexpr wpi::units::meter_t Z() const { return m_translation.Z(); }
145
146 /**
147 * Returns the underlying rotation.
148 *
149 * @return Reference to the rotational component of the pose.
150 */
151 constexpr const Rotation3d& Rotation() const { return m_rotation; }
152
153 /**
154 * Multiplies the current pose by a scalar.
155 *
156 * @param scalar The scalar.
157 *
158 * @return The new scaled Pose3d.
159 */
160 constexpr Pose3d operator*(double scalar) const {
161 return Pose3d{m_translation * scalar, m_rotation * scalar};
162 }
163
164 /**
165 * Divides the current pose by a scalar.
166 *
167 * @param scalar The scalar.
168 *
169 * @return The new scaled Pose3d.
170 */
171 constexpr Pose3d operator/(double scalar) const {
172 return *this * (1.0 / scalar);
173 }
174
175 /**
176 * Rotates the pose around the origin and returns the new pose.
177 *
178 * @param other The rotation to transform the pose by, which is applied
179 * extrinsically (from the global frame).
180 *
181 * @return The rotated pose.
182 */
183 constexpr Pose3d RotateBy(const Rotation3d& other) const {
184 return {m_translation.RotateBy(other), m_rotation.RotateBy(other)};
185 }
186
187 /**
188 * Transforms the pose by the given transformation and returns the new
189 * transformed pose. The transform is applied relative to the pose's frame.
190 * Note that this differs from Pose3d::RotateBy(const Rotation3d&), which is
191 * applied relative to the global frame and around the origin.
192 *
193 * @param other The transform to transform the pose by.
194 *
195 * @return The transformed pose.
196 */
197 constexpr Pose3d TransformBy(const Transform3d& other) const;
198
199 /**
200 * Returns the current pose relative to the given pose.
201 *
202 * This function can often be used for trajectory tracking or pose
203 * stabilization algorithms to get the error between the reference and the
204 * current pose.
205 *
206 * @param other The pose that is the origin of the new coordinate frame that
207 * the current pose will be converted into.
208 *
209 * @return The current pose relative to the new origin pose.
210 */
211 constexpr Pose3d RelativeTo(const Pose3d& other) const;
212
213 /**
214 * Rotates the current pose around a point in 3D space.
215 *
216 * @param point The point in 3D space to rotate around.
217 * @param rot The rotation to rotate the pose by.
218 *
219 * @return The new rotated pose.
220 */
221 constexpr Pose3d RotateAround(const Translation3d& point,
222 const Rotation3d& rot) const {
223 return {m_translation.RotateAround(point, rot), m_rotation.RotateBy(rot)};
224 }
225
226 /**
227 * Returns an affine transformation matrix representation of this pose.
228 */
229 constexpr Eigen::Matrix4d ToMatrix() const {
230 auto vec = m_translation.ToVector();
231 auto mat = m_rotation.ToMatrix();
232 return Eigen::Matrix4d{{mat(0, 0), mat(0, 1), mat(0, 2), vec(0)},
233 {mat(1, 0), mat(1, 1), mat(1, 2), vec(1)},
234 {mat(2, 0), mat(2, 1), mat(2, 2), vec(2)},
235 {0.0, 0.0, 0.0, 1.0}};
236 }
237
238 /**
239 * Returns a Pose2d representing this Pose3d projected into the X-Y plane.
240 */
241 constexpr Pose2d ToPose2d() const {
242 return Pose2d{m_translation.X(), m_translation.Y(), m_rotation.Z()};
243 }
244
245 /**
246 * Returns the nearest Pose3d from a collection of poses.
247 *
248 * If two or more poses in the collection have the same distance from this
249 * pose, return the one with the closest rotation component.
250 *
251 * @param poses The collection of poses.
252 * @return The nearest Pose3d from the collection.
253 */
254 constexpr Pose3d Nearest(std::span<const Pose3d> poses) const {
255 return *std::min_element(
256 poses.begin(), poses.end(), [this](const Pose3d& a, const Pose3d& b) {
257 auto aDistance = this->Translation().Distance(a.Translation());
258 auto bDistance = this->Translation().Distance(b.Translation());
259
260 // If the distances are equal sort by difference in rotation
261 if (aDistance == bDistance) {
262 return gcem::abs(this->Rotation()
263 .RelativeTo(a.Rotation())
264 .Angle()
265 .value()) <
266 gcem::abs(this->Rotation()
267 .RelativeTo(b.Rotation())
268 .Angle()
269 .value());
270 }
271 return aDistance < bDistance;
272 });
273 }
274
275 /**
276 * Returns the nearest Pose3d from a collection of poses.
277 *
278 * If two or more poses in the collection have the same distance from this
279 * pose, return the one with the closest rotation component.
280 *
281 * @param poses The collection of poses.
282 * @return The nearest Pose3d from the collection.
283 */
284 constexpr Pose3d Nearest(std::initializer_list<Pose3d> poses) const {
285 return *std::min_element(
286 poses.begin(), poses.end(), [this](const Pose3d& a, const Pose3d& b) {
287 auto aDistance = this->Translation().Distance(a.Translation());
288 auto bDistance = this->Translation().Distance(b.Translation());
289
290 // If the distances are equal sort by difference in rotation
291 if (aDistance == bDistance) {
292 return gcem::abs(this->Rotation()
293 .RelativeTo(a.Rotation())
294 .Angle()
295 .value()) <
296 gcem::abs(this->Rotation()
297 .RelativeTo(b.Rotation())
298 .Angle()
299 .value());
300 }
301 return aDistance < bDistance;
302 });
303 }
304
305 private:
306 Translation3d m_translation;
307 Rotation3d m_rotation;
308};
309
311void to_json(wpi::util::json& json, const Pose3d& pose);
312
314void from_json(const wpi::util::json& json, Pose3d& pose);
315
316} // namespace wpi::math
317
319
320namespace wpi::math {
321
322constexpr Transform3d Pose3d::operator-(const Pose3d& other) const {
323 const auto pose = this->RelativeTo(other);
324 return Transform3d{pose.Translation(), pose.Rotation()};
325}
326
327constexpr Pose3d Pose3d::TransformBy(const Transform3d& other) const {
328 // Rotating the transform's rotation by the pose's rotation extrinsically is
329 // equivalent to rotating the pose's rotation by the transform's rotation
330 // intrinsically. (We define transforms as being applied intrinsically.)
331 return {m_translation + (other.Translation().RotateBy(m_rotation)),
332 other.Rotation().RotateBy(m_rotation)};
333}
334
335constexpr Pose3d Pose3d::RelativeTo(const Pose3d& other) const {
336 const Transform3d transform{other, *this};
337 return {transform.Translation(), transform.Rotation()};
338}
339
340} // namespace wpi::math
341
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:30
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.hpp:31
constexpr Pose3d operator*(double scalar) const
Multiplies the current pose by a scalar.
Definition Pose3d.hpp:160
constexpr Pose3d TransformBy(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Definition Pose3d.hpp:327
constexpr Pose3d(Translation3d translation, Rotation3d rotation)
Constructs a pose with the specified translation and rotation.
Definition Pose3d.hpp:44
constexpr Pose3d(const Pose2d &pose)
Constructs a 3D pose from a 2D pose in the X-Y plane.
Definition Pose3d.hpp:87
constexpr Pose3d RotateBy(const Rotation3d &other) const
Rotates the pose around the origin and returns the new pose.
Definition Pose3d.hpp:183
constexpr Pose3d Nearest(std::initializer_list< Pose3d > poses) const
Returns the nearest Pose3d from a collection of poses.
Definition Pose3d.hpp:284
constexpr Pose3d Nearest(std::span< const Pose3d > poses) const
Returns the nearest Pose3d from a collection of poses.
Definition Pose3d.hpp:254
constexpr wpi::units::meter_t Z() const
Returns the Z component of the pose's translation.
Definition Pose3d.hpp:144
constexpr wpi::units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition Pose3d.hpp:137
constexpr const Translation3d & Translation() const
Returns the underlying translation.
Definition Pose3d.hpp:123
constexpr Eigen::Matrix4d ToMatrix() const
Returns an affine transformation matrix representation of this pose.
Definition Pose3d.hpp:229
constexpr const Rotation3d & Rotation() const
Returns the underlying rotation.
Definition Pose3d.hpp:151
constexpr Pose3d operator+(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Definition Pose3d.hpp:101
constexpr Pose2d ToPose2d() const
Returns a Pose2d representing this Pose3d projected into the X-Y plane.
Definition Pose3d.hpp:241
constexpr bool operator==(const Pose3d &) const =default
Checks equality between this Pose3d and another object.
constexpr wpi::units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose3d.hpp:130
constexpr Pose3d operator/(double scalar) const
Divides the current pose by a scalar.
Definition Pose3d.hpp:171
constexpr Pose3d()=default
Constructs a pose at the origin facing toward the positive X axis.
constexpr Pose3d RelativeTo(const Pose3d &other) const
Returns the current pose relative to the given pose.
Definition Pose3d.hpp:335
constexpr Transform3d operator-(const Pose3d &other) const
Returns the Transform3d that maps the one pose to another.
Definition Pose3d.hpp:322
constexpr Pose3d RotateAround(const Translation3d &point, const Rotation3d &rot) const
Rotates the current pose around a point in 3D space.
Definition Pose3d.hpp:221
constexpr Pose3d(const Eigen::Matrix4d &matrix)
Constructs a pose with the specified affine transformation matrix.
Definition Pose3d.hpp:67
constexpr Pose3d(wpi::units::meter_t x, wpi::units::meter_t y, wpi::units::meter_t z, Rotation3d rotation)
Constructs a pose with x, y, and z translations instead of a separate Translation3d.
Definition Pose3d.hpp:57
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:72
constexpr Rotation3d RotateBy(const Rotation3d &other) const
Adds the new rotation to the current rotation.
Definition Rotation3d.hpp:336
Represents a transformation for a Pose3d in the pose's frame.
Definition Transform3d.hpp:23
constexpr const Rotation3d & Rotation() const
Returns the rotational component of the transformation.
Definition Transform3d.hpp:137
constexpr const Translation3d & Translation() const
Returns the translation component of the transformation.
Definition Transform3d.hpp:96
Represents a translation in 3D space.
Definition Translation3d.hpp:34
Definition json.hpp:85
Definition variable.hpp:1006
Definition StringMap.hpp:773
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