WPILibC++ 2027.0.0-alpha-3
Loading...
Searching...
No Matches
Transform2d.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 Pose2d;
17struct Twist2d;
18
19/**
20 * Represents a transformation for a Pose2d 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 Transform2d(const Pose2d& initial, const Pose2d& 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 Transform2d(Translation2d translation, Rotation2d rotation)
39 : m_translation{std::move(translation)},
40 m_rotation{std::move(rotation)} {}
41
42 /**
43 * Constructs a transform with x and y translations instead of a separate
44 * Translation2d.
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 rotation The rotational component of the transform.
49 */
50 constexpr Transform2d(units::meter_t x, units::meter_t y, Rotation2d rotation)
51 : m_translation{x, y}, m_rotation{std::move(rotation)} {}
52
53 /**
54 * Constructs a pose with the specified affine transformation matrix.
55 *
56 * @param matrix The affine transformation matrix.
57 * @throws std::domain_error if the affine transformation matrix is invalid.
58 */
59 constexpr explicit Transform2d(const Eigen::Matrix3d& matrix)
60 : m_translation{Eigen::Vector2d{{matrix(0, 2)}, {matrix(1, 2)}}},
61 m_rotation{Eigen::Matrix2d{{matrix(0, 0), matrix(0, 1)},
62 {matrix(1, 0), matrix(1, 1)}}} {
63 if (matrix(2, 0) != 0.0 || matrix(2, 1) != 0.0 || matrix(2, 2) != 1.0) {
64 throw std::domain_error("Affine transformation matrix is invalid");
65 }
66 }
67
68 /**
69 * Constructs the identity transform -- maps an initial pose to itself.
70 */
71 constexpr Transform2d() = default;
72
73 /**
74 * Returns the translation component of the transformation.
75 *
76 * @return Reference to the translational component of the transform.
77 */
78 constexpr const Translation2d& Translation() const { return m_translation; }
79
80 /**
81 * Returns the X component of the transformation's translation.
82 *
83 * @return The x component of the transformation's translation.
84 */
85 constexpr units::meter_t X() const { return m_translation.X(); }
86
87 /**
88 * Returns the Y component of the transformation's translation.
89 *
90 * @return The y component of the transformation's translation.
91 */
92 constexpr units::meter_t Y() const { return m_translation.Y(); }
93
94 /**
95 * Returns an affine transformation matrix representation of this
96 * transformation.
97 */
98 constexpr Eigen::Matrix3d ToMatrix() const {
99 auto vec = m_translation.ToVector();
100 auto mat = m_rotation.ToMatrix();
101 return Eigen::Matrix3d{{mat(0, 0), mat(0, 1), vec(0)},
102 {mat(1, 0), mat(1, 1), vec(1)},
103 {0.0, 0.0, 1.0}};
104 }
105
106 /**
107 * Returns the rotational component of the transformation.
108 *
109 * @return Reference to the rotational component of the transform.
110 */
111 constexpr const Rotation2d& Rotation() const { return m_rotation; }
112
113 /**
114 * Returns a Twist2d of the current transform (pose delta). If b is the output
115 * of {@code a.Log()}, then {@code b.Exp()} would yield a.
116 *
117 * @return The twist that maps the current transform.
118 */
119 constexpr Twist2d Log() const;
120
121 /**
122 * Invert the transformation. This is useful for undoing a transformation.
123 *
124 * @return The inverted transformation.
125 */
126 constexpr Transform2d Inverse() const {
127 // We are rotating the difference between the translations
128 // using a clockwise rotation matrix. This transforms the global
129 // delta into a local delta (relative to the initial pose).
130 return Transform2d{(-Translation()).RotateBy(-Rotation()), -Rotation()};
131 }
132
133 /**
134 * Multiplies the transform by the scalar.
135 *
136 * @param scalar The scalar.
137 * @return The scaled Transform2d.
138 */
139 constexpr Transform2d operator*(double scalar) const {
140 return Transform2d(m_translation * scalar, m_rotation * scalar);
141 }
142
143 /**
144 * Divides the transform by the scalar.
145 *
146 * @param scalar The scalar.
147 * @return The scaled Transform2d.
148 */
149 constexpr Transform2d operator/(double scalar) const {
150 return *this * (1.0 / scalar);
151 }
152
153 /**
154 * Composes two transformations. The second transform is applied relative to
155 * the orientation of the first.
156 *
157 * @param other The transform to compose with this one.
158 * @return The composition of the two transformations.
159 */
160 constexpr Transform2d operator+(const Transform2d& other) const;
161
162 /**
163 * Checks equality between this Transform2d and another object.
164 */
165 constexpr bool operator==(const Transform2d&) const = default;
166
167 private:
168 Translation2d m_translation;
169 Rotation2d m_rotation;
170};
171
172} // namespace frc
173
174#include "frc/geometry/Pose2d.h"
175#include "frc/geometry/Twist2d.h"
176
177namespace frc {
178
179constexpr Transform2d::Transform2d(const Pose2d& initial, const Pose2d& final) {
180 // We are rotating the difference between the translations
181 // using a clockwise rotation matrix. This transforms the global
182 // delta into a local delta (relative to the initial pose).
183 m_translation = (final.Translation() - initial.Translation())
184 .RotateBy(-initial.Rotation());
185
186 m_rotation = final.Rotation() - initial.Rotation();
187}
188
189constexpr Transform2d Transform2d::operator+(const Transform2d& other) const {
190 return Transform2d{Pose2d{}, Pose2d{}.TransformBy(*this).TransformBy(other)};
191}
192
193constexpr Twist2d Transform2d::Log() const {
194 const auto dtheta = m_rotation.Radians().value();
195 const auto halfDtheta = dtheta / 2.0;
196
197 const auto cosMinusOne = m_rotation.Cos() - 1;
198
199 double halfThetaByTanOfHalfDtheta;
200
201 if (gcem::abs(cosMinusOne) < 1E-9) {
202 halfThetaByTanOfHalfDtheta = 1.0 - 1.0 / 12.0 * dtheta * dtheta;
203 } else {
204 halfThetaByTanOfHalfDtheta = -(halfDtheta * m_rotation.Sin()) / cosMinusOne;
205 }
206
207 const Translation2d translationPart =
208 m_translation.RotateBy({halfThetaByTanOfHalfDtheta, -halfDtheta}) *
209 gcem::hypot(halfThetaByTanOfHalfDtheta, halfDtheta);
210
211 return {translationPart.X(), translationPart.Y(), units::radian_t{dtheta}};
212}
213
214} // namespace frc
215
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:27
constexpr Pose2d TransformBy(const Transform2d &other) const
Transforms the pose by the given transformation and returns the new pose.
Definition Pose2d.h:287
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition Pose2d.h:127
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition Pose2d.h:106
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:26
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.h:222
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.h:229
constexpr units::radian_t Radians() const
Returns the radian value of the rotation constrained within [-π, π].
Definition Rotation2d.h:206
Represents a transformation for a Pose2d in the pose's frame.
Definition Transform2d.h:22
constexpr const Translation2d & Translation() const
Returns the translation component of the transformation.
Definition Transform2d.h:78
constexpr units::meter_t X() const
Returns the X component of the transformation's translation.
Definition Transform2d.h:85
constexpr Transform2d(Translation2d translation, Rotation2d rotation)
Constructs a transform with the given translation and rotation components.
Definition Transform2d.h:38
constexpr Transform2d Inverse() const
Invert the transformation.
Definition Transform2d.h:126
constexpr const Rotation2d & Rotation() const
Returns the rotational component of the transformation.
Definition Transform2d.h:111
constexpr Transform2d(const Eigen::Matrix3d &matrix)
Constructs a pose with the specified affine transformation matrix.
Definition Transform2d.h:59
constexpr Eigen::Matrix3d ToMatrix() const
Returns an affine transformation matrix representation of this transformation.
Definition Transform2d.h:98
constexpr bool operator==(const Transform2d &) const =default
Checks equality between this Transform2d and another object.
constexpr Transform2d()=default
Constructs the identity transform – maps an initial pose to itself.
constexpr units::meter_t Y() const
Returns the Y component of the transformation's translation.
Definition Transform2d.h:92
constexpr Transform2d(units::meter_t x, units::meter_t y, Rotation2d rotation)
Constructs a transform with x and y translations instead of a separate Translation2d.
Definition Transform2d.h:50
constexpr Transform2d operator/(double scalar) const
Divides the transform by the scalar.
Definition Transform2d.h:149
constexpr Transform2d operator*(double scalar) const
Multiplies the transform by the scalar.
Definition Transform2d.h:139
constexpr Twist2d Log() const
Returns a Twist2d of the current transform (pose delta).
Definition Transform2d.h:193
constexpr Transform2d operator+(const Transform2d &other) const
Composes two transformations.
Definition Transform2d.h:189
Represents a translation in 2D space.
Definition Translation2d.h:30
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.h:101
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition Translation2d.h:164
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.h:108
Definition variable.hpp:742
Definition SystemServer.h:9
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr common_return_t< T1, T2 > hypot(const T1 x, const T2 y) noexcept
Compile-time Pythagorean addition function.
Definition hypot.hpp:147
Definition PointerIntPair.h:280
A change in distance along a 2D arc since the last pose update.
Definition Twist2d.h:24