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