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