math_utils.hpp 5.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206
  1. /*
  2. * COPYRIGHT AND PERMISSION NOTICE
  3. * Penn Software MSCKF_VIO
  4. * Copyright (C) 2017 The Trustees of the University of Pennsylvania
  5. * All rights reserved.
  6. */
  7. // The original file belongs to MSCKF_VIO (https://github.com/KumarRobotics/msckf_vio/)
  8. // Some changes have been made to use it in livox_slam_ware
  9. #ifndef MATH_UTILS_HPP
  10. #define MATH_UTILS_HPP
  11. #include <cmath>
  12. #include <Eigen/Dense>
  13. namespace livox_slam_ware {
  14. /*
  15. * @brief Create a skew-symmetric matrix from a 3-element vector.
  16. * @note Performs the operation:
  17. * w -> [ 0 -w3 w2]
  18. * [ w3 0 -w1]
  19. * [-w2 w1 0]
  20. */
  21. inline Eigen::Matrix3d skewSymmetric(const Eigen::Vector3d& w) {
  22. Eigen::Matrix3d w_hat;
  23. w_hat(0, 0) = 0;
  24. w_hat(0, 1) = -w(2);
  25. w_hat(0, 2) = w(1);
  26. w_hat(1, 0) = w(2);
  27. w_hat(1, 1) = 0;
  28. w_hat(1, 2) = -w(0);
  29. w_hat(2, 0) = -w(1);
  30. w_hat(2, 1) = w(0);
  31. w_hat(2, 2) = 0;
  32. return w_hat;
  33. }
  34. /*
  35. * @brief Normalize the given quaternion to unit quaternion.
  36. */
  37. inline void quaternionNormalize(Eigen::Vector4d& q) {
  38. double norm = q.norm();
  39. q = q / norm;
  40. return;
  41. }
  42. /*
  43. * @brief Perform q1 * q2.
  44. *
  45. * Format of q1 and q2 is as [x,y,z,w]
  46. */
  47. inline Eigen::Vector4d quaternionMultiplication(
  48. const Eigen::Vector4d& q1,
  49. const Eigen::Vector4d& q2) {
  50. Eigen::Matrix4d L;
  51. // QXC: Hamilton
  52. L(0, 0) = q1(3); L(0, 1) = -q1(2); L(0, 2) = q1(1); L(0, 3) = q1(0);
  53. L(1, 0) = q1(2); L(1, 1) = q1(3); L(1, 2) = -q1(0); L(1, 3) = q1(1);
  54. L(2, 0) = -q1(1); L(2, 1) = q1(0); L(2, 2) = q1(3); L(2, 3) = q1(2);
  55. L(3, 0) = -q1(0); L(3, 1) = -q1(1); L(3, 2) = -q1(2); L(3, 3) = q1(3);
  56. Eigen::Vector4d q = L * q2;
  57. quaternionNormalize(q);
  58. return q;
  59. }
  60. /*
  61. * @brief Convert the vector part of a quaternion to a
  62. * full quaternion.
  63. * @note This function is useful to convert delta quaternion
  64. * which is usually a 3x1 vector to a full quaternion.
  65. * For more details, check Section 3.2 "Kalman Filter Update" in
  66. * "Indirect Kalman Filter for 3D Attitude Estimation:
  67. * A Tutorial for quaternion Algebra".
  68. */
  69. inline Eigen::Vector4d smallAngleQuaternion(
  70. const Eigen::Vector3d& dtheta) {
  71. Eigen::Vector3d dq = dtheta / 2.0;
  72. Eigen::Vector4d q;
  73. double dq_square_norm = dq.squaredNorm();
  74. if (dq_square_norm <= 1) {
  75. q.head<3>() = dq;
  76. q(3) = std::sqrt(1-dq_square_norm);
  77. } else {
  78. q.head<3>() = dq;
  79. q(3) = 1;
  80. q = q / std::sqrt(1+dq_square_norm);
  81. }
  82. return q;
  83. }
  84. /*
  85. * @brief Convert the vector part of a quaternion to a
  86. * full quaternion.
  87. * @note This function is useful to convert delta quaternion
  88. * which is usually a 3x1 vector to a full quaternion.
  89. * For more details, check Section 3.2 "Kalman Filter Update" in
  90. * "Indirect Kalman Filter for 3D Attitude Estimation:
  91. * A Tutorial for quaternion Algebra".
  92. */
  93. inline Eigen::Quaterniond getSmallAngleQuaternion(
  94. const Eigen::Vector3d& dtheta) {
  95. Eigen::Vector3d dq = dtheta / 2.0;
  96. Eigen::Quaterniond q;
  97. double dq_square_norm = dq.squaredNorm();
  98. if (dq_square_norm <= 1) {
  99. q.x() = dq(0);
  100. q.y() = dq(1);
  101. q.z() = dq(2);
  102. q.w() = std::sqrt(1-dq_square_norm);
  103. } else {
  104. q.x() = dq(0);
  105. q.y() = dq(1);
  106. q.z() = dq(2);
  107. q.w() = 1;
  108. q.normalize();
  109. }
  110. return q;
  111. }
  112. /*
  113. * @brief Convert a quaternion to the corresponding rotation matrix
  114. * @note Pay attention to the convention used. The function follows the
  115. * conversion in "Indirect Kalman Filter for 3D Attitude Estimation:
  116. * A Tutorial for Quaternion Algebra", Equation (78).
  117. *
  118. * The input quaternion should be in the form
  119. * [q1, q2, q3, q4(scalar)]^T
  120. */
  121. inline Eigen::Matrix3d quaternionToRotation(
  122. const Eigen::Vector4d& q) {
  123. // QXC: Hamilton
  124. const double& qw = q(3);
  125. const double& qx = q(0);
  126. const double& qy = q(1);
  127. const double& qz = q(2);
  128. Eigen::Matrix3d R;
  129. R(0, 0) = 1-2*(qy*qy+qz*qz); R(0, 1) = 2*(qx*qy-qw*qz); R(0, 2) = 2*(qx*qz+qw*qy);
  130. R(1, 0) = 2*(qx*qy+qw*qz); R(1, 1) = 1-2*(qx*qx+qz*qz); R(1, 2) = 2*(qy*qz-qw*qx);
  131. R(2, 0) = 2*(qx*qz-qw*qy); R(2, 1) = 2*(qy*qz+qw*qx); R(2, 2) = 1-2*(qx*qx+qy*qy);
  132. return R;
  133. }
  134. /*
  135. * @brief Convert a rotation matrix to a quaternion.
  136. * @note Pay attention to the convention used. The function follows the
  137. * conversion in "Indirect Kalman Filter for 3D Attitude Estimation:
  138. * A Tutorial for Quaternion Algebra", Equation (78).
  139. *
  140. * The input quaternion should be in the form
  141. * [q1, q2, q3, q4(scalar)]^T
  142. */
  143. inline Eigen::Vector4d rotationToQuaternion(
  144. const Eigen::Matrix3d& R) {
  145. Eigen::Vector4d score;
  146. score(0) = R(0, 0);
  147. score(1) = R(1, 1);
  148. score(2) = R(2, 2);
  149. score(3) = R.trace();
  150. int max_row = 0, max_col = 0;
  151. score.maxCoeff(&max_row, &max_col);
  152. Eigen::Vector4d q = Eigen::Vector4d::Zero();
  153. // QXC: Hamilton
  154. if (max_row == 0) {
  155. q(0) = std::sqrt(1+2*R(0, 0)-R.trace()) / 2.0;
  156. q(1) = (R(0, 1)+R(1, 0)) / (4*q(0));
  157. q(2) = (R(0, 2)+R(2, 0)) / (4*q(0));
  158. q(3) = (R(2, 1)-R(1, 2)) / (4*q(0));
  159. } else if (max_row == 1) {
  160. q(1) = std::sqrt(1+2*R(1, 1)-R.trace()) / 2.0;
  161. q(0) = (R(0, 1)+R(1, 0)) / (4*q(1));
  162. q(2) = (R(1, 2)+R(2, 1)) / (4*q(1));
  163. q(3) = (R(0, 2)-R(2, 0)) / (4*q(1));
  164. } else if (max_row == 2) {
  165. q(2) = std::sqrt(1+2*R(2, 2)-R.trace()) / 2.0;
  166. q(0) = (R(0, 2)+R(2, 0)) / (4*q(2));
  167. q(1) = (R(1, 2)+R(2, 1)) / (4*q(2));
  168. q(3) = (R(1, 0)-R(0, 1)) / (4*q(2));
  169. } else {
  170. q(3) = std::sqrt(1+R.trace()) / 2.0;
  171. q(0) = (R(2, 1)-R(1, 2)) / (4*q(3));
  172. q(1) = (R(0, 2)-R(2, 0)) / (4*q(3));
  173. q(2) = (R(1, 0)-R(0, 1)) / (4*q(3));
  174. }
  175. if (q(3) < 0) q = -q;
  176. quaternionNormalize(q);
  177. return q;
  178. }
  179. } // end namespace livox_slam_ware
  180. #endif // MATH_UTILS_HPP