21#include "units/angle.h"
22#include "units/math.h"
100 constexpr Rotation3d(units::radian_t roll, units::radian_t pitch,
101 units::radian_t yaw) {
103 double cr = units::math::cos(roll * 0.5);
104 double sr = units::math::sin(roll * 0.5);
106 double cp = units::math::cos(pitch * 0.5);
107 double sp = units::math::sin(pitch * 0.5);
109 double cy = units::math::cos(yaw * 0.5);
110 double sy = units::math::sin(yaw * 0.5);
112 m_q =
Quaternion{cr * cp * cy + sr * sp * sy, sr * cp * cy - cr * sp * sy,
113 cr * sp * cy + sr * cp * sy, cr * cp * sy - sr * sp * cy};
123 constexpr Rotation3d(
const Eigen::Vector3d& axis, units::radian_t angle) {
130 Eigen::Vector3d v{{axis(0) / norm * units::math::sin(angle / 2.0),
131 axis(1) / norm * units::math::sin(angle / 2.0),
132 axis(2) / norm * units::math::sin(angle / 2.0)}};
133 m_q =
Quaternion{units::math::cos(angle / 2.0), v(0), v(1), v(2)};
152 constexpr explicit Rotation3d(
const Eigen::Matrix3d& rotationMatrix) {
153 auto impl = []<
typename Matrix3d>(
const Matrix3d& R) ->
Quaternion {
156 if ((R * R.transpose() - Matrix3d::Identity()).norm() > 1e-9) {
157 throw std::domain_error(
"Rotation matrix isn't orthogonal");
164 throw std::domain_error(
165 "Rotation matrix is orthogonal but not special orthogonal");
170 double trace = R(0, 0) + R(1, 1) + R(2, 2);
179 x = (R(2, 1) - R(1, 2)) * s;
180 y = (R(0, 2) - R(2, 0)) * s;
181 z = (R(1, 0) - R(0, 1)) * s;
183 if (R(0, 0) > R(1, 1) && R(0, 0) > R(2, 2)) {
184 double s = 2.0 *
gcem::sqrt(1.0 + R(0, 0) - R(1, 1) - R(2, 2));
185 w = (R(2, 1) - R(1, 2)) / s;
187 y = (R(0, 1) + R(1, 0)) / s;
188 z = (R(0, 2) + R(2, 0)) / s;
189 }
else if (R(1, 1) > R(2, 2)) {
190 double s = 2.0 *
gcem::sqrt(1.0 + R(1, 1) - R(0, 0) - R(2, 2));
191 w = (R(0, 2) - R(2, 0)) / s;
192 x = (R(0, 1) + R(1, 0)) / s;
194 z = (R(1, 2) + R(2, 1)) / s;
196 double s = 2.0 *
gcem::sqrt(1.0 + R(2, 2) - R(0, 0) - R(1, 1));
197 w = (R(1, 0) - R(0, 1)) / s;
198 x = (R(0, 2) + R(2, 0)) / s;
199 y = (R(1, 2) + R(2, 1)) / s;
207 if (std::is_constant_evaluated()) {
210 m_q = impl(rotationMatrix);
225 const Eigen::Vector3d&
final) {
228 double dotNorm = dot / normProduct;
230 if (dotNorm > 1.0 - 1E-9) {
234 }
else if (dotNorm < -1.0 + 1E-9) {
244 Eigen::Vector3d other;
248 other = Eigen::Vector3d{{1, 0, 0}};
251 other = Eigen::Vector3d{{0, 0, 1}};
256 other = Eigen::Vector3d{{0, 1, 0}};
259 other = Eigen::Vector3d{{0, 0, 1}};
265 double axisNorm = axis.norm();
266 m_q =
Quaternion{0.0, axis(0) / axisNorm, axis(1) / axisNorm,
285 :
Rotation3d{0_rad, 0_rad, rotation.Radians()} {}
304 return RotateBy(other);
325 return *
this + -other;
344 if (m_q.W() >= 0.0) {
345 return Rotation3d{Eigen::Vector3d{{m_q.X(), m_q.Y(), m_q.Z()}},
346 2.0 * units::radian_t{scalar *
gcem::acos(m_q.W())}};
348 return Rotation3d{Eigen::Vector3d{{-m_q.X(), -m_q.Y(), -m_q.Z()}},
349 2.0 * units::radian_t{scalar *
gcem::acos(-m_q.W())}};
361 return *
this * (1.0 / scalar);
369 m_q.Norm() * other.m_q.Norm()) < 1e-9;
417 constexpr units::radian_t
X()
const {
424 double cxcy = 1.0 - 2.0 * (x * x + y * y);
425 double sxcy = 2.0 * (w * x + y * z);
426 double cy_sq = cxcy * cxcy + sxcy * sxcy;
437 constexpr units::radian_t
Y()
const {
444 double ratio = 2.0 * (w * y - z * x);
446 return units::radian_t{
gcem::copysign(std::numbers::pi / 2.0, ratio)};
455 constexpr units::radian_t
Z()
const {
462 double cycz = 1.0 - 2.0 * (y * y + z * z);
463 double cysz = 2.0 * (w * z + x * y);
464 double cy_sq = cycz * cycz + cysz * cysz;
468 return units::radian_t{
gcem::atan2(2.0 * w * z, w * w - z * z)};
475 constexpr Eigen::Vector3d
Axis()
const {
476 double norm =
gcem::hypot(m_q.X(), m_q.Y(), m_q.Z());
478 return Eigen::Vector3d{{0.0, 0.0, 0.0}};
480 return Eigen::Vector3d{{m_q.X() / norm, m_q.Y() / norm, m_q.Z() / norm}};
487 constexpr units::radian_t
Angle()
const {
488 double norm =
gcem::hypot(m_q.X(), m_q.Y(), m_q.Z());
489 return units::radian_t{2.0 *
gcem::atan2(norm, m_q.W())};
502 return Eigen::Matrix3d{{1.0 - 2.0 * (y * y + z * z), 2.0 * (x * y - w * z),
503 2.0 * (x * z + w * y)},
504 {2.0 * (x * y + w * z), 1.0 - 2.0 * (x * x + z * z),
505 2.0 * (y * z - w * x)},
506 {2.0 * (x * z - w * y), 2.0 * (y * z + w * x),
507 1.0 - 2.0 * (x * x + y * y)}};
515 constexpr Eigen::Vector3d
ToVector()
const {
return m_q.ToRotationVector(); }
538 return (endValue - startValue) * t + startValue;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
namespace for Niels Lohmann
Definition json.h:99
Represents a quaternion.
Definition Quaternion.h:19
constexpr Quaternion Normalize() const
Normalizes the quaternion.
Definition Quaternion.h:138
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.h:72
constexpr const Quaternion & GetQuaternion() const
Returns the quaternion representation of the Rotation3d.
Definition Rotation3d.h:412
constexpr Rotation3d(const Quaternion &q)
Constructs a Rotation3d from a quaternion.
Definition Rotation3d.h:84
constexpr Rotation3d operator+(const Rotation3d &other) const
Adds two rotations together.
Definition Rotation3d.h:303
constexpr Eigen::Matrix3d ToMatrix() const
Returns rotation matrix representation of this rotation.
Definition Rotation3d.h:495
constexpr units::radian_t Z() const
Returns the counterclockwise rotation angle around the Z axis (yaw).
Definition Rotation3d.h:455
constexpr Rotation3d()=default
Constructs a Rotation3d representing no rotation.
constexpr Rotation3d(const Eigen::Vector3d &initial, const Eigen::Vector3d &final)
Constructs a Rotation3d that rotates the initial vector onto the final vector.
Definition Rotation3d.h:224
constexpr Rotation3d operator/(double scalar) const
Divides the current rotation by a scalar.
Definition Rotation3d.h:360
constexpr Rotation2d ToRotation2d() const
Returns a Rotation2d representing this Rotation3d projected into the X-Y plane.
Definition Rotation3d.h:521
constexpr Rotation3d(const Eigen::Matrix3d &rotationMatrix)
Constructs a Rotation3d from a rotation matrix.
Definition Rotation3d.h:152
constexpr Rotation3d operator*(double scalar) const
Multiplies the current rotation by a scalar.
Definition Rotation3d.h:342
constexpr Rotation3d operator-(const Rotation3d &other) const
Subtracts the new rotation from the current rotation and returns the new rotation.
Definition Rotation3d.h:324
constexpr Eigen::Vector3d Axis() const
Returns the axis in the axis-angle representation of this rotation.
Definition Rotation3d.h:475
constexpr Rotation3d operator-() const
Takes the inverse of the current rotation.
Definition Rotation3d.h:333
constexpr units::radian_t Angle() const
Returns the angle in the axis-angle representation of this rotation.
Definition Rotation3d.h:487
constexpr units::radian_t X() const
Returns the counterclockwise rotation angle around the X axis (roll).
Definition Rotation3d.h:417
constexpr Eigen::Vector3d ToVector() const
Returns rotation vector representation of this rotation.
Definition Rotation3d.h:515
constexpr Rotation3d RotateBy(const Rotation3d &other) const
Adds the new rotation to the current rotation.
Definition Rotation3d.h:383
constexpr Rotation3d(const Eigen::Vector3d &rvec)
Constructs a Rotation3d with the given rotation vector representation.
Definition Rotation3d.h:143
constexpr Rotation3d(const Eigen::Vector3d &axis, units::radian_t angle)
Constructs a Rotation3d with the given axis-angle representation.
Definition Rotation3d.h:123
constexpr units::radian_t Y() const
Returns the counterclockwise rotation angle around the Y axis (pitch).
Definition Rotation3d.h:437
constexpr bool operator==(const Rotation3d &other) const
Checks equality between this Rotation3d and another object.
Definition Rotation3d.h:367
constexpr Rotation3d RelativeTo(const Rotation3d &other) const
Returns the current rotation relative to the given rotation.
Definition Rotation3d.h:399
constexpr Rotation3d(units::radian_t roll, units::radian_t pitch, units::radian_t yaw)
Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
Definition Rotation3d.h:100
constexpr Rotation3d(const Rotation2d &rotation)
Constructs a 3D rotation from a 2D rotation in the X-Y plane.
Definition Rotation3d.h:284
Compile-time wrapper for Eigen::Matrix.
Definition ct_matrix.h:26
constexpr Scalar dot(const ct_matrix< Scalar, RhsRows, RhsCols > &rhs) const
Constexpr version of Eigen's vector dot member function.
Definition ct_matrix.h:262
constexpr Scalar determinant() const
Constexpr version of Eigen's 2x2 matrix determinant member function.
Definition ct_matrix.h:316
constexpr Scalar norm() const
Constexpr version of Eigen's norm member function.
Definition ct_matrix.h:281
constexpr ct_matrix< Scalar, 3, 1 > cross(const ct_matrix< Scalar, 3, 1 > &rhs)
Constexpr version of Eigen's 3D vector cross member function.
Definition ct_matrix.h:303
WPILIB_DLLEXPORT void to_json(wpi::json &json, const Rotation3d &rotation)
WPILIB_DLLEXPORT void from_json(const wpi::json &json, Rotation3d &rotation)
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr return_t< T > asin(const T x) noexcept
Compile-time arcsine function.
Definition asin.hpp:82
constexpr T1 copysign(const T1 x, const T2 y) noexcept
Compile-time copy sign function.
Definition copysign.hpp:41
constexpr common_return_t< T1, T2 > hypot(const T1 x, const T2 y) noexcept
Compile-time Pythagorean addition function.
Definition hypot.hpp:147
constexpr return_t< T > sqrt(const T x) noexcept
Compile-time square-root function.
Definition sqrt.hpp:109
constexpr return_t< T > acos(const T x) noexcept
Compile-time arccosine function.
Definition acos.hpp:84
constexpr common_return_t< T1, T2 > atan2(const T1 y, const T2 x) noexcept
Compile-time two-argument arctangent function.
Definition atan2.hpp:88
constexpr T Lerp(const T &startValue, const T &endValue, double t)
Linearly interpolates between two values.
Definition MathExtras.h:772