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