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