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