WPILibC++ 2026.2.1
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;
17
18/**
19 * Represents a transformation for a Pose3d in the pose's frame. Translation is
20 * applied before rotation. (The translation is applied in the pose's original
21 * frame, not the transformed frame.)
22 */
24 public:
25 /**
26 * Constructs the transform that maps the initial pose to the final pose.
27 *
28 * @param initial The initial pose for the transformation.
29 * @param final The final pose for the transformation.
30 */
31 constexpr Transform3d(const Pose3d& initial, const Pose3d& final);
32
33 /**
34 * Constructs a transform with the given translation and rotation components.
35 *
36 * @param translation Translational component of the transform.
37 * @param rotation Rotational component of the transform.
38 */
39 constexpr Transform3d(Translation3d translation, Rotation3d rotation)
40 : m_translation{std::move(translation)},
41 m_rotation{std::move(rotation)} {}
42
43 /**
44 * Constructs a transform with x, y, and z translations instead of a separate
45 * Translation3d.
46 *
47 * @param x The x component of the translational component of the transform.
48 * @param y The y component of the translational component of the transform.
49 * @param z The z component of the translational component of the transform.
50 * @param rotation The rotational component of the transform.
51 */
52 constexpr Transform3d(units::meter_t x, units::meter_t y, units::meter_t z,
53 Rotation3d rotation)
54 : m_translation{x, y, z}, m_rotation{std::move(rotation)} {}
55
56 /**
57 * Constructs a transform with the specified affine transformation matrix.
58 *
59 * @param matrix The affine transformation matrix.
60 * @throws std::domain_error if the affine transformation matrix is invalid.
61 */
62 constexpr explicit Transform3d(const Eigen::Matrix4d& matrix)
63 : m_translation{Eigen::Vector3d{
64 {matrix(0, 3)}, {matrix(1, 3)}, {matrix(2, 3)}}},
65 m_rotation{
66 Eigen::Matrix3d{{matrix(0, 0), matrix(0, 1), matrix(0, 2)},
67 {matrix(1, 0), matrix(1, 1), matrix(1, 2)},
68 {matrix(2, 0), matrix(2, 1), matrix(2, 2)}}} {
69 if (matrix(3, 0) != 0.0 || matrix(3, 1) != 0.0 || matrix(3, 2) != 0.0 ||
70 matrix(3, 3) != 1.0) {
71 throw std::domain_error("Affine transformation matrix is invalid");
72 }
73 }
74
75 /**
76 * Constructs the identity transform -- maps an initial pose to itself.
77 */
78 constexpr Transform3d() = default;
79
80 /**
81 * Constructs a 3D transform from a 2D transform in the X-Y plane.
82 **
83 * @param transform The 2D transform.
84 * @see Rotation3d(Rotation2d)
85 * @see Translation3d(Translation2d)
86 */
87 constexpr explicit Transform3d(const frc::Transform2d& transform)
88 : m_translation{frc::Translation3d{transform.Translation()}},
89 m_rotation{frc::Rotation3d{transform.Rotation()}} {}
90
91 /**
92 * Returns the translation component of the transformation.
93 *
94 * @return Reference to the translational component of the transform.
95 */
96 constexpr const Translation3d& Translation() const { return m_translation; }
97
98 /**
99 * Returns the X component of the transformation's translation.
100 *
101 * @return The x component of the transformation's translation.
102 */
103 constexpr units::meter_t X() const { return m_translation.X(); }
104
105 /**
106 * Returns the Y component of the transformation's translation.
107 *
108 * @return The y component of the transformation's translation.
109 */
110 constexpr units::meter_t Y() const { return m_translation.Y(); }
111
112 /**
113 * Returns the Z component of the transformation's translation.
114 *
115 * @return The z component of the transformation's translation.
116 */
117 constexpr units::meter_t Z() const { return m_translation.Z(); }
118
119 /**
120 * Returns an affine transformation matrix representation of this
121 * transformation.
122 */
123 constexpr Eigen::Matrix4d ToMatrix() const {
124 auto vec = m_translation.ToVector();
125 auto mat = m_rotation.ToMatrix();
126 return Eigen::Matrix4d{{mat(0, 0), mat(0, 1), mat(0, 2), vec(0)},
127 {mat(1, 0), mat(1, 1), mat(1, 2), vec(1)},
128 {mat(2, 0), mat(2, 1), mat(2, 2), vec(2)},
129 {0.0, 0.0, 0.0, 1.0}};
130 }
131
132 /**
133 * Returns the rotational component of the transformation.
134 *
135 * @return Reference to the rotational component of the transform.
136 */
137 constexpr const Rotation3d& Rotation() const { return m_rotation; }
138
139 /**
140 * Invert the transformation. This is useful for undoing a transformation.
141 *
142 * @return The inverted transformation.
143 */
144 constexpr Transform3d Inverse() const {
145 // We are rotating the difference between the translations
146 // using a clockwise rotation matrix. This transforms the global
147 // delta into a local delta (relative to the initial pose).
148 return Transform3d{(-Translation()).RotateBy(-Rotation()), -Rotation()};
149 }
150
151 /**
152 * Multiplies the transform by the scalar.
153 *
154 * @param scalar The scalar.
155 * @return The scaled Transform3d.
156 */
157 constexpr Transform3d operator*(double scalar) const {
158 return Transform3d(m_translation * scalar, m_rotation * scalar);
159 }
160
161 /**
162 * Divides the transform by the scalar.
163 *
164 * @param scalar The scalar.
165 * @return The scaled Transform3d.
166 */
167 constexpr Transform3d operator/(double scalar) const {
168 return *this * (1.0 / scalar);
169 }
170
171 /**
172 * Composes two transformations. The second transform is applied relative to
173 * the orientation of the first.
174 *
175 * @param other The transform to compose with this one.
176 * @return The composition of the two transformations.
177 */
178 constexpr Transform3d operator+(const Transform3d& other) const;
179
180 /**
181 * Checks equality between this Transform3d and another object.
182 */
183 constexpr bool operator==(const Transform3d&) const = default;
184
185 private:
186 Translation3d m_translation;
187 Rotation3d m_rotation;
188};
189
190} // namespace frc
191
192#include "frc/geometry/Pose3d.h"
193
194namespace frc {
195
196constexpr Transform3d::Transform3d(const Pose3d& initial, const Pose3d& final) {
197 // To transform the global translation delta to be relative to the initial
198 // pose, rotate by the inverse of the initial pose's orientation.
199 m_translation = (final.Translation() - initial.Translation())
200 .RotateBy(-initial.Rotation());
201
202 m_rotation = final.Rotation().RelativeTo(initial.Rotation());
203}
204
205constexpr Transform3d Transform3d::operator+(const Transform3d& other) const {
206 return Transform3d{Pose3d{}, Pose3d{}.TransformBy(*this).TransformBy(other)};
207}
208
209} // namespace frc
210
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:31
constexpr Pose3d TransformBy(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Definition Pose3d.h:394
constexpr const Translation3d & Translation() const
Returns the underlying translation.
Definition Pose3d.h:123
constexpr const Rotation3d & Rotation() const
Returns the underlying rotation.
Definition Pose3d.h:151
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.h:72
constexpr Rotation3d RelativeTo(const Rotation3d &other) const
Returns the current rotation relative to the given rotation.
Definition Rotation3d.h:399
Represents a transformation for a Pose2d in the pose's frame.
Definition Transform2d.h:21
Represents a transformation for a Pose3d in the pose's frame.
Definition Transform3d.h:23
constexpr const Rotation3d & Rotation() const
Returns the rotational component of the transformation.
Definition Transform3d.h:137
constexpr Eigen::Matrix4d ToMatrix() const
Returns an affine transformation matrix representation of this transformation.
Definition Transform3d.h:123
constexpr units::meter_t X() const
Returns the X component of the transformation's translation.
Definition Transform3d.h:103
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:52
constexpr Transform3d operator*(double scalar) const
Multiplies the transform by the scalar.
Definition Transform3d.h:157
constexpr Transform3d operator+(const Transform3d &other) const
Composes two transformations.
Definition Transform3d.h:205
constexpr Transform3d(const Eigen::Matrix4d &matrix)
Constructs a transform with the specified affine transformation matrix.
Definition Transform3d.h:62
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:39
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:110
constexpr Transform3d Inverse() const
Invert the transformation.
Definition Transform3d.h:144
constexpr Transform3d operator/(double scalar) const
Divides the transform by the scalar.
Definition Transform3d.h:167
constexpr const Translation3d & Translation() const
Returns the translation component of the transformation.
Definition Transform3d.h:96
constexpr Transform3d(const frc::Transform2d &transform)
Constructs a 3D transform from a 2D transform in the X-Y plane.
Definition Transform3d.h:87
constexpr units::meter_t Z() const
Returns the Z component of the transformation's translation.
Definition Transform3d.h:117
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
Definition variable.hpp:742
Definition CAN.h:11
Implement std::hash so that hash_code can be used in STL containers.
Definition PointerIntPair.h:280