WPILibC++ 2027.0.0-alpha-2
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
19#include "units/length.h"
20
21namespace frc {
22
23class Transform2d;
24
25/**
26 * Represents a 2D pose containing translational and rotational elements.
27 */
29 public:
30 /**
31 * Constructs a pose at the origin facing toward the positive X axis.
32 */
33 constexpr Pose2d() = default;
34
35 /**
36 * Constructs a pose with the specified translation and rotation.
37 *
38 * @param translation The translational component of the pose.
39 * @param rotation The rotational component of the pose.
40 */
41 constexpr Pose2d(Translation2d translation, Rotation2d rotation)
42 : m_translation{std::move(translation)},
43 m_rotation{std::move(rotation)} {}
44
45 /**
46 * Constructs a pose with x and y translations instead of a separate
47 * Translation2d.
48 *
49 * @param x The x component of the translational component of the pose.
50 * @param y The y component of the translational component of the pose.
51 * @param rotation The rotational component of the pose.
52 */
53 constexpr Pose2d(units::meter_t x, units::meter_t y, 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 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 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 * Obtain a new Pose2d from a (constant curvature) velocity.
202 *
203 * See https://file.tavsys.net/control/controls-engineering-in-frc.pdf section
204 * 10.2 "Pose exponential" for a derivation.
205 *
206 * The twist is a change in pose in the robot's coordinate frame since the
207 * previous pose update. When the user runs exp() on the previous known
208 * field-relative pose with the argument being the twist, the user will
209 * receive the new field-relative pose.
210 *
211 * "Exp" represents the pose exponential, which is solving a differential
212 * equation moving the pose forward in time.
213 *
214 * @param twist The change in pose in the robot's coordinate frame since the
215 * previous pose update. For example, if a non-holonomic robot moves forward
216 * 0.01 meters and changes angle by 0.5 degrees since the previous pose
217 * update, the twist would be Twist2d{0.01_m, 0_m, 0.5_deg}.
218 *
219 * @return The new pose of the robot.
220 */
221 constexpr Pose2d Exp(const Twist2d& twist) const;
222
223 /**
224 * Returns a Twist2d that maps this pose to the end pose. If c is the output
225 * of a.Log(b), then a.Exp(c) would yield b.
226 *
227 * @param end The end pose for the transformation.
228 *
229 * @return The twist that maps this to end.
230 */
231 constexpr Twist2d Log(const Pose2d& end) const;
232
233 /**
234 * Returns an affine transformation matrix representation of this pose.
235 */
236 constexpr Eigen::Matrix3d ToMatrix() const {
237 auto vec = m_translation.ToVector();
238 auto mat = m_rotation.ToMatrix();
239 return Eigen::Matrix3d{{mat(0, 0), mat(0, 1), vec(0)},
240 {mat(1, 0), mat(1, 1), vec(1)},
241 {0.0, 0.0, 1.0}};
242 }
243
244 /**
245 * Returns the nearest Pose2d from a collection of poses.
246 *
247 * If two or more poses in the collection have the same distance from this
248 * pose, return the one with the closest rotation component.
249 *
250 * @param poses The collection of poses.
251 * @return The nearest Pose2d from the collection.
252 */
253 constexpr Pose2d Nearest(std::span<const Pose2d> poses) const {
254 return *std::min_element(
255 poses.begin(), poses.end(), [this](const Pose2d& a, const Pose2d& b) {
256 auto aDistance = this->Translation().Distance(a.Translation());
257 auto bDistance = this->Translation().Distance(b.Translation());
258
259 // If the distances are equal sort by difference in rotation
260 if (aDistance == bDistance) {
261 return gcem::abs(
262 (this->Rotation() - a.Rotation()).Radians().value()) <
263 gcem::abs(
264 (this->Rotation() - b.Rotation()).Radians().value());
265 }
266 return aDistance < bDistance;
267 });
268 }
269
270 /**
271 * Returns the nearest Pose2d from a collection of poses.
272 *
273 * If two or more poses in the collection have the same distance from this
274 * pose, return the one with the closest rotation component.
275 *
276 * @param poses The collection of poses.
277 * @return The nearest Pose2d from the collection.
278 */
279 constexpr Pose2d Nearest(std::initializer_list<Pose2d> poses) const {
280 return *std::min_element(
281 poses.begin(), poses.end(), [this](const Pose2d& a, const Pose2d& b) {
282 auto aDistance = this->Translation().Distance(a.Translation());
283 auto bDistance = this->Translation().Distance(b.Translation());
284
285 // If the distances are equal sort by difference in rotation
286 if (aDistance == bDistance) {
287 return gcem::abs(
288 (this->Rotation() - a.Rotation()).Radians().value()) <
289 gcem::abs(
290 (this->Rotation() - b.Rotation()).Radians().value());
291 }
292 return aDistance < bDistance;
293 });
294 }
295
296 private:
297 Translation2d m_translation;
298 Rotation2d m_rotation;
299};
300
302void to_json(wpi::json& json, const Pose2d& pose);
303
305void from_json(const wpi::json& json, Pose2d& pose);
306
307} // namespace frc
308
311
313
314namespace frc {
315
316constexpr Transform2d Pose2d::operator-(const Pose2d& other) const {
317 const auto pose = this->RelativeTo(other);
318 return Transform2d{pose.Translation(), pose.Rotation()};
319}
320
321constexpr Pose2d Pose2d::TransformBy(const frc::Transform2d& other) const {
322 return {m_translation + (other.Translation().RotateBy(m_rotation)),
323 other.Rotation() + m_rotation};
324}
325
326constexpr Pose2d Pose2d::RelativeTo(const Pose2d& other) const {
327 const Transform2d transform{other, *this};
328 return {transform.Translation(), transform.Rotation()};
329}
330
331constexpr Pose2d Pose2d::Exp(const Twist2d& twist) const {
332 const auto dx = twist.dx;
333 const auto dy = twist.dy;
334 const auto dtheta = twist.dtheta.value();
335
336 const auto sinTheta = gcem::sin(dtheta);
337 const auto cosTheta = gcem::cos(dtheta);
338
339 double s, c;
340 if (gcem::abs(dtheta) < 1E-9) {
341 s = 1.0 - 1.0 / 6.0 * dtheta * dtheta;
342 c = 0.5 * dtheta;
343 } else {
344 s = sinTheta / dtheta;
345 c = (1 - cosTheta) / dtheta;
346 }
347
348 const Transform2d transform{Translation2d{dx * s - dy * c, dx * c + dy * s},
349 Rotation2d{cosTheta, sinTheta}};
350
351 return *this + transform;
352}
353
354constexpr Twist2d Pose2d::Log(const Pose2d& end) const {
355 const auto transform = end.RelativeTo(*this);
356 const auto dtheta = transform.Rotation().Radians().value();
357 const auto halfDtheta = dtheta / 2.0;
358
359 const auto cosMinusOne = transform.Rotation().Cos() - 1;
360
361 double halfThetaByTanOfHalfDtheta;
362
363 if (gcem::abs(cosMinusOne) < 1E-9) {
364 halfThetaByTanOfHalfDtheta = 1.0 - 1.0 / 12.0 * dtheta * dtheta;
365 } else {
366 halfThetaByTanOfHalfDtheta =
367 -(halfDtheta * transform.Rotation().Sin()) / cosMinusOne;
368 }
369
370 const Translation2d translationPart =
371 transform.Translation().RotateBy(
372 {halfThetaByTanOfHalfDtheta, -halfDtheta}) *
373 gcem::hypot(halfThetaByTanOfHalfDtheta, halfDtheta);
374
375 return {translationPart.X(), translationPart.Y(), units::radian_t{dtheta}};
376}
377
378} // 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:28
constexpr Pose2d TransformBy(const Transform2d &other) const
Transforms the pose by the given transformation and returns the new pose.
Definition Pose2d.h:321
constexpr Transform2d operator-(const Pose2d &other) const
Returns the Transform2d that maps the one pose to another.
Definition Pose2d.h:316
constexpr Pose2d operator+(const Transform2d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Definition Pose2d.h:85
constexpr Pose2d(Translation2d translation, Rotation2d rotation)
Constructs a pose with the specified translation and rotation.
Definition Pose2d.h:41
constexpr Pose2d RotateAround(const Translation2d &point, const Rotation2d &rot) const
Rotates the current pose around a point in 2D space.
Definition Pose2d.h:195
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:128
constexpr Pose2d operator*(double scalar) const
Multiplies the current pose by a scalar.
Definition Pose2d.h:137
constexpr units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition Pose2d.h:121
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:53
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose2d.h:114
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:159
constexpr Pose2d RelativeTo(const Pose2d &other) const
Returns the current pose relative to the given pose.
Definition Pose2d.h:326
constexpr Pose2d(const Eigen::Matrix3d &matrix)
Constructs a pose with the specified affine transformation matrix.
Definition Pose2d.h:62
constexpr Twist2d Log(const Pose2d &end) const
Returns a Twist2d that maps this pose to the end pose.
Definition Pose2d.h:354
constexpr Pose2d operator/(double scalar) const
Divides the current pose by a scalar.
Definition Pose2d.h:148
constexpr Pose2d Nearest(std::span< const Pose2d > poses) const
Returns the nearest Pose2d from a collection of poses.
Definition Pose2d.h:253
constexpr Pose2d Exp(const Twist2d &twist) const
Obtain a new Pose2d from a (constant curvature) velocity.
Definition Pose2d.h:331
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition Pose2d.h:107
constexpr Pose2d Nearest(std::initializer_list< Pose2d > poses) const
Returns the nearest Pose2d from a collection of poses.
Definition Pose2d.h:279
constexpr Eigen::Matrix3d ToMatrix() const
Returns an affine transformation matrix representation of this pose.
Definition Pose2d.h:236
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:21
Represents a translation in 2D space.
Definition Translation2d.h:29
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.h:83
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition Translation2d.h:135
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.h:90
Definition variable.hpp:735
Definition SystemServer.h:9
WPILIB_DLLEXPORT void to_json(wpi::json &json, const Rotation3d &rotation)
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr return_t< T > cos(const T x) noexcept
Compile-time cosine function.
Definition cos.hpp:83
constexpr return_t< T > sin(const T x) noexcept
Compile-time sine function.
Definition sin.hpp:85
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:22
units::meter_t dy
Linear "dy" component.
Definition Twist2d.h:31
units::meter_t dx
Linear "dx" component.
Definition Twist2d.h:26
units::radian_t dtheta
Angular "dtheta" component (radians)
Definition Twist2d.h:36
Type representing an arbitrary unit.
Definition base.h:888