16#include "wpi/units/angle.hpp"
17#include "wpi/units/math.hpp"
97 constexpr Rotation3d(wpi::units::radian_t roll, wpi::units::radian_t pitch,
98 wpi::units::radian_t yaw) {
100 double cr = wpi::units::math::cos(roll * 0.5);
101 double sr = wpi::units::math::sin(roll * 0.5);
103 double cp = wpi::units::math::cos(pitch * 0.5);
104 double sp = wpi::units::math::sin(pitch * 0.5);
106 double cy = wpi::units::math::cos(yaw * 0.5);
107 double sy = wpi::units::math::sin(yaw * 0.5);
109 m_q =
Quaternion{cr * cp * cy + sr * sp * sy, sr * cp * cy - cr * sp * sy,
110 cr * sp * cy + sr * cp * sy, cr * cp * sy - sr * sp * cy};
121 wpi::units::radian_t angle) {
128 Eigen::Vector3d v{{axis(0) / norm * wpi::units::math::sin(angle / 2.0),
129 axis(1) / norm * wpi::units::math::sin(angle / 2.0),
130 axis(2) / norm * wpi::units::math::sin(angle / 2.0)}};
131 m_q =
Quaternion{wpi::units::math::cos(angle / 2.0), v(0), v(1), v(2)};
150 constexpr explicit Rotation3d(
const Eigen::Matrix3d& rotationMatrix) {
151 auto impl = []<
typename Matrix3d>(
const Matrix3d& R) ->
Quaternion {
154 if ((R * R.transpose() - Matrix3d::Identity()).norm() > 1e-9) {
155 throw std::domain_error(
"Rotation matrix isn't orthogonal");
162 throw std::domain_error(
163 "Rotation matrix is orthogonal but not special orthogonal");
168 double trace = R(0, 0) + R(1, 1) + R(2, 2);
177 x = (R(2, 1) - R(1, 2)) * s;
178 y = (R(0, 2) - R(2, 0)) * s;
179 z = (R(1, 0) - R(0, 1)) * s;
181 if (R(0, 0) > R(1, 1) && R(0, 0) > R(2, 2)) {
182 double s = 2.0 *
gcem::sqrt(1.0 + R(0, 0) - R(1, 1) - R(2, 2));
183 w = (R(2, 1) - R(1, 2)) / s;
185 y = (R(0, 1) + R(1, 0)) / s;
186 z = (R(0, 2) + R(2, 0)) / s;
187 }
else if (R(1, 1) > R(2, 2)) {
188 double s = 2.0 *
gcem::sqrt(1.0 + R(1, 1) - R(0, 0) - R(2, 2));
189 w = (R(0, 2) - R(2, 0)) / s;
190 x = (R(0, 1) + R(1, 0)) / s;
192 z = (R(1, 2) + R(2, 1)) / s;
194 double s = 2.0 *
gcem::sqrt(1.0 + R(2, 2) - R(0, 0) - R(1, 1));
195 w = (R(1, 0) - R(0, 1)) / s;
196 x = (R(0, 2) + R(2, 0)) / s;
197 y = (R(1, 2) + R(2, 1)) / s;
205 if (std::is_constant_evaluated()) {
208 m_q =
impl(rotationMatrix);
223 const Eigen::Vector3d&
final) {
226 double dotNorm = dot / normProduct;
228 if (dotNorm > 1.0 - 1E-9) {
232 }
else if (dotNorm < -1.0 + 1E-9) {
242 Eigen::Vector3d other;
246 other = Eigen::Vector3d{{1, 0, 0}};
249 other = Eigen::Vector3d{{0, 0, 1}};
254 other = Eigen::Vector3d{{0, 1, 0}};
257 other = Eigen::Vector3d{{0, 0, 1}};
263 double axisNorm = axis.norm();
264 m_q =
Quaternion{0.0, axis(0) / axisNorm, axis(1) / axisNorm,
283 :
Rotation3d{0_rad, 0_rad, rotation.Radians()} {}
300 return Rotation3d{}.Interpolate(*
this, scalar);
311 return *
this * (1.0 / scalar);
319 m_q.Norm() * other.m_q.
Norm()) < 1e-9;
373 const auto& q0 = m_q;
374 const auto& q1 = endValue.m_q;
375 auto delta = q1 * q0.
Inverse();
376 if (delta.W() < 0.0) {
377 delta =
Quaternion{-delta.W(), -delta.X(), -delta.Y(), -delta.Z()};
390 constexpr wpi::units::radian_t
X()
const {
397 double cxcy = 1.0 - 2.0 * (x * x + y * y);
398 double sxcy = 2.0 * (w * x + y * z);
399 double cy_sq = cxcy * cxcy + sxcy * sxcy;
401 return wpi::units::radian_t{
gcem::atan2(sxcy, cxcy)};
410 constexpr wpi::units::radian_t
Y()
const {
417 double ratio = 2.0 * (w * y - z * x);
419 return wpi::units::radian_t{
422 return wpi::units::radian_t{
gcem::asin(ratio)};
429 constexpr wpi::units::radian_t
Z()
const {
436 double cycz = 1.0 - 2.0 * (y * y + z * z);
437 double cysz = 2.0 * (w * z + x * y);
438 double cy_sq = cycz * cycz + cysz * cysz;
440 return wpi::units::radian_t{
gcem::atan2(cysz, cycz)};
442 return wpi::units::radian_t{
gcem::atan2(2.0 * w * z, w * w - z * z)};
449 constexpr Eigen::Vector3d
Axis()
const {
450 double norm =
gcem::hypot(m_q.X(), m_q.Y(), m_q.Z());
452 return Eigen::Vector3d{{0.0, 0.0, 0.0}};
454 return Eigen::Vector3d{{m_q.X() / norm, m_q.Y() / norm, m_q.Z() / norm}};
461 constexpr wpi::units::radian_t
Angle()
const {
462 double norm =
gcem::hypot(m_q.X(), m_q.Y(), m_q.Z());
463 return wpi::units::radian_t{2.0 *
gcem::atan2(norm, m_q.W())};
476 return Eigen::Matrix3d{{1.0 - 2.0 * (y * y + z * z), 2.0 * (x * y - w * z),
477 2.0 * (x * z + w * y)},
478 {2.0 * (x * y + w * z), 1.0 - 2.0 * (x * x + z * z),
479 2.0 * (y * z - w * x)},
480 {2.0 * (x * z - w * y), 2.0 * (y * z + w * x),
481 1.0 - 2.0 * (x * x + y * y)}};
489 constexpr Eigen::Vector3d
ToVector()
const {
return m_q.ToRotationVector(); }
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a quaternion.
Definition Quaternion.hpp:20
constexpr Quaternion Inverse() const
Returns the inverse of the quaternion.
Definition Quaternion.hpp:131
constexpr Quaternion Normalize() const
Normalizes the quaternion.
Definition Quaternion.hpp:139
constexpr double Norm() const
Calculates the L2 norm of the quaternion.
Definition Quaternion.hpp:151
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:69
constexpr wpi::units::radian_t X() const
Returns the counterclockwise rotation angle around the X axis (roll).
Definition Rotation3d.hpp:390
constexpr Rotation2d ToRotation2d() const
Returns a Rotation2d representing this Rotation3d projected into the X-Y plane.
Definition Rotation3d.hpp:495
constexpr Eigen::Vector3d ToVector() const
Returns rotation vector representation of this rotation.
Definition Rotation3d.hpp:489
constexpr Rotation3d operator/(double scalar) const
Divides the current rotation by a scalar.
Definition Rotation3d.hpp:310
constexpr Rotation3d(const Eigen::Matrix3d &rotationMatrix)
Constructs a Rotation3d from a rotation matrix.
Definition Rotation3d.hpp:150
constexpr const Quaternion & GetQuaternion() const
Returns the quaternion representation of the Rotation3d.
Definition Rotation3d.hpp:385
constexpr Rotation3d Interpolate(Rotation3d endValue, double t) const
Interpolates between this rotation and another.
Definition Rotation3d.hpp:367
constexpr Rotation3d()=default
Constructs a Rotation3d representing no rotation.
constexpr Rotation3d(const Quaternion &q)
Constructs a Rotation3d from a quaternion.
Definition Rotation3d.hpp:81
constexpr Eigen::Vector3d Axis() const
Returns the axis in the axis-angle representation of this rotation.
Definition Rotation3d.hpp:449
constexpr Rotation3d(wpi::units::radian_t roll, wpi::units::radian_t pitch, wpi::units::radian_t yaw)
Constructs a Rotation3d from extrinsic roll, pitch, and yaw.
Definition Rotation3d.hpp:97
constexpr Rotation3d operator*(double scalar) const
Multiplies the current rotation by a scalar.
Definition Rotation3d.hpp:299
constexpr wpi::units::radian_t Z() const
Returns the counterclockwise rotation angle around the Z axis (yaw).
Definition Rotation3d.hpp:429
constexpr Rotation3d Inverse() const
Takes the inverse of the current rotation.
Definition Rotation3d.hpp:290
constexpr wpi::units::radian_t Angle() const
Returns the angle in the axis-angle representation of this rotation.
Definition Rotation3d.hpp:461
constexpr Rotation3d(const Eigen::Vector3d &rvec)
Constructs a Rotation3d with the given rotation vector representation.
Definition Rotation3d.hpp:141
constexpr Eigen::Matrix3d ToMatrix() const
Returns rotation matrix representation of this rotation.
Definition Rotation3d.hpp:469
constexpr Rotation3d(const Eigen::Vector3d &initial, const Eigen::Vector3d &final)
Constructs a Rotation3d that rotates the initial vector onto the final vector.
Definition Rotation3d.hpp:222
constexpr bool operator==(const Rotation3d &other) const
Checks equality between this Rotation3d and another object.
Definition Rotation3d.hpp:317
constexpr Rotation3d RelativeTo(const Rotation3d &other) const
Returns the current rotation relative to the given rotation.
Definition Rotation3d.hpp:349
constexpr Rotation3d(const Eigen::Vector3d &axis, wpi::units::radian_t angle)
Constructs a Rotation3d with the given axis-angle representation.
Definition Rotation3d.hpp:120
constexpr wpi::units::radian_t Y() const
Returns the counterclockwise rotation angle around the Y axis (pitch).
Definition Rotation3d.hpp:410
constexpr Rotation3d(const Rotation2d &rotation)
Constructs a 3D rotation from a 2D rotation in the X-Y plane.
Definition Rotation3d.hpp:282
constexpr Rotation3d RotateBy(const Rotation3d &other) const
Adds the new rotation to the current rotation.
Definition Rotation3d.hpp:333
Compile-time wrapper for Eigen::Matrix.
Definition ct_matrix.hpp:26
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.hpp:303
constexpr Scalar dot(const ct_matrix< Scalar, RhsRows, RhsCols > &rhs) const
Constexpr version of Eigen's vector dot member function.
Definition ct_matrix.hpp:262
constexpr Scalar norm() const
Constexpr version of Eigen's norm member function.
Definition ct_matrix.hpp:281
constexpr Scalar determinant() const
Constexpr version of Eigen's 2x2 matrix determinant member function.
Definition ct_matrix.hpp:316
basic_json<> json
default specialization
Definition json_fwd.hpp:62
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 common_return_t< T1, T2 > atan2(const T1 y, const T2 x) noexcept
Compile-time two-argument arctangent function.
Definition atan2.hpp:88
Definition RobotBase.hpp:26
Definition LinearSystem.hpp:20
ct_matrix< double, 3, 3 > ct_matrix3d
Definition ct_matrix.hpp:385
WPILIB_DLLEXPORT void to_json(wpi::util::json &json, const Translation2d &state)
WPILIB_DLLEXPORT void from_json(const wpi::util::json &json, Translation2d &state)
constexpr T Lerp(const T &startValue, const T &endValue, double t)
Linearly interpolates between two values.
Definition MathExtras.hpp:780
Definition CvSource.hpp:15