WPILibC++ 2027.0.0-alpha-3
Loading...
Searching...
No Matches
Transform3d.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 <utility>
8
9#include <wpi/SymbolExports.h>
10
13
14namespace frc {
15
16class Pose3d;
17struct Twist3d;
18
19/**
20 * Represents a transformation for a Pose3d in the pose's frame.
21 */
23 public:
24 /**
25 * Constructs the transform that maps the initial pose to the final pose.
26 *
27 * @param initial The initial pose for the transformation.
28 * @param final The final pose for the transformation.
29 */
30 constexpr Transform3d(const Pose3d& initial, const Pose3d& final);
31
32 /**
33 * Constructs a transform with the given translation and rotation components.
34 *
35 * @param translation Translational component of the transform.
36 * @param rotation Rotational component of the transform.
37 */
38 constexpr Transform3d(Translation3d translation, Rotation3d rotation)
39 : m_translation{std::move(translation)},
40 m_rotation{std::move(rotation)} {}
41
42 /**
43 * Constructs a transform with x, y, and z translations instead of a separate
44 * Translation3d.
45 *
46 * @param x The x component of the translational component of the transform.
47 * @param y The y component of the translational component of the transform.
48 * @param z The z component of the translational component of the transform.
49 * @param rotation The rotational component of the transform.
50 */
51 constexpr Transform3d(units::meter_t x, units::meter_t y, units::meter_t z,
52 Rotation3d rotation)
53 : m_translation{x, y, z}, m_rotation{std::move(rotation)} {}
54
55 /**
56 * Constructs a transform with the specified affine transformation matrix.
57 *
58 * @param matrix The affine transformation matrix.
59 * @throws std::domain_error if the affine transformation matrix is invalid.
60 */
61 constexpr explicit Transform3d(const Eigen::Matrix4d& matrix)
62 : m_translation{Eigen::Vector3d{
63 {matrix(0, 3)}, {matrix(1, 3)}, {matrix(2, 3)}}},
64 m_rotation{
65 Eigen::Matrix3d{{matrix(0, 0), matrix(0, 1), matrix(0, 2)},
66 {matrix(1, 0), matrix(1, 1), matrix(1, 2)},
67 {matrix(2, 0), matrix(2, 1), matrix(2, 2)}}} {
68 if (matrix(3, 0) != 0.0 || matrix(3, 1) != 0.0 || matrix(3, 2) != 0.0 ||
69 matrix(3, 3) != 1.0) {
70 throw std::domain_error("Affine transformation matrix is invalid");
71 }
72 }
73
74 /**
75 * Constructs the identity transform -- maps an initial pose to itself.
76 */
77 constexpr Transform3d() = default;
78
79 /**
80 * Constructs a 3D transform from a 2D transform in the X-Y plane.
81 **
82 * @param transform The 2D transform.
83 * @see Rotation3d(Rotation2d)
84 * @see Translation3d(Translation2d)
85 */
86 constexpr explicit Transform3d(const frc::Transform2d& transform)
87 : m_translation{frc::Translation3d{transform.Translation()}},
88 m_rotation{frc::Rotation3d{transform.Rotation()}} {}
89
90 /**
91 * Returns the translation component of the transformation.
92 *
93 * @return Reference to the translational component of the transform.
94 */
95 constexpr const Translation3d& Translation() const { return m_translation; }
96
97 /**
98 * Returns the X component of the transformation's translation.
99 *
100 * @return The x component of the transformation's translation.
101 */
102 constexpr units::meter_t X() const { return m_translation.X(); }
103
104 /**
105 * Returns the Y component of the transformation's translation.
106 *
107 * @return The y component of the transformation's translation.
108 */
109 constexpr units::meter_t Y() const { return m_translation.Y(); }
110
111 /**
112 * Returns the Z component of the transformation's translation.
113 *
114 * @return The z component of the transformation's translation.
115 */
116 constexpr units::meter_t Z() const { return m_translation.Z(); }
117
118 /**
119 * Returns an affine transformation matrix representation of this
120 * transformation.
121 */
122 constexpr Eigen::Matrix4d ToMatrix() const {
123 auto vec = m_translation.ToVector();
124 auto mat = m_rotation.ToMatrix();
125 return Eigen::Matrix4d{{mat(0, 0), mat(0, 1), mat(0, 2), vec(0)},
126 {mat(1, 0), mat(1, 1), mat(1, 2), vec(1)},
127 {mat(2, 0), mat(2, 1), mat(2, 2), vec(2)},
128 {0.0, 0.0, 0.0, 1.0}};
129 }
130
131 /**
132 * Returns the rotational component of the transformation.
133 *
134 * @return Reference to the rotational component of the transform.
135 */
136 constexpr const Rotation3d& Rotation() const { return m_rotation; }
137
138 /**
139 * Returns a Twist3d of the current transform (pose delta). If b is the output
140 * of {@code a.Log()}, then {@code b.Exp()} would yield a.
141 *
142 * @return The twist that maps the current transform.
143 */
144 constexpr Twist3d Log() const;
145
146 /**
147 * Invert the transformation. This is useful for undoing a transformation.
148 *
149 * @return The inverted transformation.
150 */
151 constexpr Transform3d Inverse() const {
152 // We are rotating the difference between the translations
153 // using a clockwise rotation matrix. This transforms the global
154 // delta into a local delta (relative to the initial pose).
155 return Transform3d{(-Translation()).RotateBy(-Rotation()), -Rotation()};
156 }
157
158 /**
159 * Multiplies the transform by the scalar.
160 *
161 * @param scalar The scalar.
162 * @return The scaled Transform3d.
163 */
164 constexpr Transform3d operator*(double scalar) const {
165 return Transform3d(m_translation * scalar, m_rotation * scalar);
166 }
167
168 /**
169 * Divides the transform by the scalar.
170 *
171 * @param scalar The scalar.
172 * @return The scaled Transform3d.
173 */
174 constexpr Transform3d operator/(double scalar) const {
175 return *this * (1.0 / scalar);
176 }
177
178 /**
179 * Composes two transformations. The second transform is applied relative to
180 * the orientation of the first.
181 *
182 * @param other The transform to compose with this one.
183 * @return The composition of the two transformations.
184 */
185 constexpr Transform3d operator+(const Transform3d& other) const;
186
187 /**
188 * Checks equality between this Transform3d and another object.
189 */
190 constexpr bool operator==(const Transform3d&) const = default;
191
192 private:
193 Translation3d m_translation;
194 Rotation3d m_rotation;
195};
196
197} // namespace frc
198
199#include "frc/geometry/Pose3d.h"
200#include "frc/geometry/Twist3d.h"
202
203namespace frc {
204
205constexpr Transform3d::Transform3d(const Pose3d& initial, const Pose3d& final) {
206 // We are rotating the difference between the translations
207 // using a clockwise rotation matrix. This transforms the global
208 // delta into a local delta (relative to the initial pose).
209 m_translation = (final.Translation() - initial.Translation())
210 .RotateBy(-initial.Rotation());
211
212 m_rotation = final.Rotation() - initial.Rotation();
213}
214
215constexpr Transform3d Transform3d::operator+(const Transform3d& other) const {
216 return Transform3d{Pose3d{}, Pose3d{}.TransformBy(*this).TransformBy(other)};
217}
218
219constexpr Twist3d Transform3d::Log() const {
220 // Implementation from Section 3.2 of https://ethaneade.org/lie.pdf
221
222 auto impl = [this]<typename Matrix3d, typename Vector3d>() -> Twist3d {
223 Vector3d u{{m_translation.X().value(), m_translation.Y().value(),
224 m_translation.Z().value()}};
225 Vector3d rvec = m_rotation.ToVector();
226 Matrix3d omega = detail::RotationVectorToMatrix(rvec);
227 Matrix3d omegaSq = omega * omega;
228 double theta = rvec.norm();
229 double thetaSq = theta * theta;
230
231 double C;
232 if (gcem::abs(theta) < 1E-7) {
233 // Taylor Expansions around θ = 0
234 // A = 1/1! - θ²/3! + θ⁴/5!
235 // B = 1/2! - θ²/4! + θ⁴/6!
236 // C = 1/6 * (1/2 + θ²/5! + θ⁴/7!)
237 // sources:
238 // A:
239 // https://www.wolframalpha.com/input?i2d=true&i=series+expansion+of+Divide%5Bsin%5C%2840%29x%5C%2841%29%2Cx%5D+at+x%3D0
240 // B:
241 // https://www.wolframalpha.com/input?i2d=true&i=series+expansion+of+Divide%5B1-cos%5C%2840%29x%5C%2841%29%2CPower%5Bx%2C2%5D%5D+at+x%3D0
242 // C:
243 // https://www.wolframalpha.com/input?i2d=true&i=series+expansion+of+Divide%5B1-Divide%5BDivide%5Bsin%5C%2840%29x%5C%2841%29%2Cx%5D%2C2Divide%5B1-cos%5C%2840%29x%5C%2841%29%2CPower%5Bx%2C2%5D%5D%5D%2CPower%5Bx%2C2%5D%5D+at+x%3D0
244 C = 1 / 12.0 + thetaSq / 720 + thetaSq * thetaSq / 30240;
245 } else {
246 // A = std::sin(θ)/θ
247 // B = (1 - std::cos(θ)) / θ²
248 // C = (1 - A/(2*B)) / θ²
249 double A = gcem::sin(theta) / theta;
250 double B = (1 - gcem::cos(theta)) / thetaSq;
251 C = (1 - A / (2 * B)) / thetaSq;
252 }
253
254 Matrix3d V_inv = Matrix3d::Identity() - 0.5 * omega + C * omegaSq;
255
256 Vector3d translation_component = V_inv * u;
257
258 return Twist3d{units::meter_t{translation_component(0)},
259 units::meter_t{translation_component(1)},
260 units::meter_t{translation_component(2)},
261 units::radian_t{rvec(0)},
262 units::radian_t{rvec(1)},
263 units::radian_t{rvec(2)}};
264 };
265
266 if (std::is_constant_evaluated()) {
267 return impl.template operator()<ct_matrix3d, ct_vector3d>();
268 }
269 return impl.template operator()<Eigen::Matrix3d, Eigen::Vector3d>();
270}
271
272} // namespace frc
273
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:30
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 const Translation3d & Translation() const
Returns the underlying translation.
Definition Pose3d.h:122
constexpr const Rotation3d & Rotation() const
Returns the underlying rotation.
Definition Pose3d.h:150
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
constexpr Eigen::Vector3d ToVector() const
Returns rotation vector representation of this rotation.
Definition Rotation3d.h:432
Represents a transformation for a Pose2d in the pose's frame.
Definition Transform2d.h:22
Represents a transformation for a Pose3d in the pose's frame.
Definition Transform3d.h:22
constexpr const Rotation3d & Rotation() const
Returns the rotational component of the transformation.
Definition Transform3d.h:136
constexpr Eigen::Matrix4d ToMatrix() const
Returns an affine transformation matrix representation of this transformation.
Definition Transform3d.h:122
constexpr units::meter_t X() const
Returns the X component of the transformation's translation.
Definition Transform3d.h:102
constexpr Transform3d(units::meter_t x, units::meter_t y, units::meter_t z, Rotation3d rotation)
Constructs a transform with x, y, and z translations instead of a separate Translation3d.
Definition Transform3d.h:51
constexpr Transform3d operator*(double scalar) const
Multiplies the transform by the scalar.
Definition Transform3d.h:164
constexpr Transform3d operator+(const Transform3d &other) const
Composes two transformations.
Definition Transform3d.h:215
constexpr Transform3d(const Eigen::Matrix4d &matrix)
Constructs a transform with the specified affine transformation matrix.
Definition Transform3d.h:61
constexpr Transform3d()=default
Constructs the identity transform – maps an initial pose to itself.
constexpr Transform3d(Translation3d translation, Rotation3d rotation)
Constructs a transform with the given translation and rotation components.
Definition Transform3d.h:38
constexpr Twist3d Log() const
Returns a Twist3d of the current transform (pose delta).
Definition Transform3d.h:219
constexpr bool operator==(const Transform3d &) const =default
Checks equality between this Transform3d and another object.
constexpr units::meter_t Y() const
Returns the Y component of the transformation's translation.
Definition Transform3d.h:109
constexpr Transform3d Inverse() const
Invert the transformation.
Definition Transform3d.h:151
constexpr Transform3d operator/(double scalar) const
Divides the transform by the scalar.
Definition Transform3d.h:174
constexpr const Translation3d & Translation() const
Returns the translation component of the transformation.
Definition Transform3d.h:95
constexpr Transform3d(const frc::Transform2d &transform)
Constructs a 3D transform from a 2D transform in the X-Y plane.
Definition Transform3d.h:86
constexpr units::meter_t Z() const
Returns the Z component of the transformation's translation.
Definition Transform3d.h:116
Represents a translation in 3D space.
Definition Translation3d.h:31
constexpr Translation3d RotateBy(const Rotation3d &other) const
Applies a rotation to the translation in 3D space.
Definition Translation3d.h:178
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation3d.h:130
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation3d.h:123
constexpr units::meter_t Z() const
Returns the Z component of the translation.
Definition Translation3d.h:137
Compile-time wrapper for Eigen::Matrix.
Definition ct_matrix.h:26
Definition variable.hpp:742
constexpr ct_matrix3d RotationVectorToMatrix(const ct_vector3d &rotation)
Definition RotationVectorToMatrix.h:13
Definition SystemServer.h:9
ct_matrix< double, 3, 3 > ct_matrix3d
Definition ct_matrix.h:385
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr return_t< T > cos(const T x) noexcept
Compile-time cosine function.
Definition cos.hpp:83
constexpr return_t< T > sin(const T x) noexcept
Compile-time sine function.
Definition sin.hpp:85
Definition PointerIntPair.h:280
A change in distance along a 3D arc since the last pose update.
Definition Twist3d.h:24