8#include <initializer_list>
44 : m_translation{
std::move(translation)},
45 m_rotation{
std::move(rotation)} {}
56 constexpr Pose3d(units::meter_t x, units::meter_t y, units::meter_t z,
58 : m_translation{x, y, z}, m_rotation{
std::move(rotation)} {}
66 constexpr explicit Pose3d(
const Eigen::Matrix4d& matrix)
67 : m_translation{
Eigen::Vector3d{
68 {matrix(0, 3)}, {matrix(1, 3)}, {matrix(2, 3)}}},
70 Eigen::Matrix3d{{matrix(0, 0), matrix(0, 1), matrix(0, 2)},
71 {matrix(1, 0), matrix(1, 1), matrix(1, 2)},
72 {matrix(2, 0), matrix(2, 1), matrix(2, 2)}}} {
73 if (matrix(3, 0) != 0.0 || matrix(3, 1) != 0.0 || matrix(3, 2) != 0.0 ||
74 matrix(3, 3) != 1.0) {
75 throw std::domain_error(
"Affine transformation matrix is invalid");
87 : m_translation{pose.X(), pose.Y(), 0_m},
88 m_rotation{0_rad, 0_rad, pose.Rotation().Radians()} {}
101 return TransformBy(other);
129 constexpr units::meter_t
X()
const {
return m_translation.X(); }
136 constexpr units::meter_t
Y()
const {
return m_translation.Y(); }
143 constexpr units::meter_t
Z()
const {
return m_translation.Z(); }
160 return Pose3d{m_translation * scalar, m_rotation * scalar};
171 return *
this * (1.0 / scalar);
183 return {m_translation.RotateBy(other), m_rotation.RotateBy(other)};
222 return {m_translation.RotateAround(point, rot), m_rotation.RotateBy(rot)};
229 auto vec = m_translation.ToVector();
230 auto mat = m_rotation.ToMatrix();
231 return Eigen::Matrix4d{{mat(0, 0), mat(0, 1), mat(0, 2), vec(0)},
232 {mat(1, 0), mat(1, 1), mat(1, 2), vec(1)},
233 {mat(2, 0), mat(2, 1), mat(2, 2), vec(2)},
234 {0.0, 0.0, 0.0, 1.0}};
241 return Pose2d{m_translation.X(), m_translation.Y(), m_rotation.Z()};
254 return *std::min_element(
255 poses.begin(), poses.end(), [
this](
const Pose3d& a,
const Pose3d& b) {
256 auto aDistance = this->Translation().Distance(a.Translation());
257 auto bDistance = this->Translation().Distance(b.Translation());
260 if (aDistance == bDistance) {
262 (this->Rotation() - a.Rotation()).Angle().value()) <
263 gcem::abs((this->Rotation() - b.Rotation()).Angle().value());
265 return aDistance < bDistance;
279 return *std::min_element(
280 poses.begin(), poses.end(), [
this](
const Pose3d& a,
const Pose3d& b) {
281 auto aDistance = this->Translation().Distance(a.Translation());
282 auto bDistance = this->Translation().Distance(b.Translation());
285 if (aDistance == bDistance) {
287 (this->Rotation() - a.Rotation()).Angle().value()) <
288 gcem::abs((this->Rotation() - b.Rotation()).Angle().value());
290 return aDistance < bDistance;
295 Translation3d m_translation;
296 Rotation3d m_rotation;
313 return Transform3d{pose.Translation(), pose.Rotation()};
317 return {m_translation + (other.Translation().
RotateBy(m_rotation)),
318 other.Rotation() + m_rotation};
323 return {transform.Translation(), transform.Rotation()};
#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:27
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:30
constexpr Pose3d(const Pose2d &pose)
Constructs a 3D pose from a 2D pose in the X-Y plane.
Definition Pose3d.h:86
constexpr Pose3d(units::meter_t x, units::meter_t y, units::meter_t z, Rotation3d rotation)
Constructs a pose with x, y, and z translations instead of a separate Translation3d.
Definition Pose3d.h:56
constexpr Pose3d TransformBy(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Definition Pose3d.h:316
constexpr Pose3d RotateBy(const Rotation3d &other) const
Rotates the pose around the origin and returns the new pose.
Definition Pose3d.h:182
constexpr const Translation3d & Translation() const
Returns the underlying translation.
Definition Pose3d.h:122
constexpr Pose3d(Translation3d translation, Rotation3d rotation)
Constructs a pose with the specified translation and rotation.
Definition Pose3d.h:43
constexpr units::meter_t Z() const
Returns the Z component of the pose's translation.
Definition Pose3d.h:143
constexpr Pose3d operator/(double scalar) const
Divides the current pose by a scalar.
Definition Pose3d.h:170
constexpr Eigen::Matrix4d ToMatrix() const
Returns an affine transformation matrix representation of this pose.
Definition Pose3d.h:228
constexpr Pose3d RotateAround(const Translation3d &point, const Rotation3d &rot) const
Rotates the current pose around a point in 3D space.
Definition Pose3d.h:220
constexpr Pose2d ToPose2d() const
Returns a Pose2d representing this Pose3d projected into the X-Y plane.
Definition Pose3d.h:240
constexpr Pose3d Nearest(std::initializer_list< Pose3d > poses) const
Returns the nearest Pose3d from a collection of poses.
Definition Pose3d.h:278
constexpr const Rotation3d & Rotation() const
Returns the underlying rotation.
Definition Pose3d.h:150
constexpr units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition Pose3d.h:136
constexpr Pose3d operator*(double scalar) const
Multiplies the current pose by a scalar.
Definition Pose3d.h:159
constexpr Pose3d RelativeTo(const Pose3d &other) const
Returns the current pose relative to the given pose.
Definition Pose3d.h:321
constexpr Pose3d(const Eigen::Matrix4d &matrix)
Constructs a pose with the specified affine transformation matrix.
Definition Pose3d.h:66
constexpr bool operator==(const Pose3d &) const =default
Checks equality between this Pose3d and another object.
constexpr Transform3d operator-(const Pose3d &other) const
Returns the Transform3d that maps the one pose to another.
Definition Pose3d.h:311
constexpr Pose3d Nearest(std::span< const Pose3d > poses) const
Returns the nearest Pose3d from a collection of poses.
Definition Pose3d.h:253
constexpr Pose3d operator+(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Definition Pose3d.h:100
constexpr Pose3d()=default
Constructs a pose at the origin facing toward the positive X axis.
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose3d.h:129
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
Represents a translation in 3D space.
Definition Translation3d.h:31
Definition variable.hpp:742
Definition SystemServer.h:9
WPILIB_DLLEXPORT void to_json(wpi::json &json, const Rotation3d &rotation)
WPILIB_DLLEXPORT void from_json(const wpi::json &json, Rotation3d &rotation)
Definition PointerIntPair.h:280