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