8#include <initializer_list>
42 : m_translation{
std::move(translation)},
43 m_rotation{
std::move(rotation)} {}
54 constexpr Pose3d(wpi::units::meter_t x, wpi::units::meter_t y,
56 : m_translation{x, y, z}, m_rotation{
std::move(rotation)} {}
64 constexpr explicit Pose3d(
const Eigen::Matrix4d& matrix)
65 : m_translation{
Eigen::Vector3d{
66 {matrix(0, 3)}, {matrix(1, 3)}, {matrix(2, 3)}}},
68 Eigen::Matrix3d{{matrix(0, 0), matrix(0, 1), matrix(0, 2)},
69 {matrix(1, 0), matrix(1, 1), matrix(1, 2)},
70 {matrix(2, 0), matrix(2, 1), matrix(2, 2)}}} {
71 if (matrix(3, 0) != 0.0 || matrix(3, 1) != 0.0 || matrix(3, 2) != 0.0 ||
72 matrix(3, 3) != 1.0) {
73 throw std::domain_error(
"Affine transformation matrix is invalid");
85 : m_translation{pose.
X(), pose.
Y(), 0_m},
86 m_rotation{0_rad, 0_rad, pose.
Rotation().Radians()} {}
127 constexpr wpi::units::meter_t
X()
const {
return m_translation.X(); }
134 constexpr wpi::units::meter_t
Y()
const {
return m_translation.Y(); }
141 constexpr wpi::units::meter_t
Z()
const {
return m_translation.Z(); }
158 return Pose3d{m_translation * scalar, m_rotation * scalar};
169 return *
this * (1.0 / scalar);
181 return {m_translation.RotateBy(other), m_rotation.RotateBy(other)};
220 return {m_translation.RotateAround(point, rot), m_rotation.RotateBy(rot)};
227 auto vec = m_translation.ToVector();
228 auto mat = m_rotation.ToMatrix();
229 return Eigen::Matrix4d{{mat(0, 0), mat(0, 1), mat(0, 2), vec(0)},
230 {mat(1, 0), mat(1, 1), mat(1, 2), vec(1)},
231 {mat(2, 0), mat(2, 1), mat(2, 2), vec(2)},
232 {0.0, 0.0, 0.0, 1.0}};
239 return Pose2d{m_translation.X(), m_translation.Y(), m_rotation.Z()};
252 return *std::min_element(
253 poses.begin(), poses.end(), [
this](
const Pose3d& a,
const Pose3d& b) {
254 auto aDistance = this->Translation().Distance(a.Translation());
255 auto bDistance = this->Translation().Distance(b.Translation());
258 if (aDistance == bDistance) {
259 return gcem::abs(this->Rotation()
260 .RelativeTo(a.Rotation())
263 gcem::abs(this->Rotation()
264 .RelativeTo(b.Rotation())
268 return aDistance < bDistance;
282 return *std::min_element(
283 poses.begin(), poses.end(), [
this](
const Pose3d& a,
const Pose3d& b) {
284 auto aDistance = this->Translation().Distance(a.Translation());
285 auto bDistance = this->Translation().Distance(b.Translation());
288 if (aDistance == bDistance) {
289 return gcem::abs(this->Rotation()
290 .RelativeTo(a.Rotation())
293 gcem::abs(this->Rotation()
294 .RelativeTo(b.Rotation())
298 return aDistance < bDistance;
303 Translation3d m_translation;
304 Rotation3d m_rotation;
321 return Transform3d{pose.Translation(), pose.Rotation()};
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.hpp:28
constexpr Pose3d operator*(double scalar) const
Multiplies the current pose by a scalar.
Definition Pose3d.hpp:157
constexpr Pose3d TransformBy(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Definition Pose3d.hpp:324
constexpr Pose3d(Translation3d translation, Rotation3d rotation)
Constructs a pose with the specified translation and rotation.
Definition Pose3d.hpp:41
constexpr Pose3d(const Pose2d &pose)
Constructs a 3D pose from a 2D pose in the X-Y plane.
Definition Pose3d.hpp:84
constexpr Pose3d RotateBy(const Rotation3d &other) const
Rotates the pose around the origin and returns the new pose.
Definition Pose3d.hpp:180
constexpr Pose3d Nearest(std::initializer_list< Pose3d > poses) const
Returns the nearest Pose3d from a collection of poses.
Definition Pose3d.hpp:281
constexpr Pose3d Nearest(std::span< const Pose3d > poses) const
Returns the nearest Pose3d from a collection of poses.
Definition Pose3d.hpp:251
constexpr wpi::units::meter_t Z() const
Returns the Z component of the pose's translation.
Definition Pose3d.hpp:141
constexpr wpi::units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition Pose3d.hpp:134
constexpr const Translation3d & Translation() const
Returns the underlying translation.
Definition Pose3d.hpp:120
constexpr Eigen::Matrix4d ToMatrix() const
Returns an affine transformation matrix representation of this pose.
Definition Pose3d.hpp:226
constexpr const Rotation3d & Rotation() const
Returns the underlying rotation.
Definition Pose3d.hpp:148
constexpr Pose3d operator+(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Definition Pose3d.hpp:98
constexpr Pose2d ToPose2d() const
Returns a Pose2d representing this Pose3d projected into the X-Y plane.
Definition Pose3d.hpp:238
constexpr bool operator==(const Pose3d &) const =default
Checks equality between this Pose3d and another object.
constexpr wpi::units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose3d.hpp:127
constexpr Pose3d operator/(double scalar) const
Divides the current pose by a scalar.
Definition Pose3d.hpp:168
constexpr Pose3d()=default
Constructs a pose at the origin facing toward the positive X axis.
constexpr Pose3d RelativeTo(const Pose3d &other) const
Returns the current pose relative to the given pose.
Definition Pose3d.hpp:332
constexpr Transform3d operator-(const Pose3d &other) const
Returns the Transform3d that maps the one pose to another.
Definition Pose3d.hpp:319
constexpr Pose3d RotateAround(const Translation3d &point, const Rotation3d &rot) const
Rotates the current pose around a point in 3D space.
Definition Pose3d.hpp:218
constexpr Pose3d(const Eigen::Matrix4d &matrix)
Constructs a pose with the specified affine transformation matrix.
Definition Pose3d.hpp:64
constexpr Pose3d(wpi::units::meter_t x, wpi::units::meter_t y, wpi::units::meter_t z, Rotation3d rotation)
Constructs a pose with x, y, and z translations instead of a separate Translation3d.
Definition Pose3d.hpp:54
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:69
constexpr Rotation3d RotateBy(const Rotation3d &other) const
Adds the new rotation to the current rotation.
Definition Rotation3d.hpp:333
Represents a translation in 3D space.
Definition Translation3d.hpp:31
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)