Brian Silverman | dac0a4b | 2020-06-23 17:03:09 -0700 | [diff] [blame] | 1 | #ifndef AOS_CONTROLS_QUATERNION_UTILS_H_ |
| 2 | #define AOS_CONTROLS_QUATERNION_UTILS_H_ |
| 3 | |
| 4 | #include "Eigen/Dense" |
| 5 | #include "Eigen/Geometry" |
| 6 | #include "glog/logging.h" |
| 7 | |
James Kuszmaul | 6175066 | 2021-06-21 21:32:33 -0700 | [diff] [blame] | 8 | namespace frc971 { |
Brian Silverman | dac0a4b | 2020-06-23 17:03:09 -0700 | [diff] [blame] | 9 | namespace controls { |
| 10 | |
| 11 | // Function to compute the quaternion average of a bunch of quaternions. Each |
| 12 | // column in the input matrix is a quaternion (optionally scaled by it's |
| 13 | // weight). |
| 14 | template <int SM> |
| 15 | inline Eigen::Matrix<double, 4, 1> QuaternionMean( |
| 16 | Eigen::Matrix<double, 4, SM> input) { |
| 17 | // Algorithm to compute the average of a bunch of quaternions: |
| 18 | // http://www.acsu.buffalo.edu/~johnc/ave_quat07.pdf |
| 19 | |
| 20 | Eigen::Matrix<double, 4, 4> m = input * input.transpose(); |
| 21 | |
| 22 | Eigen::EigenSolver<Eigen::Matrix<double, 4, 4>> solver; |
| 23 | solver.compute(m); |
| 24 | |
| 25 | Eigen::EigenSolver<Eigen::Matrix<double, 4, 4>>::EigenvectorsType |
| 26 | eigenvectors = solver.eigenvectors(); |
| 27 | Eigen::EigenSolver<Eigen::Matrix<double, 4, 4>>::EigenvalueType eigenvalues = |
| 28 | solver.eigenvalues(); |
| 29 | |
| 30 | int max_index = 0; |
| 31 | double max_eigenvalue = 0.0; |
| 32 | for (int i = 0; i < 4; ++i) { |
| 33 | const double eigenvalue = std::abs(eigenvalues(i, 0)); |
| 34 | if (eigenvalue > max_eigenvalue) { |
| 35 | max_eigenvalue = eigenvalue; |
| 36 | max_index = i; |
| 37 | } |
| 38 | } |
| 39 | |
| 40 | // Assume that there shouldn't be any imaginary components to the eigenvector. |
| 41 | // I can't prove this is true, but everyone else seems to assume it... |
| 42 | // TODO(james): Handle this more rigorously. |
| 43 | for (int i = 0; i < 4; ++i) { |
| 44 | CHECK_LT(eigenvectors(i, max_index).imag(), 1e-4) |
| 45 | << eigenvectors(i, max_index); |
| 46 | } |
| 47 | return eigenvectors.col(max_index).real().normalized(); |
| 48 | } |
| 49 | |
| 50 | // Converts from a quaternion to a rotation vector, where the rotation vector's |
| 51 | // direction represents the axis to rotate around and its magnitude represents |
| 52 | // the number of radians to rotate. |
| 53 | Eigen::Matrix<double, 3, 1> ToRotationVectorFromQuaternion( |
| 54 | const Eigen::Matrix<double, 4, 1> &X); |
| 55 | |
| 56 | inline Eigen::Matrix<double, 3, 1> ToRotationVectorFromQuaternion( |
| 57 | const Eigen::Quaternion<double> &X) { |
| 58 | return ToRotationVectorFromQuaternion(X.coeffs()); |
| 59 | } |
| 60 | |
| 61 | // Converts from a rotation vector to a quaternion. If you supply max_angle_cap, |
| 62 | // then the rotation vector's magnitude will be clipped to be no more than |
| 63 | // max_angle_cap before being converted to a quaternion. |
| 64 | Eigen::Matrix<double, 4, 1> ToQuaternionFromRotationVector( |
| 65 | const Eigen::Matrix<double, 3, 1> &X, |
| 66 | const double max_angle_cap = std::numeric_limits<double>::infinity()); |
| 67 | |
milind-u | e53bf55 | 2021-12-11 14:42:00 -0800 | [diff] [blame^] | 68 | // Creates a rotational velocity vector to be integrated. |
| 69 | // |
| 70 | // omega is the rotational velocity vector in body coordinates. |
| 71 | // q is a matrix with the compononents of the quaternion in it. |
| 72 | // |
| 73 | // Returns dq / dt |
| 74 | inline Eigen::Vector4d QuaternionDerivative(Eigen::Vector3d omega, |
| 75 | const Eigen::Vector4d &q_matrix) { |
| 76 | // See https://www.ashwinnarayan.com/post/how-to-integrate-quaternions/ for |
| 77 | // another resource on quaternion integration and derivitives. |
| 78 | Eigen::Quaternion<double> q(q_matrix); |
| 79 | |
| 80 | Eigen::Quaternion<double> omega_q; |
| 81 | omega_q.w() = 0.0; |
| 82 | omega_q.vec() = 0.5 * omega; |
| 83 | |
| 84 | Eigen::Quaternion<double> deriv = q * omega_q; |
| 85 | return deriv.coeffs(); |
| 86 | } |
| 87 | |
| 88 | // d QuaternionDerivative / d omega |
| 89 | Eigen::Matrix<double, 4, 3> QuaternionDerivativeDerivitive( |
| 90 | const Eigen::Vector4d &q_matrix); |
| 91 | inline Eigen::Matrix<double, 4, 3> QuaternionDerivativeDerivitive( |
| 92 | const Eigen::Quaternion<double> &q) { |
| 93 | return QuaternionDerivativeDerivitive(q.coeffs()); |
| 94 | } |
| 95 | |
Brian Silverman | dac0a4b | 2020-06-23 17:03:09 -0700 | [diff] [blame] | 96 | } // namespace controls |
James Kuszmaul | 6175066 | 2021-06-21 21:32:33 -0700 | [diff] [blame] | 97 | } // namespace frc971 |
Brian Silverman | dac0a4b | 2020-06-23 17:03:09 -0700 | [diff] [blame] | 98 | |
| 99 | #endif // AOS_CONTROLS_QUATERNION_UTILS_H_ |