8#include <initializer_list>
42 : m_translation{
std::move(translation)},
43 m_rotation{
std::move(rotation)} {}
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");
86 return TransformBy(other);
114 constexpr units::meter_t
X()
const {
return m_translation.X(); }
121 constexpr units::meter_t
Y()
const {
return m_translation.Y(); }
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)};
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)},
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());
256 if (aDistance == bDistance) {
258 (this->Rotation() - a.Rotation()).Radians().value()) <
260 (this->Rotation() - b.Rotation()).Radians().value());
262 return aDistance < bDistance;
272 return *std::min_element(
273 poses.begin(), poses.end(), [
this](
const Pose2d& a,
const Pose2d& b) {
274 auto aDistance = this->Translation().Distance(a.Translation());
275 auto bDistance = this->Translation().Distance(b.Translation());
278 if (aDistance == bDistance) {
280 (this->Rotation() - a.Rotation()).Radians().value()) <
282 (this->Rotation() - b.Rotation()).Radians().value());
284 return aDistance < bDistance;
289 Translation2d m_translation;
290 Rotation2d m_rotation;
310 return Transform2d{pose.Translation(), pose.Rotation()};
314 return {m_translation + (other.Translation().
RotateBy(m_rotation)),
315 other.Rotation() + m_rotation};
320 return {transform.Translation(), transform.Rotation()};
324 const auto dx = twist.
dx;
325 const auto dy = twist.
dy;
326 const auto dtheta = twist.
dtheta.value();
333 s = 1.0 - 1.0 / 6.0 * dtheta * dtheta;
336 s = sinTheta / dtheta;
337 c = (1 - cosTheta) / dtheta;
343 return *
this + transform;
347 const auto transform = end.RelativeTo(*
this);
348 const auto dtheta = transform.Rotation().Radians().value();
349 const auto halfDtheta = dtheta / 2.0;
351 const auto cosMinusOne = transform.Rotation().Cos() - 1;
353 double halfThetaByTanOfHalfDtheta;
356 halfThetaByTanOfHalfDtheta = 1.0 - 1.0 / 12.0 * dtheta * dtheta;
358 halfThetaByTanOfHalfDtheta =
359 -(halfDtheta * transform.Rotation().Sin()) / cosMinusOne;
364 {halfThetaByTanOfHalfDtheta, -halfDtheta}) *
365 gcem::hypot(halfThetaByTanOfHalfDtheta, halfDtheta);
367 return {translationPart.
X(), translationPart.
Y(), units::radian_t{dtheta}};
#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:313
constexpr Transform2d operator-(const Pose2d &other) const
Returns the Transform2d that maps the one pose to another.
Definition Pose2d.h:308
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:318
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:346
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:249
constexpr Pose2d Exp(const Twist2d &twist) const
Obtain a new Pose2d from a (constant curvature) velocity.
Definition Pose2d.h:323
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:271
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:31
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:739
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
Implement std::hash so that hash_code can be used in STL containers.
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