8#include <initializer_list>
16#include "wpi/units/length.hpp"
41 : m_translation{
std::move(translation)},
42 m_rotation{
std::move(rotation)} {}
52 constexpr Pose2d(wpi::units::meter_t x, wpi::units::meter_t y,
54 : m_translation{x, y}, m_rotation{
std::move(rotation)} {}
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");
114 constexpr wpi::units::meter_t
X()
const {
return m_translation.X(); }
121 constexpr wpi::units::meter_t
Y()
const {
return m_translation.Y(); }
138 return Pose2d{m_translation * scalar, m_rotation * scalar};
149 return *
this * (1.0 / scalar);
160 return {m_translation.RotateBy(other), m_rotation.RotateBy(other)};
197 return {m_translation.RotateAround(point, rot), m_rotation.RotateBy(rot)};
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)},
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());
227 if (aDistance == bDistance) {
229 (this->Rotation() - a.Rotation()).Radians().value()) <
231 (this->Rotation() - b.Rotation()).Radians().value());
233 return aDistance < bDistance;
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());
253 if (aDistance == bDistance) {
255 (this->Rotation() - a.Rotation()).Radians().value()) <
257 (this->Rotation() - b.Rotation()).Radians().value());
259 return aDistance < bDistance;
264 Translation2d m_translation;
265 Rotation2d m_rotation;
284 return Transform2d{pose.Translation(), pose.Rotation()};
#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 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)