7#include <initializer_list>
89 constexpr units::meter_t
X()
const {
return m_translation.X(); }
96 constexpr units::meter_t
Y()
const {
return m_translation.Y(); }
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Pose2d Nearest(std::span< const Pose2d > poses) const
Returns the nearest Pose2d from a collection of poses.
Transform2d operator-(const Pose2d &other) const
Returns the Transform2d that maps the one pose to another.
Pose2d Nearest(std::initializer_list< Pose2d > poses) const
Returns the nearest Pose2d from a collection of poses.
Twist2d Log(const Pose2d &end) const
Returns a Twist2d that maps this pose to the end pose.
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:103
constexpr units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition: Pose2d.h:96
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition: Pose2d.h:89
Pose2d Exp(const Twist2d &twist) const
Obtain a new Pose2d from a (constant curvature) velocity.
bool operator==(const Pose2d &) const =default
Checks equality between this Pose2d and another object.
Pose2d RelativeTo(const Pose2d &other) const
Returns the current pose relative to the given pose.
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition: Pose2d.h:82
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Represents a translation in 2D space.
Definition: Translation2d.h:27
Definition: AprilTagPoseEstimator.h:15
WPILIB_DLLEXPORT void from_json(const wpi::json &json, AprilTagFieldLayout &layout)
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13
WPILIB_DLLEXPORT void to_json(wpi::json &json, const AprilTagFieldLayout &layout)
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510
constexpr dimensionless::scalar_t operator/(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept
Division for convertible unit_t types with a linear scale.
Definition: base.h:2644
constexpr unit_t< Units, T, NonLinearScale > operator+(const unit_t< Units, T, NonLinearScale > &u) noexcept
Definition: base.h:2328
constexpr auto operator*(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept -> unit_t< compound_unit< squared< typename units::traits::unit_t_traits< UnitTypeLhs >::unit_type > > >
Multiplication type for convertible unit_t types with a linear scale.
Definition: base.h:2588
A change in distance along a 2D arc since the last pose update.
Definition: Twist2d.h:21